Niryo robot arm commander

This package is made to interact with the arm through MoveIt! package and command the robot motion.

All commands are firstly received on the actionlib server which:
  • Handles concurrent requests.

  • Checks if the command can’t be processed due to other factors (ex: learning mode).

  • Validates parameters.

  • Calls required controllers and returns appropriate status and message.

It belongs to the ROS namespace: /niryo_robot_arm_commander.

Package Documentation

ROS topics

Publishers

Topic Name

Type

Description

/niryo_robot/blockly/save_trajectory

std_msgs/Int32

Whether a recorded trajectory can be saved to blockly

/niryo_robot/collision_detected

std_msgs/Bool

Whether a collision is detected or not

/niryo_robot/jog_interface/errors

std_msgs/String

Publish jog error message when using the jog interface

/niryo_robot/jog_interface/is_enabled

std_msgs/Bool

Whether the jog interface is enabled or not

/niryo_robot/max_acceleration_scaling_factor

std_msgs/Int32

Publish the maximum acceleration percentage scaling factor

/niryo_robot/max_velocity_scaling_factor

std_msgs/Int32

Publish the maximum velocity percentage scaling factor

/niryo_robot/robot_state

niryo_robot_msgs/RobotState

Publish the robot state (TCP pose with x-axis forward and TCP speed) (deprecated)

/niryo_robot/robot_state_v2

niryo_robot_msgs/RobotState

Publish the robot state (TCP pose with z-axis forward and TCP speed)

/niryo_robot_arm_commander/is_active

std_msgs/Bool

Indicate whether a command is currently running or not

/niryo_robot_arm_commander/learning_trajectory

std_msgs/Bool

Indicates whether a robot is currently learning a trajectory or not

/niryo_robot_arm_commander/trajectory_list

niryo_robot_msgs/BasicObjectArray

List of saved trajectories name & description

/niryo_robot_follow_joint_trajectory_controller/command

trajectory_msgs/JointTrajectory

Command the arm through the FollowJointTrajectory controller via its command topic

/niryo_robot_follow_joint_trajectory_controller/follow_joint_trajectory/goal

control_msgs/FollowJointTrajectoryActionGoal

Command the arm through the FollowJointTrajectory controller via its action server

/rosout

rosgraph_msgs/Log

N/A

/tf_static

tf2_msgs/TFMessage

N/A

Subscribers

Topic Name

Type

Description

/joint_states

sensor_msgs/JointState

Position, velocity and effort of all the joints

/niryo_robot/hardware_interface/collision_detected

std_msgs/Bool

Whether a collision is detected or not

/niryo_robot/learning_mode/state

std_msgs/Bool

Whether the robot is in freemotion mode or not

/niryo_robot/robot_state_v2

niryo_robot_msgs/RobotState

Publish the robot state (TCP pose with z-axis forward and TCP speed)

/niryo_robot_arm_commander/send_jog_command_ik

niryo_robot_arm_commander/CommandJog

Send a jog command to the robot using a pose (Inverse Kinematics)

/niryo_robot_arm_commander/send_jog_joints_command

niryo_robot_arm_commander/CommandJog

Send a jog command to the robot using joints values (Forward Kinematics)

/niryo_robot_follow_joint_trajectory_controller/follow_joint_trajectory/goal

control_msgs/FollowJointTrajectoryActionGoal

Command the arm through the FollowJointTrajectory controller via its action server

/niryo_robot_follow_joint_trajectory_controller/follow_joint_trajectory/result

control_msgs/FollowJointTrajectoryActionResult

N/A

/niryo_robot_follow_joint_trajectory_controller/state

control_msgs/JointTrajectoryControllerState

N/A

/niryo_robot_hardware_interface/end_effector_interface/save_pos_button_status

end_effector_interface/EEButtonStatus

Publish Save Button’s state

/niryo_robot_hardware_interface/hardware_status

niryo_robot_msgs/HardwareStatus

Status of robot’s hardware devices (joints, tools, end effector panel, calibration, etc…)

/niryo_robot_rpi/pause_state

niryo_robot_arm_commander/PausePlanExecution

Publish the current execution state launched when button is pressed”

/tf

tf2_msgs/TFMessage

N/A

/tf_static

tf2_msgs/TFMessage

N/A

ROS Services

Service Name

Type

Description

/niryo_robot/jog_interface/enable

niryo_robot_msgs/SetBool

Enable/disable the jog interface

/niryo_robot/jog_interface/jog_shift_commander

niryo_robot_arm_commander/JogShift

Send a jog command to shift robot’s joints or TCP

/niryo_robot/kinematics/forward

niryo_robot_arm_commander/GetFK

Get TCP pose from joint values with x axis forward (deprecated)

/niryo_robot/kinematics/forward_v2

niryo_robot_arm_commander/GetFK

Get TCP pose from joint values with z axis forward

/niryo_robot/kinematics/inverse

niryo_robot_arm_commander/GetIK

Get joints configuration from TCP pose with x axis forward (deprecated)

/niryo_robot/kinematics/inverse_v2

niryo_robot_arm_commander/GetIK

Get joints configuration from TCP pose with z axis forward

/niryo_robot_arm_commander/compute_waypointed_trajectory

niryo_robot_arm_commander/ComputeTrajectory

Compute a trajectory from a list of waypoints

/niryo_robot_arm_commander/get_joints_limit

niryo_robot_arm_commander/GetJointLimits

N/A

/niryo_robot_arm_commander/get_loggers

roscpp/GetLoggers

N/A

/niryo_robot_arm_commander/get_trajectory

niryo_robot_arm_commander/GetTrajectory

Get a given saved trajectory

/niryo_robot_arm_commander/get_trajectory_list

niryo_robot_msgs/GetNameDescriptionList

Get the list of saved trajectory name & description

/niryo_robot_arm_commander/is_active

niryo_robot_msgs/GetBool

Indicate whether a command is currently running or not

/niryo_robot_arm_commander/manage_trajectory

niryo_robot_arm_commander/ManageTrajectory

Save/Edit/Delete/Execute a trajectory

/niryo_robot_arm_commander/set_acceleration_factor

niryo_robot_msgs/SetInt

Set the acceleration factor percentage (0% - 200%)

/niryo_robot_arm_commander/set_logger_level

roscpp/SetLoggerLevel

N/A

/niryo_robot_arm_commander/set_max_velocity_scaling_factor

niryo_robot_msgs/SetInt

Set the percentage of maximum speed (0% - 200%)

/niryo_robot_arm_commander/stop_command

niryo_robot_msgs/Trigger

Stop the current command

/niryo_robot_arm_commander/tf2_frames

tf2_msgs/FrameGraph

N/A

ROS Parameters

Parameter Name

Default value

Simulation value

Unit

Description

/niryo_robot_arm_commander/active_publish_rate_sec

0.1

N/A

seconds

Publish rate for the topic which checks if a goal is currently active or not

/niryo_robot_arm_commander/allow_replanning

True

N/A

bool

Whether replanning is allowed or not (MoveIt! parameter)

/niryo_robot_arm_commander/command_still_active_max_tries

3

N/A

int

Maximum number of tries to check if a command is still active before aborting the new command

/niryo_robot_arm_commander/compute_plan_max_tries

3

N/A

int

Maximum number of tries to compute a plan before aborting the command

/niryo_robot_arm_commander/display_trajectories

False

N/A

bool

Whether the trajectories should be displayed in Rviz or not

/niryo_robot_arm_commander/eef_step

0.02

N/A

meters

Step between generated waypoints for the end effector trajectory

/niryo_robot_arm_commander/error_tolerance_joint

[0.2, 0.2, 0.2, 0.2, 0.2, 0.2]

N/A

radians

Error tolerance for joints when using the jog controller

/niryo_robot_arm_commander/goal_joint_tolerance

0.0001

N/A

radians

Goal joint tolerance for the MoveIt! motion planner

/niryo_robot_arm_commander/goal_orientation_tolerance

0.001

N/A

radians

Goal orientation tolerance for the MoveIt! motion planner

/niryo_robot_arm_commander/goal_position_tolerance

0.0001

N/A

meters

Goal position tolerance for the MoveIt! motion planner

/niryo_robot_arm_commander/hardware_version

ned2

N/A

string

Hardware version of the robot

/niryo_robot_arm_commander/initialized

True

N/A

bool

Whether the arm commander is initialized or not

/niryo_robot_arm_commander/jog_enable_publish_rate

1.0

N/A

N/A

N/A

/niryo_robot_arm_commander/jog_limits/joints

0.2

N/A

radians

Joints limits applied to clamp the jog command

/niryo_robot_arm_commander/jog_limits/rotation

0.5

N/A

radians

Rotation limits applied to clamp the jog command

/niryo_robot_arm_commander/jog_limits/translation

0.05

N/A

meters

Translation limits applied to clamp the jog command

/niryo_robot_arm_commander/jog_timer_rate_sec

0.15

N/A

seconds

Publish rate for jog controller

/niryo_robot_arm_commander/joint_controller_name

/niryo_robot_follow_joint_trajectory_controller

N/A

string

Name of the joint trajectory controller

/niryo_robot_arm_commander/joint_names

[‘joint_1’, ‘joint_2’, ‘joint_3’, ‘joint_4’, ‘joint_5’, ‘joint_6’]

N/A

string

Names of the joints of the robot

/niryo_robot_arm_commander/jump_threshold

0.0

N/A

radians

Jump threshold for the MoveIt! motion planner

/niryo_robot_arm_commander/log_level

INFO

N/A

N/A

N/A

/niryo_robot_arm_commander/move_group_commander_name

arm

N/A

string

Name of the group that MoveIt is controlling

/niryo_robot_arm_commander/reference_frame

world

N/A

string

Reference frame used by MoveIt!

/niryo_robot_arm_commander/time_without_jog_TCP_limit

0.5

N/A

seconds

Time without jog command before disabling the jog controller

/niryo_robot_arm_commander/trajectory_frequency

7

N/A

Hz

Waypoint acquisition frequency while recording a trajectory

/niryo_robot_arm_commander/trajectory_minimum_timeout

3.0

N/A

N/A

N/A

ROS Action

Namespace: robot_action

Publishers

Topic Name

Type

Description

/niryo_robot_arm_commander/robot_action/feedback

niryo_robot_arm_commander/RobotMoveActionFeedback

N/A

/niryo_robot_arm_commander/robot_action/result

niryo_robot_arm_commander/RobotMoveActionResult

N/A

/niryo_robot_arm_commander/robot_action/status

actionlib_msgs/GoalStatusArray

N/A

Subscribers

Topic Name

Type

Description

/niryo_robot_arm_commander/robot_action/cancel

actionlib_msgs/GoalID

N/A

/niryo_robot_arm_commander/robot_action/goal

niryo_robot_arm_commander/RobotMoveActionGoal

Command the arm through an action server

The ArmMoveCommand message

This message is used when you want to send a move goal to the robot via the action server. You need to fill the cmd_type field with one of the listed constant depending on the type of command you need to send. Then, you can fill the data field corresponding to your cmd_type.

For example, if you command type is EXECUTE_TRAJ, you need to fill dist_smoothing and list_poses.

int32 JOINTS = 0            # uses joints 
int32 POSE = 1              # uses position and rpy 
int32 POSITION = 2          # uses position
int32 RPY = 3               # uses rpy
int32 POSE_QUAT = 4         # uses position and orientation
int32 LINEAR_POSE = 5       # uses position and rpy
int32 SHIFT_POSE = 6        # uses shift
int32 SHIFT_LINEAR_POSE = 7 # uses shift
int32 EXECUTE_TRAJ = 8      # uses dist_smoothing, list_poses
int32 DRAW_SPIRAL = 9
int32 DRAW_CIRCLE = 10
int32 EXECUTE_FULL_TRAJ = 11
int32 EXECUTE_RAW_TRAJ = 12

int32 cmd_type

int32 LEGACY = 1
int32 DH_CONVENTION = 2
int32 tcp_version

float64[] joints
geometry_msgs/Point position
niryo_robot_msgs/RPY rpy
geometry_msgs/Quaternion orientation
niryo_robot_arm_commander/ShiftPose shift

geometry_msgs/Pose[] list_poses
float32 dist_smoothing

trajectory_msgs/JointTrajectory trajectory

float64[] args