Skip to content

Introduction to the ROS2 Calling API Interface Package (V1.0.0)

To facilitate users in controlling the robotic arm through ROS2, RealMan provides an API-based ROS2 package, and the details on the control of the robotic arm are available in the relevant documents and descriptions of the API. In actual use, users establish communication with the robotic arm through the Ethernet port to control the robotic arm.

Error description

Type of the controller error

S/NError Code (Hexadecimal)Description
10x0000Normal system
20x1001Abnormal joint communication
30x1002Target angle out of limit
40x1003Point unreachable as a singularity
50x1004Real-time kernel communication error
60x1005Joint communication bus error
70x1006Planning layer kernel error
80x1007Joint overspeed
90x1008End interface board disconnected
100x1009Speed out of limit
110x100AAcceleration out of limit
120x100BJoint brake release failed
130x100COverspeed during drag teaching
140x100DRobotic arm collision
150x100ENull work frame
160x100FNull tool frame
170x1010Joint disabling error

Type of the joint error

S/NError Code (Hexadecimal)Description
10x0000Normal joint
20x0001FOC error
30x0002Overvoltage
40x0004Undervoltage
50x0008Over-temperature
60x0010Start failed
70x0020Encoder error
80x0040Overcurrent
90x0080Software error
100x0100Temperature sensor error
110x0200Position out of limit error
120x0400Invalid joint ID
130x0800Position tracking error
140x1000Current detection error
150x2000Brake release failed
160x4000Position command step warning
170x8000Multi-coil joint data loss
180xF000Communication frame loss

Type of the API error

ParameterTypeDescriptionHandling Suggestions
0intSuccess.-
1intThe controller returns false, indicating that the parameters are sent incorrectly or the robotic arm state is wrong.- Validate JSON Command:
① Enable DEBUG logs for the API to capture the raw JSON data.
② Check JSON syntax: Ensure correct formatting of parentheses, quotes, commas, etc. (You can use a JSON validation tool).
③ Verify against the API documentation that parameter names, data types, and value ranges comply with the specifications.
④ After fixing the issues, resend the command and check if the controller returns a normal status code and business data.
- Check Robot Arm Status:
① Check for real-time error messages in the robot arm controller or logs (such as hardware failures, over-limit conditions), and reset, calibrate, or troubleshoot hardware issues according to the prompts.
② After fixing the issues, resend the command and check if the controller returns a normal status code and business data.
-1intThe data transmission fails, indicating that a problem occurs during the communication.Check Network Connectivity:
Use tools like ping/telnet to check if the communication link with the controller is normal.
-2intThe data reception fails, indicating that a problem occurs during the communication, or the controller has a return timeout.- Check Network Connectivity:
Use tools like ping/telnet to check if the communication link with the controller is normal.
- Verify Version Compatibility:
① Check if the controller firmware version supports the current API functions. For specific version compatibility, refer to the Version Description.
② If the version is too low, upgrade the controller or use an API version that is compatible.
- Call the ModbusTCP interface: Applicable only when reading from or writing to the ModbusTCP device of the controller. After creating the robot arm control handle, you must call the rm_set_modbustcp_mode() interface; otherwise, no return value will be received.
-3intThe return value parse fails, indicating that the received data format is incorrect or incomplete.Verify Version Compatibility:
① Check if the controller firmware version supports the current API functions. For specific version compatibility, refer to the Version Description.
② If the version is too low, upgrade the controller or use an API version that is compatible.
-4intThe current in-position equipment verification fails, indicating the current in-position equipment is not the joints/elevators/grippers/dexterous hands.- Detect Concurrent Control by Multiple Devices: Check if other devices are sending motion commands to the robot arm, including the motion of the robot arm, gripper, dexterous hand, and elevator.
- Monitor Command Events in Real-Time: Register the callback function rm_get_arm_event_call_back:
① Capture device arrival events (such as motion completion, timeout, etc.).
② Determine the specific device type that triggered the event through the device parameter in the callback.
-5intThe single-thread mode does not receive a return value after the timeout, indicating that the timeout period may be improper.- Check Timeout Setting: In single-thread blocking mode, it supports configuring the timeout for waiting for the device to complete its motion. Ensure that the timeout is set longer than the device's motion time.
- Check Network Connectivity:
Use tools like ping/telnet to check if the communication link with the controller is normal.

ROS_Function_Package_Robotic_Arm_Instructions

This section describes how to query and control the robotic arm through the topic of ROS.

Joint configuration

Clear the joint error code Jointerrclear.msg

Parameter description:

ParameterTypeDescription
joint_numuint8Corresponding joint number, the six degrees of freedom are numbered sequentially from 1 to 6, and the seven degrees of freedom are numbered sequentially from 1 to 7.

Usage command demo:

json
ros2 topic pub /rm_driver/set_joint_err_clear_cmd rm_ros_interfaces/msg/Jointerrclear "joint_num: 1"

Return command demo:

json
ros2 topic echo /rm_driver/set_joint_err_clear_result

Parameter description:

ParameterTypeDescription
std_msgsbooltrue: setting succeeded, false: setting failed.

Work frame setting

Change the current work frame

Parameter description:

ParameterTypeDescription
std_msgsStringROS built-in msg.

Usage command demo:

json
ros2 topic pub /rm_driver/change_work_frame_cmd std_msgs/msg/String "data: 'Base'"

Return command demo:

json
ros2 topic echo /rm_driver/change_work_frame_result

Parameter description:

ParameterTypeDescription
std_msgsbooltrue: setting succeeded, false: setting failed.

Frame getting

Get the current tool frame

Parameter description:

ParameterTypeDescription
std_msgsEmptyROS built-in msg.

Usage command demo:

json
ros2 topic pub --once /rm_driver/get_current_tool_frame_cmd std_msgs/msg/Empty "{}"

Return command demo: Name of the current tool frame.

json
ros2 topic echo /rm_driver/get_current_tool_frame_result

Get the names of all tool frames

Parameter description:

ParameterTypeDescription
std_msgsEmptyROS built-in msg.

Usage command demo:

json
ros2 topic pub /rm_driver/get_all_tool_frame_cmd std_msgs/msg/Empty "{}"

Return command demo: Names of all tool frames.

json
ros2 topic echo /rm_driver/get_all_tool_frame_result

Get the current work frame

Parameter description:

ParameterTypeDescription
std_msgsEmptyROS built-in msg.

Usage command demo:

json
ros2 topic pub --once /rm_driver/get_curr_workFrame_cmd std_msgs/msg/Empty "{}"

Return command demo:

json
ros2 topic echo /rm_driver/get_curr_workFrame_result

Parameter description:

ParameterTypeDescription
std_msgsbooltrue: setting succeeded, false: setting failed.

Get the names of all work frames

Parameter description:

ParameterTypeDescription
std_msgsEmptyROS built-in msg.

Usage command demo:

json
ros2 topic pub --once /rm_driver/get_all_work_frame_cmd std_msgs/msg/Empty "{}"

Return command demo: Names of all work frames.

json
ros2 topic echo /rm_driver/get_all_work_frame_result

Robotic arm state getting

Get the current robotic arm state — return the angle and Euler angle of each joint

Parameter description:

ParameterTypeDescription
std_msgsEmptyROS built-in msg.

Usage command demo:

json
ros2 topic pub --once /rm_driver/get_current_arm_state_cmd std_msgs/msg/Empty "{}"

Return command demo: Current joint state (angle) + pose (Euler angle) + error message.

json
ros2 topic echo /rm_driver/get_current_arm_original_state_result

Get the current robotic arm state — return the radian and quaternion of each joint

Parameter description:

ParameterTypeDescription
std_msgsEmptyROS built-in msg.

Usage command demo:

json
ros2 topic pub --once /rm_driver/get_current_arm_state_cmd std_msgs/msg/Empty "{}"

Return command demo: Current joint state (radian) + pose (quaternion) + error message.

json
ros2 topic echo /rm_driver/get_current_arm_state_result

Robotic arm motion planning

Joint motion MoveJ.msg

Parameter description:

ParameterTypeDescription
jointfloat32[6]Joint angle, in rad.
speeduint8Speed percentage, 0−100.
trajectory_connectuint8Optional, indicating whether to plan the motion together with the next trajectory.
0: The motion is planned immediately,
1: It is planned together with the next trajectory. When set to 1, the trajectory will not execute immediately.
blockboolBlocking/Non-blocking mode, true: blocking mode, false: non-blocking mode.
dofuint8The degrees of freedom of the robotic arm.

Usage command demo: 6-DoF robotic arm:

json
ros2 topic pub --once /rm_driver/movej_cmd rm_ros_interfaces/msg/Movej "joint: [0, 0, 0, 0, 0, 0] speed: 20 block: true trajectory_connect: 0 dof: 6"

7-DoF robotic arm:

json
ros2 topic pub --once /rm_driver/movej_cmd rm_ros_interfaces/msg/Movej "joint: [0, 0, 0, 0, 0, 0, 0] speed: 20 block: true trajectory_connect: 0 dof: 7"

Return command demo:

json
ros2 topic echo /rm_driver/movej_result

Parameter description:

ParameterTypeDescription
std_msgsbooltrue: setting succeeded, false: setting failed. Return the error code from the driver terminal.

Cartesian-space linear motion Movel.msg

Parameter description:

ParameterTypeDescription
geometry_msgs/PosefloatRobotic arm pose, including x, y, z coordinates (float type, in m) + quaternion.
speeduint8Speed percentage, 0−100.
trajectory_connectuint8Optional, indicating whether to plan the motion together with the next trajectory.
0: The motion is planned immediately,
1: It is planned together with the next trajectory. When set to 1, the trajectory will not execute immediately.
blockboolBlocking/Non-blocking mode, true: blocking mode, false: non-blocking mode.

Usage command demo: Firstly, execute the MoveJ_P:

json
ros2 topic pub --once /rm_driver/movej_p_cmd rm_ros_interfaces/msg/Movejp "pose:position: x: -0.317239 y: 0.120903 z: 0.255765 orientation: x: -0.983404 y: -0.178432 z: 0.032271 w: 0.006129 speed:20 trajectory_connect: 0 block: true"

Then, execute the MoveL:

json
ros2 topic pub --once /rm_driver/movel_cmd rm_ros_interfaces/msg/Movel "pose: position: x: -0.317239 y: 0.120903 z: 0.295765 orientation: x: -0.983404 y: -0.178432 z: 0.032271 w: 0.006129 speed: 20 trajectory_connect: 0 block: true"

Return command demo:

json
ros2 topic echo /rm_driver/movel_result

Parameter description:

ParameterTypeDescription
std_msgsbooltrue: setting succeeded, false: setting failed. Return the error code from the driver terminal.

Cartesian-space circular motion Movec.msg

ParameterTypeDescription
pose_midgeometry_msgs/PoseMiddle pose of the robotic arm, including x, y, z coordinates (float type, in m) + quaternion.
pose_endgeometry_msgs/PoseEnd pose of the robotic arm, including x, y, z coordinates (float type, in m) + quaternion.
speeduint8Speed percentage, 0−100.
trajectory_connectuint8Optional, indicating whether to plan the motion together with the next trajectory.
0: The motion is planned immediately,
1: It is planned together with the next trajectory. When set to 1, the trajectory will not execute immediately.
blockboolBlocking/Non-blocking mode, true: blocking mode, false: non-blocking mode.
loopuint16Number of rotations.

Usage command demo: Firstly, execute the MoveJ_P:

json
ros2 topic pub --once /rm_driver/movej_p_cmd rm_ros_interfaces/msg/Movejp "pose: position: x: 0.274946 y: -0.058786 z: 0.299028 orientation: x: 0.7071 y: -0.7071 z: 0.0 w: 0.0 speed: 0 trajectory_connect: 0 block: true"

Then, execute the MoveC to reach the given position:

json
ros2 topic pub --once /rm_driver/movec_cmd rm_ros_interfaces/msg/Movec "pose_mid: position: x: 0.324946 y: -0.008786 z: 0.299028 orientation: x: 0.7071 y: -0.7071 z: 0.0 w: 0.0 pose_end: position: x: 0.274946 y: 0.041214 z: 0.299028 orientation: x: 0.7071 y: -0.7071 z: 0.0 w: 0.0 speed: 20 trajectory_connect: 0 block: false loop: 0

Return command demo:

json
ros2 topic echo /rm_driver/movec_result

Joint angle pass-through via CANFD JointPos.msg

ParameterTypeDescription
jointfloat32[6]Joint angle, in rad.
followboolFollow state, true: high follow, false: low follow, default: high follow.
expandfloat32Expansion angle, in rad.
dofuint8The degrees of freedom of the robotic arm.

Usage command demo: Pass-through requires continuously sending multiple consecutive points to achieve the functionality, rather than simply relying on the following command. Currently, the moveit2 uses an angle pass-through control.

json
ros2 topic pub /rm_driver/movej_canfd_cmd rm_ros_interfaces/msg/Jointpos "joint: [0, 0, 0, 0, 0, 0] follow: false expand: 0.0 dof: 6"

Return command demo: Succeeded: no return value; failed: return the error code from the driver terminal.

Customize high following mode joint angle CANFD transmission

ParameterTypeDescription
jointfloat32[6]Joint angle, in rad.
followboolFollow state, true: high follow, false: low follow, default: high follow.
expandfloat32Expansion angle, in rad.
trajectory_modeuint8When the high following mode is set, multiple modes are supported, including 0- complete transparent transmission mode, 1- curve fitting mode and 2- filtering mode.
radiouint8Set 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.
dofuint8The degrees of freedom of the robotic arm.

Usage command demo: Pass-through requires continuously sending multiple consecutive points to achieve the functionality, rather than simply relying on the following command. Currently, the moveit2 uses an angle pass-through control.

json
ros2 topic pub /rm_driver/movej_canfd_custom_cmd rm_ros_interfaces/msg/Jointposcustom "joint: [0, 0, 0, 0, 0, 0] follow: false expand: 0.0 trajectory_mode: 0 radio: 0 dof: 6"

Return command demo: Succeeded: no return value; failed: return the error code from the driver terminal.

Pose pass-through via CANFD Jointpos.msg

ParameterTypeDescription
posegeometry_msgs/PosePass-through pose, including x, y, z coordinates (float type, in m) + quaternion.
followboolFollow state, true: high follow, false: low follow, default: high follow.

Usage command demo: A large number of consecutive points (more than 10) are required and continuously published with a cycle of at least 2 ms. However, simply relying on the following command will not accomplish the task.

json
ros2 topic pub /rm_driver/movep_canfd_cmd rm_ros_interfaces/msg/Cartepos "pose: position: x: 0.0 y: 0.0 z: 0.0 orientation: x: 0.0 y: 0.0 z: 0.0 w: 1.0 follow: false"

Return command demo: Succeeded: no return value; failed: return the error code from the driver terminal.

Customize high following mode pose CANFD transmission

ParameterTypeDescription
posegeometry_msgs/PosePass-through pose, including x, y, z coordinates (float type, in m) + quaternion.
followboolFollow state, true: high follow, false: low follow, default: high follow.
trajectory_modeuint8When the high following mode is set, multiple modes are supported, including 0- complete transparent transmission mode, 1- curve fitting mode and 2- filtering mode.
radiouint8Set 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.

Usage command demo: A large number of consecutive points (more than 10) are required and continuously published with a cycle of at least 2 ms. However, simply relying on the following command will not accomplish the task.

json
ros2 topic pub /rm_driver/movep_canfd_custom_cmd rm_ros_interfaces/msg/Carteposcustom "pose: position: x: 0.0 y: 0.0 z: 0.0 orientation: x: 0.0 y: 0.0 z: 0.0 w: 1.0 follow: false trajectory_mode: 0 radio: 0"

Return command demo: Succeeded: no return value; failed: return the error code from the driver terminal.

Joint space planning to target pose Movejp.msg

ParameterTypeDescription
posegeometry_msgs/PoseTarget pose, including x, y, z coordinates (float type, in m) + quaternion.
speeduint8Speed percentage, 0−100.
blockboolBlocking/Non-blocking mode, true: blocking mode, false: non-blocking mode.

Usage command demo:

json
ros2 topic pub --once /rm_driver/movej_p_cmd rm_ros_interfaces/msg/Movejp "pose: position: x: -0.317239 y: 0.120903 z: 0.255765 orientation: x: -0.983404 y: -0.178432 z: 0.032271 w: 0.006129 speed: 20 block: true"

Return command demo:

json
ros2 topic echo /rm_driver/movej_p_result

Parameter description:

ParameterTypeDescription
std_msgsbooltrue: setting succeeded, false: setting failed. Return the error code from the driver terminal.

Quick stop std_msgs

ParameterTypeDescription
std_msgsStringROS built-in msg.

Usage command demo:

json
ros2 topic pub /rm_driver/move_stop_cmd std_msgs/msg/Empty "{}"

Return command demo:

json
ros2 topic echo /rm_driver/move_stop_result

Parameter description:

ParameterTypeDescription
std_msgsbooltrue: setting succeeded, false: setting failed. Return the error code from the driver terminal.

Teaching instructions

Joint teaching

ParameterTypeDescription
numuint8Joint num,1~7.
directionuint8Teach direction,0-negative direction,1-positive direction.
speeduint8Speed percentage ratio coefficient, 0-100.

Usage command demo:

json
ros2 topic pub /rm_driver/set_joint_teach_cmd rm_ros_interfaces/msg/Jointteach "num: 1 direction: 0 speed: 10"

Return command demo:

json
ros2 topic echo /rm_driver/set_joint_teach_result

Parameter description:

ParameterTypeDescription
std_msgsbooltrue: setting succeeded, false: setting failed. Return the error code from the driver terminal.

Position teaching

ParameterTypeDescription
typeuint8Coordinate axis: 0:X-axis direction, 1:Y-axis direction, 2:Z-axis direction.
directionuint8Teach direction,0-negative direction,1-positive direction.
speeduint8Speed percentage ratio coefficient, 0-100.

Usage command demo:

json
ros2 topic pub /rm_driver/set_pos_teach_cmd rm_ros_interfaces/msg/Posteach "type: 2 direction: 0 speed: 10"

Return command demo:

json
ros2 topic echo /rm_driver/set_pos_teach_result

Parameter description:

ParameterTypeDescription
std_msgsbooltrue: setting succeeded, false: setting failed. Return the error code from the driver terminal.

Attitude teaching

ParameterTypeDescription
typeuint8Rotation axis: 0:RX-axis direction, 1:RY-axis direction, 2:RZ-axis direction.
directionuint8Teach direction,0-negative direction,1-positive direction.
speeduint8Speed percentage ratio coefficient, 0-100.

Usage command demo:

json
ros2 topic pub /rm_driver/set_ort_teach_cmd rm_ros_interfaces/msg/Ortteach "type: 2 direction: 0 speed: 10"

Return command demo:

json
ros2 topic echo /rm_driver/set_ort_teach_result

Parameter description:

ParameterTypeDescription
std_msgsbooltrue: setting succeeded, false: setting failed. Return the error code from the driver terminal.

Stop teaching

ParameterTypeDescription
std_msgsStringROS built-in msg.

Usage command demo:

json
ros2 topic pub /rm_driver/set_stop_teach_cmd std_msgs/msg/Empty "{}"

Return command demo:

json
ros2 topic echo /rm_driver/set_stop_teach_result

Parameter description:

ParameterTypeDescription
std_msgsbooltrue: setting succeeded, false: setting failed. Return the error code from the driver terminal.

End effector IO configuration

Set the tool power output std_msgs

ParameterTypeDescription
datauint16Power output type, 0: 0 V, 2: 12 V, 3: 24 V.

Usage command demo:

json
ros2 topic pub --once /rm_driver/set_tool_voltage_cmd std_msgs/msg/UInt16 "data: 0"

Return command demo:

json
ros2 topic echo /rm_driver/set_tool_voltage_result

Parameter description:

ParameterTypeDescription
std_msgsbooltrue: setting succeeded, false: setting failed. Return the error code from the driver terminal.

Gripper control

The RealMan robotic arm supports various common grippers. In the system, the INSPIRE-ROBOTS EG2-4C2 gripper is equipped. To facilitate user operation of the gripper, the robotic arm controller has adapted the gripper for ROS-based control.

Set the force-controlled grasping of the gripper Gripperpick.msg

ParameterTypeDescription
speeduint161−1,000, representing the gripper opening and closing speed, without a unit of measurement.
forceuint161−1,000, representing the gripping force of the gripper, with a maximum of 1.5 kg.
blockuint16Blocking/Non-blocking mode, true: blocking mode, false: non-blocking mode.
timeoutuint16The timeout setting for blocking mode, unit: seconds.

Usage command demo:

json
ros2 topic pub --once /rm_driver/set_gripper_pick_cmd rm_ros_interfaces/msg/Gripperpick "speed: 200 force: 200 block: true timeout: 10"

Return command demo:

json
ros2 topic echo /rm_driver/set_gripper_pick_result

Parameter description:

ParameterTypeDescription
std_msgsbooltrue: setting succeeded, false: setting failed. Return the error code from the driver terminal.

Set the continuous force-controlled grasping of the gripper Gripperpick.msg

ParameterTypeDescription
speeduint161−1,000, representing the gripper opening and closing speed, without a unit of measurement.
forceuint161−1,000, representing the gripping force of the gripper, with a maximum of 1.5 kg.
blockboolBlocking/Non-blocking mode, true: blocking mode, false: non-blocking mode.
timeoutuint16The timeout setting for blocking mode, unit: seconds.

Usage command demo:

json
ros2 topic pub --once /rm_driver/set_gripper_pick_on_cmd rm_ros_interfaces/msg/Gripperpick "speed: 200 force: 200 block: true timeout: 10"

Return command demo:

json
ros2 topic echo /rm_driver/set_gripper_pick_on_result

Parameter description:

ParameterTypeDescription
std_msgsbooltrue: setting succeeded, false: setting failed. Return the error code from the driver terminal.

Set the gripper to a given position Gripperset.msg

ParameterTypeDescription
positionuint16Gripper target position, range: 1−1,000, representing the gripper opening: 0−70 mm.
blockboolBlocking/Non-blocking mode, true: blocking mode, false: non-blocking mode.
timeoutuint16The timeout setting for blocking mode, unit: seconds.

Usage command demo:

json
ros2 topic pub --once /rm_driver/set_gripper_position_cmd rm_ros_interfaces/msg/Gripperset "position: 500 block: true timeout: 10"

Return command demo:

json
ros2 topic echo /rm_driver/set_gripper_position_result

Parameter description:

ParameterTypeDescription
std_msgsbooltrue: setting succeeded, false: setting failed. Return the error code from the driver terminal.

Drag teaching and trajectory replay

Set the force-position hybrid control Setforceposition.msg

ParameterTypeDescription
sensoruint80: 1-DoF force, 1: 6-DoF forc.
modeuint80: force control in the base frame, 1: force control in the tool frame.
directionuint8Force 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.
nint16Magnitude of the force, unit: N, accuracy: 0.1 N.

Usage command demo:

json
ros2 topic pub --once /rm_driver/set_force_postion_cmd rm_ros_interfaces/msg/Setforceposition "sensor: 1 mode: 0 direction: 2 n: 3"

Return command demo:

json
ros2 topic echo /rm_driver/set_force_postion_result

Parameter description:

ParameterTypeDescription
std_msgsbooltrue: setting succeeded, false: setting failed. Return the error code from the driver terminal.

Stop the force-position hybrid control std_msgs

ParameterTypeDescription
std_msgsStringROS built-in msg.

Usage command demo:

json
ros2 topic pub /rm_driver/stop_force_postion_cmd std_msgs/msg/Empty "{}"

Return command demo:

json
ros2 topic echo /rm_driver/clear_force_data_result

Parameter description:

ParameterTypeDescription
std_msgsbooltrue: setting succeeded, false: setting failed. Return the error code from the driver terminal.

Use of the 6-DoF force sensor

The RealMan RM-65F robotic arm is equipped with an integrated 6-DoF force sensor at the end effector, eliminating the need for external wiring. Users can directly control the 6-DoF force through ROS topics.

Query the 6-DoF force data

ParameterTypeDescription
std_msgsStringROS built-in msg.

Usage command demo:

json
ros2 topic pub rm_driver/get_force_data_cmd std_msgs/msg/Empty "{}"

Return command demo:

Successfully returned 6-DoF force data in the corresponding coordinate system.

  • Raw data:

    json
    ros2 topic echo /rm_driver/get_force_data_result
  • System external force data:

    json
    ros2 topic echo /rm_driver/get_zero_force_data_result
  • Work coordinate system force data:

    json
    ros2 topic echo /rm_driver/get_work_force_data_result
  • Tool coordinate system force data:

    json
    ros2 topic echo /rm_driver/get_tool_force_data_result

Clear the 6-DoF force data std_msgs

ParameterTypeDescription
std_msgsStringROS built-in msg.

Usage command demo:

json
ros2 topic pub /rm_driver/clear_force_data_cmd std_msgs/msg/Empty "{}"

Return command demo:

json
ros2 topic echo /rm_driver/clear_force_data_result

Parameter description:

ParameterTypeDescription
std_msgsbooltrue: setting succeeded, false: setting failed. Return the error code from the driver terminal.

Control of the five-fingered dexterous hand

The RealMan RM65 robotic arm is equipped with a five-fingered dexterous hand, which can be configured by the ROS.

Set the gesture sequence number of the dexterous hand Handposture.msg

ParameterTypeDescription
posture_numuint16Gesture sequence number pre-stored in the dexterous hand, range: 1−40.
blockboolBlocking/Non-blocking mode, true: blocking mode, false: non-blocking mode.
timeoutuint16The timeout setting for blocking mode, unit: seconds.

Usage command demo:

json
ros2 topic pub --once /rm_driver/set_hand_posture_cmd rm_ros_interfaces/msg/Handposture "posture_num: 1 block: true timeout: 10"

Return command demo:

json
ros2 topic echo /rm_driver/set_hand_posture_result

Parameter description:

ParameterTypeDescription
std_msgsbooltrue: setting succeeded, false: setting failed. Return the error code from the driver terminal.

Set the action sequence number of the dexterous hand Handseq.msg

ParameterTypeDescription
seq_numuint16Action sequence number pre-stored in the dexterous hand, range: 1−40.
blockboolBlocking/Non-blocking mode, true: blocking mode, false: non-blocking mode.
timeoutuint16The timeout setting for blocking mode, unit: seconds.

Usage command demo:

json
ros2 topic pub --once /rm_driver/set_hand_seq_cmd rm_ros_interfaces/msg/Handseq "seq_num: 1 block: true timeout: 10"

Return command demo:

json
ros2 topic echo /rm_driver/set_hand_seq_result

Parameter description:

ParameterTypeDescription
std_msgsbooltrue: setting succeeded, false: setting failed. Return the error code from the driver terminal.

Set the angles of the dexterous hand Handangle.msg

ParameterTypeDescription
hand_angleint16[6]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.
blockboolBlocking/Non-blocking mode, true: blocking mode, false: non-blocking mode.

Usage command demo:

json
ros2 topic pub --once /rm_driver/set_hand_angle_cmd rm_ros_interfaces/msg/Handangle "hand_angle: - 0 - 0 - 0 - 0 - 0 - 0 block: true"

Return command demo:

json
ros2 topic echo /rm_driver/set_hand_angle_result

Parameter description:

ParameterTypeDescription
std_msgsbooltrue: setting succeeded, false: setting failed. Return the error code from the driver terminal.

Set the speed of the dexterous hand Handspeed.msg

ParameterTypeDescription
hand_speedint16[6]Finger speed, range: 1−1,000.

Usage command demo:

json
ros2 topic pub --once /rm_driver/set_hand_speed_cmd rm_ros_interfaces/msg/Handspeed "hand_speed: 200"

Return command demo:

json
ros2 topic echo /rm_driver/set_hand_speed_result

Parameter description:

ParameterTypeDescription
std_msgsbooltrue: setting succeeded, false: setting failed. Return the error code from the driver terminal.

Set the force threshold of the dexterous hand Handforce.msg

ParameterTypeDescription
hand_forceint16Finger force, range: 1−1,000.

Usage command demo:

json
ros2 topic pub --once /rm_driver/set_hand_force_cmd rm_ros_interfaces/msg/Handforce "hand_force: 200"

Return command demo:

json
ros2 topic echo /rm_driver/set_hand_force_result

Parameter description:

ParameterTypeDescription
std_msgsbooltrue: setting succeeded, false: setting failed. Return the error code from the driver terminal.

Setting the angle following of the dexterous hand

ParameterTypeDescription
hand_angleint16[6]Hand angle array, the range is 0 to 2000, and -1 represents that no operation is performed on this degree of freedom and the current state remains.
blockboolwhether it is a blocking mode, bool type, true: blocking, false: non-blocking.

Usage command demo:

json
ros2 topic pub --once /rm_driver/set_hand_follow_angle_cmd rm_ros_interfaces/msg/Handangle "hand_angle: - 0 - 0 - 0 - 0 - 0 - 0 block: true"

Return command demo:

json
ros2 topic echo /rm_driver/set_hand_follow_angle_result

Parameter description:

ParameterTypeDescription
std_msgsbooltrue: setting succeeded, false: setting failed. Return the error code from the driver terminal.

Setting the posture following of the dexterous hand

ParameterTypeDescription
hand_angleint16[6]Hand posture array, the range is 0 to 1000, and -1 represents that no operation is performed on this degree of freedom and the current state remains.
blockboolwhether it is a blocking mode, bool type, true: blocking, false: non-blocking.

Usage command demo:

json
ros2 topic pub --once /rm_driver/set_hand_follow_pos_cmd rm_ros_interfaces/msg/Handangle "hand_angle: - 0 - 0 - 0 - 0 - 0 - 0 block: true"

Return command demo:

json
ros2 topic echo /rm_driver/set_hand_follow_pos_result

Parameter description:

ParameterTypeDescription
std_msgsbooltrue: setting succeeded, false: setting failed. Return the error code from the driver terminal.

Lifting mechanism

The RealMan robotic arm controller can integrate a self-developed lifting mechanism, and this interface is used for the control of the lifting mechanism.

Set the open-loop speed control of the lifting mechanism Liftspeed.msg

ParameterTypeDescription
speedint16Speed 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.
blockboolBlocking/Non-blocking mode, true: blocking mode, false: non-blocking mode.

Usage command demo:

json
ros2 topic pub /rm_driver/set_lift_speed_cmd rm_ros_interfaces/msg/Liftspeed "speed: 100 block: true"

Return command demo:

json
ros2 topic echo /rm_driver/set_lift_speed_result

Parameter description:

ParameterTypeDescription
std_msgsbooltrue: setting succeeded, false: setting failed. Return the error code from the driver terminal.

Set the closed-loop position control of the lifting mechanism Liftheight.msg

ParameterTypeDescription
heightint16Target height, unit: mm.
speedint16Speed percentage, 1−100.
blockboolBlocking/Non-blocking mode, true: blocking mode, false: non-blocking mode.

Usage command demo:

json
ros2 topic pub --once /rm_driver/set_lift_height_cmd rm_ros_interfaces/msg/Liftheight "height: 0 speed: 10 block: true"

Return command demo:

json
ros2 topic echo /rm_driver/set_lift_height_result

Parameter description:

ParameterTypeDescription
std_msgsbooltrue: setting succeeded, false: setting failed. Return the error code from the driver terminal.

Get the state of the lifting mechanism Liftstate.msg

ParameterTypeDescription
heightint16Target height, unit: mm, range: 0−2,600.
currentint16Current current.
err_flaguint16Drive error code.

Usage command demo:

json
ros2 topic pub /rm_driver/get_lift_state_cmd std_msgs/msg/Empty "{}"

Return command demo: Return if succeeded: current state of the lifting mechanism; return if failed: error code from the driver terminal.

json
ros2 topic echo /rm_driver/get_lift_state_result

End Effector Ecosystem Command Set

Reading of basic and real-time information of end-effector devices supported by the end-effector ecosystem protocol.

Setting End Effector Ecosystem Protocol Mode

ParameterTypeDescription
dataint320 - Disable protocol;
9600 - Enable protocol (baud rate 9600);
115200 - Enable protocol (baud rate 115200);
256000 - Enable protocol (baud rate 256000);
460800 - Enable protocol (baud rate 460800).

Usage command demo:

json
ros2 topic pub /rm_driver/set_rm_plus_mode_cmd std_msgs/msg/Int32 "data: 0"

Return command demo:

json
ros2 topic echo /rm_driver/set_rm_plus_mode_result

Parameter description:

ParameterTypeDescription
std_msgsbooltrue: setting succeeded, false: setting failed. Return the error code from the driver terminal.

Querying End Effector Ecosystem Protocol Mode

ParameterTypeDescription
std_msgsStringROS built-in msg.

Usage command demo:

json
ros2 topic pub /rm_driver/get_rm_plus_mode_cmd std_msgs/msg/Empty "{}"

Return command demo:

json
ros2 topic echo /rm_driver/get_rm_plus_mode_result

Parameter description:

ParameterTypeDescription
std_msgsint320 - Disable protocol;
9600 - Enable protocol (baud rate 9600);
115200 - Enable protocol (baud rate 115200);
256000 - Enable protocol (baud rate 256000);
460800 - Enable protocol (baud rate 460800).

Setting Tactile Sensor Mode

ParameterTypeDescription
dataint320 - Disable tactile sensor;
1 - Enable tactile sensor (returns processed data);
2 - Enable tactile sensor (returns raw data).

Usage command demo:

json
ros2 topic pub /rm_driver/set_rm_plus_touch_cmd std_msgs::msg::Int32 "data: 0"

Return command demo:

json
ros2 topic echo /rm_driver/set_rm_plus_touch_result

Parameter description:

ParameterTypeDescription
std_msgsbooltrue: setting succeeded, false: setting failed. Return the error code from the driver terminal.

Querying Tactile Sensor Mode

ParameterTypeDescription
std_msgsStringROS built-in msg.

Usage command demo:

json
ros2 topic pub /rm_driver/get_rm_plus_touch_cmd std_msgs/msg/Empty "{}"

Return command demo:

json
ros2 topic echo /rm_driver/get_rm_plus_touch_result

Parameter description:

ParameterTypeDescription
std_msgsint320 - Disable tactile sensor;
1 - Enable tactile sensor (returns processed data);
2 - Enable tactile sensor (returns raw data).

Pass-through force-position hybrid control compensation mode

For RealMan robotic arms in 6-DoF force versions, in addition to directly using the teach pendant to call the underlying force-position hybrid control module, users can also use this interface to integrate custom trajectories with the underlying force-position hybrid control algorithm for compensation in a periodic pass-through form. If the force data calibration is not performed before the force operation, the zero position can be calibrated through the 6-DoF force data clearing interface.

Start the pass-through force-position hybrid control compensation mode std_msgs

ParameterTypeDescription
std_msgsEmptyStart the pass-through force-position hybrid control compensation mode.

Usage command demo:

json
ros2 topic pub /rm_driver/start_force_position_move_cmd std_msgs/msg/Empty "{}"

Return command demo:

json
ros2 topic echo /rm_driver/start_force_position_move_result

Parameter description:

ParameterTypeDescription
std_msgsbooltrue: setting succeeded, false: setting failed. Return the error code from the driver terminal.

Stop the pass-through force-position hybrid control compensation mode std_msgs

ParameterTypeDescription
std_msgsEmptyStop the pass-through force-position hybrid control compensation mode.

Usage command demo:

json
ros2 topic pub /rm_driver/stop_force_position_move_cmd std_msgs/msg/Empty "{}"

Return command demo:

json
ros2 topic echo /rm_driver/stop_force_position_move_result

Parameter description:

ParameterTypeDescription
std_msgsbooltrue: setting succeeded, false: setting failed. Return the error code from the driver terminal.

Pass-through force-position hybrid control compensation — joint Forcepositionmovejoint.msg

ParameterTypeDescription
jointfloat32[6]Target joint radian.
sensoruint8Sensor type, 0: 1-DoF force, 1: 6-DoF force.
modeuint8Mode, 0: along the base frame, 1: along the end frame.
dirint16Force control direction, 0−5: X/Y/Z/Rx/Ry/Rz. For the 1-DoF force type, the default direction is the Z-axis.
forcefloat32Magnitude of the force, in N.
followboolFollow state, true: high follow, false: low follow.
dofuint8Degree of freedom of the robotic arm.

Usage command demo: A large number of consecutive points (more than 10) are required and continuously published with a cycle of at least 2 ms.

json
ros2 topic pub /rm_driver/force_position_move_joint_cmd rm_ros_interfaces/msg/Forcepositionmovejoint "joint: [0, 0, 0, 0, 0, 0] sensor: 0 mode: 0 dir: 0 force: 0.0 follow: false dof: 6"

Return command demo: Return if succeeded: NULL; return if failed: false and error code from the driver terminal.

Pass-through force-position hybrid control compensation — pose Forcepositionmovepose.msg

ParameterTypeDescription
posefloatTarget pose, including x, y, z coordinates (in m) + quaternion.
sensoruint8Sensor type, 0: 1-DoF force, 1: 6-DoF force.
modeuint8Mode, 0: along the base frame, 1: along the end frame.
dirint16Force control direction, 0−5: X/Y/Z/Rx/Ry/Rz. For the 1-DoF force type, the default direction is the Z-axis.
forcefloat32Magnitude of the force, in N.
followboolFollow state, true: high follow, false: low follow.

Usage command demo: A large number of consecutive points (more than 10) are required and continuously published with a cycle of at least 2 ms.

json
ros2 topic pub /rm_driver/force_position_move_pose_cmd rm_ros_interfaces/msg/Forcepositionmovepose "pose: position: x: 0.0 y: 0.0 z: 0.0 orientation: x: 0.0 y: 0.0 z: 0.0 w: 1.0 sensor: 0 mode: 0 dir: 0 force: 0 follow: false"

Return command demo: Return if succeeded: NULL; return if failed: false and error code from the driver terminal.

Robotic arm state active reporting

Set the UDP-based real-time robotic arm state pushing Setrealtimepush.msg

ParameterTypeDescription
cycleuint16Set the broadcast cycle, in multiple of 5 ms (1 by default, i.e., 1*5=5 ms, or 200 Hz).
portuint16Set the broadcast port number (8089 by default).
force_coordinateuint16Set the frame for external force data (only supported by robotic arms with force sensors).
ipstringSet the custom pushing target IP address (192.168.1.10 by default).
hand_enableboolWhether dexterous hand status reporting is enabled, true is enabled, and false is not enabled.
aloha_state_enableboolWhether to enable aloha main arm status reporting, true to enable, false not to enable.
arm_current_status_enableboolWhether to enable the status report of the robot arm, true to enable, false not to enable.
expand_state_enableboolWhether to enable the report of extended joint related data, true is enabled, false is not enabled.
joint_speed_enableboolWhether joint speed reporting is enabled, true is enabled, and false is not enabled.
lift_state_enableboolWhether lifting joint data reporting is enabled, true is enabled, and false is not enabled.
plus_base_enableboolBasic information of the end-effector device,true is enabled, and false is not enabled.
plus_state_enableboolReal-time information of the end-effector device,true is enabled, and false is not enabled.

Usage command demo:

json
ros2 topic pub --once /rm_driver/set_realtime_push_cmd rm_ros_interfaces/msg/Setrealtimepush "cycle: 1 port: 8089 force_coordinate: 0 ip: '192.168.1.10' hand_enable: false aloha_state_enable: false arm_current_status_enable: false expand_state_enable: false joint_speed_enable: false lift_state_enable: false"

Return command demo:

json
ros2 topic echo /rm_driver/set_realtime_push_result

Parameter description:

ParameterTypeDescription
std_msgsbooltrue: setting succeeded, false: setting failed. Return the error code from the driver terminal.

Get the UDP-based real-time robotic arm state pushing Getrealtimepush.msg

ParameterTypeDescription
std_msgsStringROS built-in msg.

Usage command demo:

json
ros2 topic pub --once /rm_driver/get_realtime_push_cmd std_msgs/msg/Empty "{}"

Return command demo:

json
ros2 topic echo /rm_driver/get_realtime_push_result

Parameter description:

ParameterTypeDescription
cycleuint16Set the broadcast cycle, in multiple of 5 ms (1 by default, i.e., 1*5=5 ms, or 200 Hz).
portuint16Set the broadcast port number (8089 by default).
force_coordinateuint16Set the frame for external force data (only supported by robotic arms with force sensors).
ipstringSet the custom pushing target IP address (192.168.1.10 by default).
hand_enableboolWhether dexterous hand status reporting is enabled, true is enabled, and false is not enabled.
aloha_state_enableboolWhether to enable aloha main arm status reporting, true to enable, false not to enable.
arm_current_status_enableboolWhether to enable the status report of the robot arm, true to enable, false not to enable.
expand_state_enableboolWhether to enable the report of extended joint related data, true is enabled, false is not enabled.
joint_speed_enableboolWhether joint speed reporting is enabled, true is enabled, and false is not enabled.
lift_state_enableboolWhether lifting joint data reporting is enabled, true is enabled, and false is not enabled.
plus_base_enableboolBasic information of the end-effector device,true is enabled, and false is not enabled.
plus_state_enableboolReal-time information of the end-effector device,true is enabled, and false is not enabled.

UDP robotic arm state active reporting

6-DoF force Sixforce.msg
ParameterTypeDescription
force_fxfloat32Magnitude of the force along the X-axis.
force_fyfloat32Magnitude of the force along the Y-axis.
force_fzfloat32Magnitude of the force along the Z-axis.
force_mxfloat32Magnitude of the rotation force along the X-axis.
force_myfloat32Magnitude of the rotation force along the Y-axis.
force_mzfloat32Magnitude of the rotation force along the Z-axis.

Usage command demo:

json
ros2 topic echo /rm_driver/udp_six_force
One-axis force Oneforce.msg
ParameterTypeDescription
force_fxfloat32Magnitude of the force along the X-axis.
force_fyfloat32Magnitude of the force along the Y-axis.
force_fzfloat32Magnitude of the force along the Z-axis. (only this value is valid)
force_mxfloat32Magnitude of the rotation force along the X-axis.
force_myfloat32Magnitude of the rotation force along the Y-axis.
force_mzfloat32Magnitude of the rotation force along the Z-axis.

Usage command demo:

json
ros2 topic echo /rm_driver/udp_one_force
Robotic arm error std_msgs
ParameterTypeDescription
datauint16Robotic arm error.

Usage command demo:

json
ros2 topic echo /rm_driver/udp_arm_err
System error std_msgs
ParameterTypeDescription
datauint16System error.

Usage command demo:

json
ros2 topic echo /rm_driver/udp_sys_err
Joint error Jointerrorcode.msg
ParameterTypeDescription
joint_erroruint16Each joint error.
dofuint8Degree of freedom of the robotic arm.

Usage command demo:

json
ros2 topic echo /rm_driver/udp_joint_error_code
Robotic arm radian data sensor_msgs
ParameterTypeDescription
secint32Time, in second.
nanosecuint32Time, in ns.
frame_idstringFrame name.
namestringJoint name.
positionfloat64Joint radian.
velocityfloat64Joint velocity.
effortfloat64Joint force.

Usage command demo:

json
ros2 topic echo /joint_states
Pose geometry_msgs
ParameterTypeDescription
Point positionfloat64Current coordinates of the robotic arm: x, y, z.
Quaternion orientationfloat64Current orientation of the robotic arm: x, y, z, w.

Usage command demo:

json
ros2 topic echo /rm_driver/udp_arm_position
External force data of the 6-DoF force sensor system Sixforce.msg
ParameterTypeDescription
force_fxfloat32Magnitude of external force along the X-axis of the current sensor frame.
force_fyfloat32Magnitude of external force along the Y-axis of the current sensor frame.
force_fzfloat32Magnitude of external force along the Z-axis of the current sensor frame.
force_mxfloat32Magnitude of the rotation force along the X-axis of the current sensor frame.
force_myfloat32Magnitude of the rotation force along the Y-axis of the current sensor frame.
force_mzfloat32Magnitude of the rotation force along the Z-axis of the current sensor frame.

Usage command demo:

json
ros2 topic echo /rm_driver/udp_six_zero_force
External force data of the one-axis force sensor system Oneforce.msg
ParameterTypeDescription
force_fxfloat32Magnitude of external force along the X-axis of the current sensor frame.
force_fyfloat32Magnitude of external force along the Y-axis of the current sensor frame.
force_fzfloat32Magnitude of external force along the Z-axis of the current sensor frame. (only this data is valid)
force_mxfloat32Magnitude of the rotation force along the X-axis of the current sensor frame.
force_myfloat32Magnitude of the rotation force along the Y-axis of the current sensor frame.
force_mzfloat32Magnitude of the rotation force along the Z-axis of the current sensor frame.

Usage command demo:

json
ros2 topic echo /rm_driver/udp_one_zero_force
Reference frame for external force data std_msgs
ParameterTypeDescription
datauint16Frame for external force data, 0: sensor frame, 1: current work frame, 2: current tool frame. This data will affect the reference frame for the external force data of the one-axis force and 6-DoF force sensor systems.

Usage command demo:

json
ros2 topic echo /rm_driver/udp_arm_coordinate
The current state of dexterous dexterity Handstatus.msg
ParameterTypeDescription
hand_angleuint16[6]Finger angle array,range:0~2000.
hand_posuint16[6]Finger position array,range:0~1000.
hand_stateuint16[6]Finger state,0 is releasing, 1 is grasping, 2 positions are in place and stop, 3 forces are in place and stop, 5 current protection stops, 6 electric cylinder stalling stops, 7 electric cylinder failure stops.
hand_forceuint16[6]Dexterous hand degree of freedom current,unit mN.
hand_erruint16Agile Hand System Error,1 indicates an error, 0 indicates no error.

Usage command demo:

json
ros2 topic echo /rm_driver/udp_hand_status
current status of the mechanical arm Armcurrentstatus.msg
ParameterTypeDescription
arm_current_statusuint16Mechanical arm status:
0-RM_IDLE_E // enabled but idle status
1-RM_MOVE_L_E // Move L moving state
2-RM_MOVE_J_E // move J moving state
3-RM_MOVE_C_E // move C moving state
4-RM_MOVE_S_E // move S moving state
5-RM _ move _ /angle transmission state
6-RM_MOVE_THROUGH_POSE_E // posture transmission state
7-RM _ move _ through _ force _ pose _ e//force control transmission state
8-RM _ move _ through _ current _ e// Current loop transparent state
9-RM_STOP_E // emergency stop state
10-RM_SLOW_STOP_E // slow stop state
11-RM_PAUSE_E // Pause state
12-RM_CURRENT_DRAG_E // Current loop drag state
13-RM_SENSOR_DRAG_E // Six-axis force drag state
14-RM _ tech _ demonstration _ e//Teaching state

Usage command demo:

json
ros2 topic echo /rm_driver/udp_arm_current_status
Current joint current Jointcurrent.msg
ParameterTypeDescription
joint_currentfloat32Current joint current with accuracy of 0.001mA.

Usage command demo:

json
ros2 topic echo /rm_driver/udp_joint_current
The current joint enabling state Jointenflag.msg
ParameterTypeDescription
joint_en_flagboolThe current joint enabling state, where 1 is the upper enabling state and 0 is the lower enabling state.

Usage command demo:

json
ros2 topic echo /rm_driver/udp_joint_en_flag
Euler angle posture of mechanical arm Jointposeeuler.msg
ParameterTypeDescription
Eulerfloat32[3]Euler angle of current waypoint attitude with accuracy of 0.001rad.
positionfloat32[3]Current waypoint position with accuracy of 0.000001M.

Usage command demo:

json
ros2 topic echo /rm_driver/udp_joint_en_flag
Current joint speed Jointspeed.msg
ParameterTypeDescription
joint_speedfloat32Current joint speed with an accuracy of 0.02RPM.

Usage command demo:

json
ros2 topic echo /rm_driver/udp_joint_speed
Current joint temperature Jointtemperature.msg
ParameterTypeDescription
joint_temperaturefloat32current joint temperature with accuracy of 0.001℃.

Usage command demo:

json
ros2 topic echo /rm_driver/udp_joint_temperature
Current joint voltage Jointvoltage.msg
ParameterTypeDescription
joint_voltagefloat32current joint voltage with accuracy of 0.001V.

Usage command demo:

json
ros2 topic echo /rm_driver/udp_joint_voltage
Reading Basic Information of End-Effector Device Rmplusbase.msg
ParameterTypeDescription
manustringDevice manufacturer.
typeint8Device type, including 1 - Two-finger gripper, 2 - Five-finger dexterous hand, 3 - Three-finger gripper.
hvstringHardware version.
svstringSoftware version.
bvstringBootloader version.
idint32Device ID.
dofint8Degrees of freedom.
checkint8Self-check switch.
beeint8Beeper switch.
forceboolForce control support.
touchboolTactile support.
touch_numint8Number of tactile sensors.
touch_swint8Tactile switch.
handint8Hand orientation, including 1 - Left hand, 2 - Right hand.
pos_upint32[12]Position upper limit.
pos_lowint32[12]Position lower limit.
angle_upint32[12]Angle upper limit.
angle_lowint32[12]Angle lower limit.
speed_upint32[12]Speed upper limit.
speed_lowint32[12]Speed lower limit.
force_upint32[12]Force upper limit.
force_lowint32[12]Force lower limit.

Usage command demo:

json
ros2 topic echo /rm_driver/udp_rm_plus_base
Reading Real-Time Information of End-Effector Device Rmplusstate.msg
ParameterTypeDescription
sys_stateint32System status.
dof_stateint32[12]Current status of each degree of freedom (DoF).
dof_errint32[12]Error information of each DoF.
posint32[12]Current position of each DoF.
speedint32[12]Current speed of each DoF.
angleint32[12]Current angles of each DoF.
currentint32[12]Current of each DoF.
normal_forceint32[18]Normal force of the tactile three-dimensional force of each DoF.
tangential_forceint32[18]Tangential force of the tactile three-dimensional force of each DoF.
tangential_force_dirint32[18]Direction of the tangential force of the tactile three-dimensional force of each DoF.
tsaint32[12]Tactile self-approach of each DoF.
tmaint32[12]Tactile mutual approach of each DoF.
touch_dataint32[18]Raw data from the tactile sensor.
forceint32[12]Torque of each DoF.

Usage command demo:

json
ros2 topic echo /rm_driver/udp_rm_plus_state