Skip to content

Introduction to the Rm_ros_interface Package

The rm_ros_interface package is intended to provide necessary message files for the RM robotic arm to run under the ROS2 framework, without any executable usage commands.
The package will be introduced in detail from the following three aspects with different purposes:

    1. Package application: Learn how to use the package.
    1. Package structure description: Understand the composition and function of files in the package.
    1. Package topic description: Know the topics of the package for easy development and use.

Code link: https://github.com/RealManRobot/ros2_rm_robot/tree/humble/rm_ros_interfaces

Structure description of the rm_ros_interface package

The current rm_ros_interface package consists of the following files.
├── CMakeLists.txt             #Build rule file
├── include                         #Dependency header file folder
│   └── rm_ros_interfaces
├── msg                          #Current message file (refer to the description below for details)
│   ├── Armcurrentstatus.msg
│   ├── Armoriginalstate.msg
│   ├── Armstate.msg
│   ├── Cartepos.msg
│   ├── Carteposcustom.msg
│   ├── Forcepositionmovejoint.msg
│   ├── Forcepositionmovepose.msg
│   ├── Force_Position_State.msg
│   ├── Getallframe.msg
│   ├── GetArmState_Command.msg
│   ├── Gripperpick.msg
│   ├── Gripperset.msg
│   ├── Handangle.msg
│   ├── Handforce.msg
│   ├── Handposture.msg
│   ├── Handseq.msg
│   ├── Handspeed.msg
│   ├── Handstatus.msg
│   ├── Jointcurrent.msg
│   ├── Jointenflag.msg
│   ├── Jointerrclear.msg
│   ├── Jointerrorcode.msg
│   ├── Jointposeeuler.msg
│   ├── Jointpos.msg
│   ├── Jointposcustom.msg
│   ├── Jointspeed.msg
│   ├── Jointteach.msg
│   ├── Jointtemperature.msg
│   ├── Jointvoltage.msg
│   ├── Liftheight.msg
│   ├── Liftspeed.msg
│   ├── Liftstate.msg
│   ├── Movec.msg
│   ├── Movej.msg
│   ├── Movejp.msg
│   ├── Movel.msg
│   ├── Ortteach.msg
│   ├── Posteach.msg
│   ├── Rmerr.msg
│   ├── Rmplusbase.msg
│   ├── Rmplusstate.msg
│   ├── Setforceposition.msg
│   ├── Setrealtimepush.msg
│   ├── Sixforce.msg
│   └── Stop.msg
├── package.xml                       #Dependency declaration file
└── src

Message description of the rm_ros_interface package

Joint error code Jointerrorcode_msg

uint16[] joint_error  
uint8 dof

msg members:

  • joint_error: each joint error.
  • dof: degree of freedom of the robotic arm.

Clear the joint error code Jointerrclear_msg

uint8 joint_num

msg members:

  • joint_num: corresponding joint number, 1−6 or 1−7 from the base to the robotic arm's gripper.

Get the names of all frames Getallframe_msg

string[10] frame_name

msg members:

  • frame_name: returned name array of all work frames.

Joint motion Movej_msg

float32[] joint  
uint8 speed  
bool block  
uint8 trajectory_connect  
uint8 dof

msg members:

  • joint: joint angle (float type), in rad.
  • speed: speed percentage, 0−100.
  • block: blocking/non-blocking mode (bool type), true: blocking mode, false: non-blocking mode.
  • trajectory_connect: 0: immediate motion planning, 1: planning together with the next trajectory. When set to 1, the trajectory will not execute immediately.
  • dof: degree of freedom of the robotic arm.

Linear motion Movel_msg

geometry_msgs/Pose pose  
uint8 speed  
uint8 trajectory_connect  
bool block

msg members:

  • pose: robotic arm pose (geometry_msgs/Pose type), including x, y, z coordinates (float type, in m) + quaternion (float type).
  • speed: speed percentage, 0−100.
  • trajectory_connect: 0: immediate motion planning, 1: planning together with the next trajectory. When set to 1, the trajectory will not execute immediately.
  • block: blocking/non-blocking mode (bool type), true: blocking mode, false: non-blocking mode.

Circular motion Movec_msg

geometry_msgs/Pose pose_mid  
geometry_msgs/Pose pose_end  
uint8 speed  
uint8 trajectory_connect  
bool block  
uint8 loop

msg members:

  • pose_mid: middle pose (geometry_msgs/Pose type), including x, y, z coordinates (float type, in m) + quaternion.
  • pose_end: target pose (geometry_msgs/Pose type), including x, y, z coordinates (float type, in m) + quaternion.
  • speed: speed percentage, 0−100.
  • trajectory_connect: 0: immediate motion planning, 1: planning together with the next trajectory. When set to 1, the trajectory will not execute immediately.
  • block: blocking/non-blocking mode (bool type), true: blocking mode, false: non-blocking mode.
  • loop: loop count.

Joint space planning to target pose Movejp_msg

geometry_msgs/Pose pose  
uint8 speed  
uint8 trajectory_connect
bool block

msg members:

  • pose: target pose (geometry_msgs/Pose type), including x, y, z coordinates (float type, in m) + quaternion.
  • speed: speed percentage, 0−100.
  • trajectory_connect: 0: immediate motion planning, 1: planning together with the next trajectory. When set to 1, the trajectory will not execute immediately.
  • block: blocking/non-blocking mode (bool type), true: blocking mode, false: non-blocking mode.

Joint_teaching Jointteach_msg

uint8 num
uint8 direction
uint8 speed

msg members:

  • num: joint num,1~7.
  • direction: teach direction,0-negative direction,1-positive direction.
  • speed: speed:speed percentage ratio coefficient, 0-100.

Position_teaching Posteach_msg

uint8 type
uint8 direction
uint8 speed

msg members:

  • type: Coordinate axis: 0:X-axis direction, 1:Y-axis direction, 2:Z-axis direction.
  • direction: teach direction,0-negative direction,1-positive direction.
  • speed: speed:speed percentage ratio coefficient, 0-100.

Attitude_teaching Ortteach_msg

uint8 type
uint8 direction
uint8 speed

msg members:

  • type: Rotation axis: 0:RX-axis direction, 1:RY-axis direction, 2:RZ-axis direction
  • direction: teach direction,0-negative direction,1-positive direction.
  • speed: speed:speed percentage ratio coefficient, 0-100.

Angle pass-through Jointpos_msg

float32[] joint  
bool follow  
float32 expand  
uint8 dof

msg members:

  • joint: joint angle (float type), in rad.
  • follow: follow state (bool type), true: high follow, false: low follow, default: high follow.
  • expand: expansion joint angle (float type), in rad.
  • dof: degree of freedom of the robotic arm.

Pose pass-through Cartepos_msg

geometry_msgs/Pose pose  
bool follow

msg members:

  • pose: robotic arm pose (geometry_msgs/Pose type), including x, y, z coordinates (float type, in m) + quaternion.
  • follow: follow state (bool type), true: high follow, false: low follow, default: high follow.

Current robotic arm state — angle and Euler angle Armoriginalstate_msg

float32[] joint  
float32[6] pose  
uint16 arm_err  
uint16 sys_err  
uint8 dof

msg members:

  • joint: joint angle (float type), in °.
  • pose: current pose of the robotic arm (float type), including x, y, z coordinates, in m, and x, y, z Euler angles, in °.
  • arm_err: robotic arm error code (unsigned int type).
  • sys_err: system error code (unsigned int type).
  • dof: degree of freedom of the robotic arm.

Current robotic arm state — radian and quaternion Armstate_msg

float32[] joint  
geometry_msgs/Pose pose  
uint16 arm_err  
uint16 sys_err  
uint8 dof

msg members:

  • joint: joint angle (float type), in rad.
  • pose: current pose of the robotic arm (float type), including x, y, z coordinates, in m, and x, y, z, w quaternions.
  • arm_err: robotic arm error code (unsigned int type).
  • sys_err: system error code (unsigned int type).
  • dof: degree of freedom of the robotic arm.

Set the force-controlled grasping of the gripper Gripperpick_msg

uint16 speed  
uint16 force  
bool block
uint16 timeout

msg members:

  • speed: grasping speed (unsigned int type), range: 1−1,000.
  • force: grasping force threshold (unsigned int type), range: 50−1,000.
  • block: blocking/non-blocking mode (bool type), true: blocking mode, false: non-blocking mode.
  • timeout: Set the timeout for the return, and the blocking mode will take effect (in seconds).

Set the continuous force-controlled grasping of the gripper Gripperpick_msg

uint16 speed  
uint16 force  
bool block
uint16 timeout

msg members:

  • speed: grasping speed (unsigned int type), range: 1−1,000.
  • force: grasping force threshold (unsigned int type), range: 50−1,000.
  • block: blocking/non-blocking mode (bool type), true: blocking mode, false: non-blocking mode.
  • timeout: Set the timeout for the return, and the blocking mode will take effect (in seconds).

Set the gripper to a given position Gripperset_msg

uint16 position  
bool block
uint16 timeout

msg members:

  • position: gripper target position (unsigned int type), range: 1−1,000, representing the gripper opening: 0−70 mm.
  • block: blocking/non-blocking mode (bool type), true: blocking mode, false: non-blocking mode.
  • timeout: Set the timeout for the return, and the blocking mode will take effect (in seconds).

Set the force-position hybrid control Setforceposition_msg

uint8 sensor  
uint8 mode  
uint8 direction  
int16 n

msg members:

  • sensor: sensor, 0: 1-DoF force, 1: 6-DoF force.
  • mode: mode, 0: force control in the work frame, 1: force control in the tool frame.
  • direction: force control direction, 0: along the X-axis, 1: along the Y-axis, 2: along the Z-axis, 3: along the RX orientation, 4: along the RY orientation, 5: along the RZ orientation.
  • n: magnitude of the force, in N.

6-DoF force data Sixforce_msg

float32 force_fx  
float32 force_fy  
float32 force_fz  
float32 force_mx  
float32 force_my  
float32 force_mz

msg members:

  • force_fx: magnitude of the force along the X-axis.
  • force_fy: magnitude of the force along the Y-axis.
  • force_fz: magnitude of the force along the Z-axis.
  • force_mx: magnitude of the rotation force along the X-axis.
  • force_my: magnitude of the rotation force along the Y-axis.
  • force_mz: magnitude of the rotation force along the Z-axis.

Set the gesture sequence number of the dexterous hand Handposture_msg

uint16 posture_num  
bool block
uint16 timeout

msg members:

  • posture_num: gesture sequence number pre-stored in the dexterous hand, range: 1−40.
  • block: blocking/non-blocking mode (bool type), true: blocking mode, false: non-blocking mode.
  • timeout: The timeout setting for blocking mode, unit: seconds.

Set the action sequence number of the dexterous hand Handseq_msg

uint16 seq_num  
bool block
uint16 timeout

msg members:

  • seq_num: action sequence number pre-stored in the dexterous hand, range: 1−40.
  • block: blocking/non-blocking mode (bool type), true: blocking mode, false: non-blocking mode.
  • timeout: The timeout setting for blocking mode, unit: seconds.

Set the angles of the dexterous hand Handangle_msg

int16[6] hand_angle   
bool block

msg members:

  • hand_angle: array of finger angles, range: 0−1,000. Additionally, -1 indicates that no action will be performed for this degree of freedom, and the current state will be maintained.
  • block: blocking/non-blocking mode (bool type), true: blocking mode, false: non-blocking mode.

Set the speed of the dexterous hand Handspeed_msg

uint16 hand_speed

msg members:

  • hand_speed: finger speed, range: 1−1,000.

Set the force threshold of the dexterous hand Handforce_msg

uint16 hand_force

msg members:

  • hand_force: finger force, range: 1−1,000.

Pass-through force-position hybrid control compensation — angle Forcepositionmovejoint_msg

float32[] joint  
uint8 sensor  
uint8 mode  
int16 dir  
float32 force  
bool follow  
uint8 dof

msg members:

  • joint: pass-through force-position hybrid control of angle, in rad.
  • sensor: sensor type, 0: 1-DoF force, 1: 6-DoF force.
  • mode: mode: 0: along the work frame, 1: along the tool frame.
  • dir: force control direction, 0−5: X/Y/Z/Rx/Ry/Rz. For the 1-DoF force type, the default direction is the Z-axis.
  • force: magnitude of the force, accuracy: 0.1 N or 0.1 N.m.
  • follow: follow state (bool type), true: high follow, false: low follow, default: high follow.
  • dof: degree of freedom of the robotic arm.

Pass-through force-position hybrid control compensation — pose Forcepositionmovejoint_msg

geometry_msgs/Pose pose  
uint8 sensor  
uint8 mode  
int16 dir  
float32 force  
bool follow

msg members:

  • pose: robotic arm pose, including position (x, y, z) + orientation (quaternion).
  • sensor: sensor type, 0: 1-DoF force, 1: 6-DoF force.
  • mode: mode: 0: along the work frame, 1: along the tool frame.
  • dir: force control direction, 0−5: X/Y/Z/Rx/Ry/Rz. For the 1-DoF force type, the default direction is the Z-axis.
  • force: magnitude of the force, accuracy: 0.1 N or 0.1 N.m.
  • follow: follow state (bool type), true: high follow, false: low follow, default: high follow.

Set the open-loop speed control — lifting mechanism Liftspeed_msg

int16 speed  
bool block

msg members:

  • speed: speed percentage, -100 to 100. 1. speed<0: Lifting mechanism moves down; 2. speed>0: Lifting mechanism moves up; 3. speed=0: Lifting mechanism stops moving.
  • block: blocking/non-blocking mode (bool type), true: blocking mode, false: non-blocking mode.

Set the closed-loop position control — lifting mechanism Liftheight_msg

uint16 height  
uint16 speed  
bool block

msg members:

  • height: target height, unit: mm.
  • speed: speed percentage, 1−100.
  • block: blocking/non-blocking mode (bool type), true: blocking mode, false: non-blocking mode.

Get the state of the lifting mechanism Liftstate_msg

int16 height   
int16 current  
uint16 err_flag

msg members:

  • height: height of the current lifting mechanism, unit: mm, accuracy: 1 mm.
  • current: current of the lifting mechanism, with a precision of 0.001 mA.
  • err_flag: error code of the lifting drive, refer to joint error codes for details.

Get or set the UDP-based real-time robotic arm state pushing Setrealtimepush_msg

uint16 cycle  
uint16 port  
uint16 force_coordinate  
string ip
bool aloha_state_enable
bool arm_current_status_enable
bool expand_state_enable
bool hand_enable
bool joint_speed_enable
bool lift_state_enable
bool plus_base_enable
bool plus_state_enable

msg members:

  • cycle: broadcast cycle, in multiples of 5 ms.
  • port: broadcast port number.
  • force_coordinate: frame for external force data, 0: sensor frame, 1: current work frame, 2: current tool frame.
  • ip: custom pushing target IP address.
  • aloha_state_enable: aloha master arm state enable.
  • arm_current_status_enable: arm_current_status enable.
  • expand_state_enable: Expansion joint-related data enable.
  • hand_enable: Dexterous hand state enable.
  • joint_speed_enable: Current joint speed, with an accuracy of 0.02 rpm.
  • lift_state_enable: Lifting joint data enable.
  • plus_base_enable: Basic information of the end-effector device enable.
  • plus_state_enable: Real-time information of the end-effector device enable.

UDP_manipulator_status_report-Armcurrentstatus_msg

uint16 arm_current_status

msg members:

  • arm_current_status: The status of the robotic arm is defined as follows:

    0-RM_IDLE_E // Enabled but idle state
    1-RM_MOVE_L_E // move L state in motion
    2-RM_MOVE_J_E // move J in motion
    3-RM_MOVE_C_E // move C state in motion
    4-RM_MOVE_S_E // move S state in motion
    5-RM_MOVE_THROUGH_JOINT_E // Angle transparent state
    6-RM_MOVE_THROUGH_POSE_E // Pose transparent state
    7-RM _ move _ through _ force _ pose _ e//Force control transparent transmission state
    8-RM_MOVE_THROUGH_CURRENT_E // Current loop transparent state
    9-RM_STOP_E // Emergency stop status
    10-RM_SLOW_STOP_E // slow stop status
    11-RM_PAUSE_E // Pause status
    12-RM_CURRENT_DRAG_E // Current loop drag status
    13-RM_SENSOR_DRAG_E // Six-axis force drag state
    14-RM_TECH_DEMONSTRATION_E // Teaching Status

UDP_joint_current_report-Jointcurrent_msg

float32[] joint_current

msg members:

  • joint_current: Current joint current with an accuracy of 0.001mA.

UDP_joint_enabling_status_report-Jointenflag_msg

bool[] joint_en_flag

msg members:

  • joint_en_flag: Current joint enabling state, 1 is up enabling and 0 is down enabling.

UDP_manipulator_Eulers_angular_pose_is_reported_to-Jointposeeuler_msg

float32[3] euler
float32[3] position

msg members:

  • euler: Euler angle of current waypoint attitude, with an accuracy of 0.001rad.
  • position: The current waypoint position has an accuracy of 0.000001M.

UDP_joint_speed_report_Jointspeed_msg

float32[] joint_speed

msg members:

  • joint_speed: Current joint speed, accuracy 0.02RPM.

UDP_joint_temperature_report_Jointtemperature_msg

float32[] joint_temperature

msg members:

  • joint_temperature: Current joint temperature, with an accuracy of 0.001℃.

UDP_joint_voltage_report_Jointvoltage_msg

float32[] joint_voltage

msg members:

  • joint_voltage: Current joint voltage, with an accuracy of 0.001V V.

System_error_code_Rmerr_msg

uint8 err_len
int32[] err

msg members:

  • err_len: uint8.
  • err: int32.

Basic_information_of_the_end_effector_device_Rmplusbase_msg

string manu
int8 type
string hv
string sv
string bv
int32 id
int8 dof
int8 check
int8 bee
bool force
bool touch
int8 touch_num
int8 touch_sw
int8 hand
int32[12] pos_up
int32[12] pos_low
int32[12] angle_up
int32[12] angle_low
int32[12] speed_up
int32[12] speed_low
int32[12] force_up
int32[12] force_low

msg members:

  • manu: Device manufacturer.
  • type: Device type, 1 - Two-finger gripper, 2 - Five-finger dexterous hand, 3 - Three-finger gripper.
  • hv: Hardware version.
  • sv: Software version.
  • bv: Bootloader version.
  • id: Device ID.
  • dof: Degrees of freedom.
  • check: Self-check switch.
  • bee: Beeper switch.
  • force: Force control support.
  • touch: Tactile support.
  • touch_num: Number of tactile sensors.
  • touch_sw: Tactile switch.
  • hand: Hand orientation, 1 - Left hand, 2 - Right hand.
  • pos_up: Position upper limit.
  • pos_low: Position lower limit.
  • angle_up: Angle upper limit 0.01°.
  • angle_low: Angle lower limit 0.01°.
  • speed_up: Speed upper limit.
  • speed_low: Speed lower limit.
  • force_up: Force upper limit 0.001N.
  • force_low: Force lower limit 0.001N.

Real_time_information_of_the_end_effector_deviceRmplusstate_msg

int32 sys_state
int32[12] dof_state
int32[12] dof_err
int32[12] pos
int32[12] speed
int32[12] angle
int32[12] current
int32[18] normal_force
int32[18] tangential_force
int32[18] tangential_force_dir
uint32[12] tsa
uint32[12] tma
int32[18] touch_data
int32[12] force

msg members:

  • sys_state: System status.
  • dof_state: Current status of each degree of freedom (DoF).
  • dof_err: Error information of each DoF.
  • pos: Current position of each DoF.
  • speed: Current Speed of Each Degree of each DoF.
  • angle: Current Angle of Each Degree of each DoF.
  • current: Current Current of Each Degree of Freedom.
  • normal_force: Normal Force of Tactile Three-Dimensional Force of Each Degree of Freedom.
  • tangential_force: Tangential Force of Tactile Three-Dimensional Force of Each Degree of Freedom.
  • tangential_force_dir: Direction of Tangential Force of Tactile Three-Dimensional Force of Each Degree of Freedom.
  • tsa: Tactile Self-Approach of Each Degree of Freedom.
  • tma: Tactile Mutual Approach of Each Degree of Freedom.
  • touch_data: Raw Data of Tactile Sensors.
  • force: Torque of Each Degree of Freedom.

Customize_high_following_mode_joint_transmission_Jointposcustom_msg

float32[] joint  
bool follow  
float32 expand  
uint8 dof
uint8 trajectory_mode
uint8 radio

msg members:

  • joint: Joint angle, float type, unit: radians.
  • follow: Follow state, bool type, true: high follow, false: low follow, default high follow if not set.
  • expand: Expand joint, float type, unit: radians.
  • dof: Degree of freedom message of the robotic arm.
  • trajectory_mode: When the high following mode is set, multiple modes are supported, including 0- complete transparent transmission mode, 1- curve fitting mode and 2- filtering mode.
  • radio: Set the smoothing coefficient in curve fitting mode (range 0-100) or the filter parameter in filtering mode (range 0-1000). The higher the value, the better the smoothing effect.

Customize_high_following_mode_pose_transmission_Carteposcustom_msg

geometry_msgs/Pose pose  
bool follow  
uint8 trajectory_mode
uint8 radio

msg members:

  • pose: Robotic arm poses geometry_msgs/Pose type, x, y, z coordinates (float type, unit: m) + quaternion.
  • follow: Follow state, bool type, true: high follow, false: low follow, default high follow if not set.
  • trajectory_mode: When the high following mode is set, multiple modes are supported, including 0- complete transparent transmission mode, 1- curve fitting mode and 2- filtering mode.
  • radio: Set the smoothing coefficient in curve fitting mode (range 0-100) or the filter parameter in filtering mode (range 0-1000). The higher the value, the better the smoothing effect.

It is mainly for the application of API to achieve some of the robotic arm functions; for a more complete introduction and use, please see RealMan Robotic Arm ROS2 Topic Detailed Description.