ROS2:
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/N | Error Code (Hexadecimal) | Description |
|---|---|---|
| 1 | 0x0000 | Normal system |
| 2 | 0x1001 | Abnormal joint communication |
| 3 | 0x1002 | Target angle out of limit |
| 4 | 0x1003 | Point unreachable as a singularity |
| 5 | 0x1004 | Real-time kernel communication error |
| 6 | 0x1005 | Joint communication bus error |
| 7 | 0x1006 | Planning layer kernel error |
| 8 | 0x1007 | Joint overspeed |
| 9 | 0x1008 | End interface board disconnected |
| 10 | 0x1009 | Speed out of limit |
| 11 | 0x100A | Acceleration out of limit |
| 12 | 0x100B | Joint brake release failed |
| 13 | 0x100C | Overspeed during drag teaching |
| 14 | 0x100D | Robotic arm collision |
| 15 | 0x100E | Null work frame |
| 16 | 0x100F | Null tool frame |
| 17 | 0x1010 | Joint disabling error |
Type of the joint error
| S/N | Error Code (Hexadecimal) | Description |
|---|---|---|
| 1 | 0x0000 | Normal joint |
| 2 | 0x0001 | FOC error |
| 3 | 0x0002 | Overvoltage |
| 4 | 0x0004 | Undervoltage |
| 5 | 0x0008 | Over-temperature |
| 6 | 0x0010 | Start failed |
| 7 | 0x0020 | Encoder error |
| 8 | 0x0040 | Overcurrent |
| 9 | 0x0080 | Software error |
| 10 | 0x0100 | Temperature sensor error |
| 11 | 0x0200 | Position out of limit error |
| 12 | 0x0400 | Invalid joint ID |
| 13 | 0x0800 | Position tracking error |
| 14 | 0x1000 | Current detection error |
| 15 | 0x2000 | Brake release failed |
| 16 | 0x4000 | Position command step warning |
| 17 | 0x8000 | Multi-coil joint data loss |
| 18 | 0xF000 | Communication frame loss |
Type of the API error
| Parameter | Type | Description | Handling Suggestions |
|---|---|---|---|
| 0 | int | Success. | - |
| 1 | int | The 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. |
| -1 | int | The 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. |
| -2 | int | The 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. |
| -3 | int | The 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. |
| -4 | int | The 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. |
| -5 | int | The 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:
| Parameter | Type | Description |
|---|---|---|
joint_num | uint8 | Corresponding 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:
ros2 topic pub /rm_driver/set_joint_err_clear_cmd rm_ros_interfaces/msg/Jointerrclear "joint_num: 1"Return command demo:
ros2 topic echo /rm_driver/set_joint_err_clear_resultParameter description:
| Parameter | Type | Description |
|---|---|---|
std_msgs | bool | true: setting succeeded, false: setting failed. |
Version Query
Get Joint Software Version
Parameter description:
| Parameter | Type | Description |
|---|---|---|
std_msgs | Empty | ROS built-in empty message type with no specific parameters. |
Usage command demo:
ros2 topic pub --once /rm_driver/get_joint_software_version_cmd std_msgs/msg/Empty "{}"Return command demo:
ros2 topic echo /rm_driver/get_joint_software_version_resultParameter description:Jointversion.msg
| Parameter | Type | Description |
|---|---|---|
joint_version | string[7] | Array of obtained software version numbers for each joint, which need to be converted to hexadecimal (for example: 54536 converted to hexadecimal is D508, corresponding to version number Vd5.0.8 (third-generation controller)). |
state | bool | Acquisition status, true: Acquisition successful, false: Acquisition failed. |
Get End Tool Software Version
Parameter description:
| Parameter | Type | Description |
|---|---|---|
std_msgs | Empty | ROS built-in empty message type with no specific parameters. |
Usage Command demo:
ros2 topic pub --once /rm_driver/get_tool_software_version_cmd std_msgs/msg/Empty "{}"Return command demo:
ros2 topic echo /rm_driver/get_tool_software_version_resultParameter description:Toolsoftwareversionv4.msg
| Parameter | Type | Description |
|---|---|---|
tool_version | string | End tool software version number. |
state | bool | Acquisition status, true: Acquisition successful, false: Acquisition failed. |
Work frame setting
Change the current work frame
Parameter description:
| Parameter | Type | Description |
|---|---|---|
std_msgs | String | ROS built-in msg. |
Usage command demo:
ros2 topic pub /rm_driver/change_work_frame_cmd std_msgs/msg/String "data: 'Base'"Return command demo:
ros2 topic echo /rm_driver/change_work_frame_resultParameter description:
| Parameter | Type | Description |
|---|---|---|
std_msgs | bool | true: setting succeeded, false: setting failed. |
Frame getting
Get the current tool frame
Parameter description:
| Parameter | Type | Description |
|---|---|---|
std_msgs | Empty | ROS built-in msg. |
Usage command demo:
ros2 topic pub --once /rm_driver/get_current_tool_frame_cmd std_msgs/msg/Empty "{}"Return command demo: Name of the current tool frame.
ros2 topic echo /rm_driver/get_current_tool_frame_resultGet the names of all tool frames
Parameter description:
| Parameter | Type | Description |
|---|---|---|
std_msgs | Empty | ROS built-in msg. |
Usage command demo:
ros2 topic pub /rm_driver/get_all_tool_frame_cmd std_msgs/msg/Empty "{}"Return command demo: Names of all tool frames.
ros2 topic echo /rm_driver/get_all_tool_frame_resultGet the current work frame
Parameter description:
| Parameter | Type | Description |
|---|---|---|
std_msgs | Empty | ROS built-in msg. |
Usage command demo:
ros2 topic pub --once /rm_driver/get_curr_workFrame_cmd std_msgs/msg/Empty "{}"Return command demo:
ros2 topic echo /rm_driver/get_curr_workFrame_resultParameter description:
| Parameter | Type | Description |
|---|---|---|
std_msgs | bool | true: setting succeeded, false: setting failed. |
Get the names of all work frames
Parameter description:
| Parameter | Type | Description |
|---|---|---|
std_msgs | Empty | ROS built-in msg. |
Usage command demo:
ros2 topic pub --once /rm_driver/get_all_work_frame_cmd std_msgs/msg/Empty "{}"Return command demo: Names of all work frames.
ros2 topic echo /rm_driver/get_all_work_frame_resultRobotic arm state getting
Get the current robotic arm state — return the angle and Euler angle of each joint
Parameter description:
| Parameter | Type | Description |
|---|---|---|
std_msgs | Empty | ROS built-in msg. |
Usage command demo:
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.
ros2 topic echo /rm_driver/get_current_arm_original_state_resultGet the current robotic arm state — return the radian and quaternion of each joint
Parameter description:
| Parameter | Type | Description |
|---|---|---|
std_msgs | Empty | ROS built-in msg. |
Usage command demo:
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.
ros2 topic echo /rm_driver/get_current_arm_state_resultRobotic arm motion planning
Joint motion MoveJ.msg
Parameter description:
| Parameter | Type | Description |
|---|---|---|
joint | float32[6] | Joint angle, in rad. |
speed | uint8 | Speed percentage, 0−100. |
trajectory_connect | uint8 | Optional, 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. |
block | bool | Blocking/Non-blocking mode, true: blocking mode, false: non-blocking mode. |
dof | uint8 | The degrees of freedom of the robotic arm. |
Usage command demo: 6-DoF robotic arm:
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:
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:
ros2 topic echo /rm_driver/movej_resultParameter description:
| Parameter | Type | Description |
|---|---|---|
std_msgs | bool | true: setting succeeded, false: setting failed. Return the error code from the driver terminal. |
Cartesian-space linear motion Movel.msg
Parameter description:
| Parameter | Type | Description |
|---|---|---|
geometry_msgs/Pose | float | Robotic arm pose, including x, y, z coordinates (float type, in m) + quaternion. |
speed | uint8 | Speed percentage, 0−100. |
trajectory_connect | uint8 | Optional, 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. |
block | bool | Blocking/Non-blocking mode, true: blocking mode, false: non-blocking mode. |
Usage command demo: Firstly, execute the MoveJ_P:
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:
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:
ros2 topic echo /rm_driver/movel_resultParameter description:
| Parameter | Type | Description |
|---|---|---|
std_msgs | bool | true: setting succeeded, false: setting failed. Return the error code from the driver terminal. |
Cartesian-space Linear Offset Motion
Parameter description:Moveloffset.msg
| Parameter | Type | Description |
|---|---|---|
geometry_msgs/Pose | float | Position and attitude offset, position unit: meters, attitude unit: radians. |
speed | int32 | Speed percentage coefficient, 1~100. |
r | int32 | Blending radius percentage coefficient, 0~100. |
trajectory_connect | bool | Trajectory connection flag, 0-Plan and execute the trajectory immediately, not connecting with subsequent trajectories; 1-Plan the current trajectory together with the next trajectory, but not execute immediately (in blocking mode, it will return immediately even if the sending is successful). |
frame_type | bool | Reference coordinate system type, 0-Work coordinate, 1-Tool coordinate. |
block | bool | Blocking setting. In multi-thread mode, 0-Non-blocking mode (return immediately after sending the command), 1-Blocking mode (return only after the robotic arm reaches the target position or planning fails); In single-thread mode, 0-Non-blocking mode (return immediately after sending the command), other values-Blocking mode and set timeout time (set according to the movement time, unit: seconds). |
Usage command demo:
Firstly, execute the MoveJ_P:
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_offset:
ros2 topic pub --once /rm_driver/movel_offset_cmd rm_ros_interfaces/msg/Moveloffset "{
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,
r: 0,
trajectory_connect: false,
frame_type: false,
block: false
}"Return command demo:
ros2 topic echo /rm_driver/movel_offset_resultParameter description:
| Parameter | Type | Description |
|---|---|---|
std_msgs | bool | true: motion successful, false: motion failed. Return the error code from the driver terminal. |
Cartesian-space circular motion Movec.msg
| Parameter | Type | Description |
|---|---|---|
pose_mid | geometry_msgs/Pose | Middle pose of the robotic arm, including x, y, z coordinates (float type, in m) + quaternion. |
pose_end | geometry_msgs/Pose | End pose of the robotic arm, including x, y, z coordinates (float type, in m) + quaternion. |
speed | uint8 | Speed percentage, 0−100. |
trajectory_connect | uint8 | Optional, 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. |
block | bool | Blocking/Non-blocking mode, true: blocking mode, false: non-blocking mode. |
loop | uint16 | Number of rotations. |
Usage command demo: Firstly, execute the MoveJ_P:
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:
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: 0Return command demo:
ros2 topic echo /rm_driver/movec_resultJoint angle pass-through via CANFD JointPos.msg
| Parameter | Type | Description |
|---|---|---|
joint | float32[6] | Joint angle, in rad. |
follow | bool | Follow state, true: high follow, false: low follow, default: high follow. |
expand | float32 | Expansion angle, in rad. |
dof | uint8 | The 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.
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
| Parameter | Type | Description |
|---|---|---|
joint | float32[6] | Joint angle, in rad. |
follow | bool | Follow state, true: high follow, false: low follow, default: high follow. |
expand | float32 | Expansion angle, in rad. |
trajectory_mode | uint8 | 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 | uint8 | 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. |
dof | uint8 | The 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.
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
| Parameter | Type | Description |
|---|---|---|
pose | geometry_msgs/Pose | Pass-through pose, including x, y, z coordinates (float type, in m) + quaternion. |
follow | bool | Follow 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.
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
| Parameter | Type | Description |
|---|---|---|
pose | geometry_msgs/Pose | Pass-through pose, including x, y, z coordinates (float type, in m) + quaternion. |
follow | bool | Follow state, true: high follow, false: low follow, default: high follow. |
trajectory_mode | uint8 | 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 | uint8 | 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. |
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.
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
| Parameter | Type | Description |
|---|---|---|
pose | geometry_msgs/Pose | Target pose, including x, y, z coordinates (float type, in m) + quaternion. |
speed | uint8 | Speed percentage, 0−100. |
block | bool | Blocking/Non-blocking mode, true: blocking mode, false: non-blocking mode. |
Usage command demo:
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:
ros2 topic echo /rm_driver/movej_p_resultParameter description:
| Parameter | Type | Description |
|---|---|---|
std_msgs | bool | true: setting succeeded, false: setting failed. Return the error code from the driver terminal. |
Quick stop std_msgs
| Parameter | Type | Description |
|---|---|---|
std_msgs | String | ROS built-in msg. |
Usage command demo:
ros2 topic pub /rm_driver/move_stop_cmd std_msgs/msg/Empty "{}"Return command demo:
ros2 topic echo /rm_driver/move_stop_resultParameter description:
| Parameter | Type | Description |
|---|---|---|
std_msgs | bool | true: setting succeeded, false: setting failed. Return the error code from the driver terminal. |
Emergency stop
Parameter description:Stop.msg
| Parameter | Type | Description |
|---|---|---|
stop | bool | Emergency stop state setting, true: Emergency stop, false: Resume. |
Usage command demo:
ros2 topic pub --once /rm_driver/emergency_stop_cmd rm_ros_interfaces/Stop "state: true"Return command demo:
ros2 topic echo /rm_driver/emergency_stop_resultParameter description:
| Parameter | Type | Description |
|---|---|---|
std_msgs | bool | true: setting succeeded, false: setting failed. Return the error code from the driver terminal. |
Teaching instructions
Joint teaching
| Parameter | Type | Description |
|---|---|---|
num | uint8 | Joint num,1~7. |
direction | uint8 | Teach direction,0-negative direction,1-positive direction. |
speed | uint8 | Speed percentage ratio coefficient, 0-100. |
Usage command demo:
ros2 topic pub /rm_driver/set_joint_teach_cmd rm_ros_interfaces/msg/Jointteach "num: 1 direction: 0 speed: 10"Return command demo:
ros2 topic echo /rm_driver/set_joint_teach_resultParameter description:
| Parameter | Type | Description |
|---|---|---|
std_msgs | bool | true: setting succeeded, false: setting failed. Return the error code from the driver terminal. |
Position teaching
| Parameter | Type | Description |
|---|---|---|
type | uint8 | Coordinate axis: 0:X-axis direction, 1:Y-axis direction, 2:Z-axis direction. |
direction | uint8 | Teach direction,0-negative direction,1-positive direction. |
speed | uint8 | Speed percentage ratio coefficient, 0-100. |
Usage command demo:
ros2 topic pub /rm_driver/set_pos_teach_cmd rm_ros_interfaces/msg/Posteach "type: 2 direction: 0 speed: 10"Return command demo:
ros2 topic echo /rm_driver/set_pos_teach_resultParameter description:
| Parameter | Type | Description |
|---|---|---|
std_msgs | bool | true: setting succeeded, false: setting failed. Return the error code from the driver terminal. |
Attitude teaching
| Parameter | Type | Description |
|---|---|---|
type | uint8 | Rotation axis: 0:RX-axis direction, 1:RY-axis direction, 2:RZ-axis direction. |
direction | uint8 | Teach direction,0-negative direction,1-positive direction. |
speed | uint8 | Speed percentage ratio coefficient, 0-100. |
Usage command demo:
ros2 topic pub /rm_driver/set_ort_teach_cmd rm_ros_interfaces/msg/Ortteach "type: 2 direction: 0 speed: 10"Return command demo:
ros2 topic echo /rm_driver/set_ort_teach_resultParameter description:
| Parameter | Type | Description |
|---|---|---|
std_msgs | bool | true: setting succeeded, false: setting failed. Return the error code from the driver terminal. |
Stop teaching
| Parameter | Type | Description |
|---|---|---|
std_msgs | String | ROS built-in msg. |
Usage command demo:
ros2 topic pub /rm_driver/set_stop_teach_cmd std_msgs/msg/Empty "{}"Return command demo:
ros2 topic echo /rm_driver/set_stop_teach_resultParameter description:
| Parameter | Type | Description |
|---|---|---|
std_msgs | bool | true: setting succeeded, false: setting failed. Return the error code from the driver terminal. |
Trajectory List
Get Trajectory List
Parameter description:Gettrajectorylist.msg
| Parameter | Type | Description |
|---|---|---|
page_num | int32 | Page number. |
page_size | int32 | Number of items per page. |
vague_search | string | Keyword for fuzzy search. |
Usage command demo:
ros2 topic pub --once /rm_driver/get_trajectory_file_list_cmd rm_ros_interfaces/msg/Gettrajectorylist "{
page_num: 1,
page_size: 10,
vague_search: 's'
}"Return command demo:
ros2 topic echo /rm_driver/get_trajectory_file_list_resultParameter description:Trajectorylist.msg
| Parameter | Type | Description |
|---|---|---|
page_num | int32 | Page number. |
page_size | int32 | Number of items per page. |
total_size | int32 | Length of the list. |
vague_search | string | Keyword for fuzzy search. |
tra_list | Trajectoryinfo[] | Returned trajectory list that matches the criteria. |
state | bool | Query status, true: successful, false: failed. |
Start Running Specified Trajectory
Parameter Description:
| Parameter | Type | Description |
|---|---|---|
std_msgs | String | ROS built-in message. |
Usage Command Demo:
ros2 topic pub --once /rm_driver/set_run_trajectory_cmd std_msgs/msg/String "data: 'sss'"Return Command Demo:
ros2 topic echo /rm_driver/set_run_trajectory_resultDelete Specified Trajectory File
Parameter Description:
| Parameter | Type | Description |
|---|---|---|
std_msgs | String | ROS built-in message. |
Usage Command Demo:
ros2 topic pub --once /rm_driver/delete_trajectory_file_cmd std_msgs/msg/String "data: 'sss'"Return Command Demo:
ros2 topic echo /rm_driver/delete_trajectory_file_resultSave Trajectory File
Parameter Description:
| Parameter | Type | Description |
|---|---|---|
std_msgs | String | ROS built-in message. |
Usage Command Demo:
ros2 topic pub --once /rm_driver/save_trajectory_file_cmd std_msgs/msg/String "data: 'test'"Return Command Demo:
ros2 topic echo /rm_driver/save_trajectory_file_resultGet Flowchart Programming Status
Parameter Description:
| Parameter | Type | Description |
|---|---|---|
std_msgs | String | ROS built-in message. |
Usage Command Demo:
ros2 topic pub --once /rm_driver/get_flowchart_program_run_state_cmd std_msgs/msg/Empty "{}"Return Command Demo:
ros2 topic echo /rm_driver/get_flowchart_program_run_state_resultParameter Description:Flowchartrunstate.msg
| Parameter | Type | Description |
|---|---|---|
run_state | int | Running state, 0 - Not started, 1 - Running, 2 - Paused. |
id | int | ID of the currently enabled file. |
name[32] | char | Name of the currently enabled file (32-character length). |
plan_speed | int | Global planning speed ratio of the currently enabled file, 1-100. |
step_mode | int | Single-step mode, 0 - Empty, 1 - Normal, 2 - Single step. |
modal_id[50] | char | ID of the flowchart block being executed (50-character length). |
state | bool | Running state flag, true: Returned when running normally, false: Returned when not running normally. |
Modbus Mode Query and Configuration
Set Controller RS485 Mode
Parameter Description:RS485params.msg
| Parameter | Type | Description |
|---|---|---|
mode | int32 | Communication mode, 0-RS485 serial communication, 1-modbus-RTU master mode, 2-modbus-RTU slave mode. |
baudrate | int32 | Baud rate, currently supports 9600, 19200, 38400, 57600, 115200, 230400, 460800. |
Usage Command Demo:
ros2 topic pub --once /rm_driver/set_controller_rs485_mode_cmd rm_ros_interfaces/msg/RS485params "{
mode: 0,
baudrate: 115200
}"Return Command Demo:
ros2 topic echo /rm_driver/set_controller_rs485_mode_resultGet Controller RS485 Mode
Parameter Description:
| Parameter | Type | Description |
|---|---|---|
std_msgs | Empty | ROS built-in message. |
Usage Command Demo:
ros2 topic pub --once /rm_driver/get_controller_rs485_mode_cmd std_msgs/msg/Empty "{}"Return Command Demo:
ros2 topic echo /rm_driver/get_controller_rs485_mode_resultParameter Description:RS485params.msg
| Parameter | Type | Description |
|---|---|---|
mode | int32 | Communication mode, 0 - Default RS485 serial communication, 1-modbus-RTU master mode, 2-modbus-RTU slave mode. |
baudrate | int32 | Baud rate (currently supports 9600, 19200, 38400, 57600, 115200, 230400, 460800). |
state | bool | Query status, true - Query successful, false - Query failed. |
Set Tool RS485 Mode
Parameter Description:RS485params.msg
| Parameter | Type | Description |
|---|---|---|
mode | int32 | Tool-side RS485 mode, 0 - Set as RTU master, 1 - Dexterous hand mode, 2 - Gripper mode. |
baudrate | int32 | Baud rate, currently supports 9600, 115200, 460800. |
Usage Command Demo:
ros2 topic pub --once /rm_driver/set_tool_rs485_mode_cmd rm_ros_interfaces/msg/RS485params "{
mode: 0,
baudrate: 115200
}"Return Command Demo:
ros2 topic echo /rm_driver/set_tool_rs485_mode_resultGet Tool RS485 Mode
Parameter Description:
| Parameter | Type | Description |
|---|---|---|
std_msgs | Empty | ROS built-in message. |
Usage Command Demo:
ros2 topic pub --once /rm_driver/get_tool_rs485_mode_cmd std_msgs/msg/Empty "{}"Return Command Demo:
ros2 topic echo /rm_driver/get_tool_rs485_mode_resultParameter Description:RS485params.msg
| Parameter | Type | Description |
|---|---|---|
mode | int32 | Tool-side RS485 mode, 0 - Set as RTU master, 1 - Dexterous hand mode, 2 - Gripper mode. |
baudrate | int32 | Baud rate (currently supports 9600, 19200, 38400, 57600, 115200, 230400, 460800). |
state | bool | Query status, true: Query successful, false: Query failed. |
Add ModbusTCP Master
Parameter Description:Modbustcpmasterinfo.msg
| Parameter | Type | Description |
|---|---|---|
master_name | string | Name of the Modbus master. |
ip | string | IP address of the TCP master. |
port | int32 | Port number of the TCP master. |
Usage Command Demo:
ros2 topic pub --once /rm_driver/add_modbus_tcp_master_cmd rm_ros_interfaces/msg/Modbustcpmasterinfo "{
master_name: '1',
ip: '127.0.0.1',
port: 502
}"Return Command Demo:
ros2 topic echo /rm_driver/add_modbus_tcp_master_resultUpdate ModbusTCP Master
Parameter Description:Modbustcpmasterinfo.msg
| Parameter | Type | Description |
|---|---|---|
master_name | string | Original name of the Modbus master. |
new_master_name | string | New name of the Modbus master. |
ip | string | IP address of the TCP master. |
port | int32 | Port number of the TCP master. |
Usage Command Demo:
ros2 topic pub /rm_driver/update_modbus_tcp_master_cmd rm_ros_interfaces/msg/Modbustcpmasterinfo "{
master_name: '1',
new_master_name: '125',
ip: '127.0.0.1',
port: 502
}"Return Command Demo:
ros2 topic echo /rm_driver/update_modbus_tcp_master_resultDelete ModbusTCP Master
Parameter Description:Mastername.msg
| Parameter | Type | Description |
|---|---|---|
master_name | string | Name of the Modbus master (transmitted via Mastername.msg). |
Usage Command Demo:
ros2 topic pub --once /rm_driver/delete_modbus_tcp_master_cmd rm_ros_interfaces/msg/Mastername "
master_name: '321'
"Return Command Demo:
ros2 topic echo /rm_driver/delete_modbus_tcp_master_resultGet Specified Modbus Master
Parameter Description:Mastername.msg
| Parameter | Type | Description |
|---|---|---|
master_name | string | Name of the Modbus master. |
Usage Command Demo:
ros2 topic pub --once /rm_driver/get_modbus_tcp_master_cmd rm_ros_interfaces/msg/Mastername "master_name: '321'"Return Command Demo:
ros2 topic echo /rm_driver/get_modbus_tcp_master_resultParameter Description:Modbustcpmasterinfo.msg
| Parameter | Type | Description |
|---|---|---|
master_name | string | Name of the Modbus master, maximum length of 15 characters, not exceeding 15 characters. |
ip | string | IP address of the TCP master. |
port | int32 | Port number of the TCP master. |
state | bool | Query status information, true: Query successful, false: Query failed. The driver terminal returns an error code when failed. |
Get Modbus Master List
Parameter Description:Getmodbustcpmasterlist.msg
| Parameter | Type | Description |
|---|---|---|
page_num | int32 | Page number. |
page_size | int32 | Page size. |
vague_search | string | Vague search keyword. Returns all master lists if input is empty. |
Usage Command Demo:
ros2 topic pub --once /rm_driver/get_modbus_tcp_master_list_cmd rm_ros_interfaces/msg/Getmodbustcpmasterlist "{
page_num: 1,
page_size: 10,
vague_search: '1'
}"Return Command Demo:
ros2 topic echo /rm_driver/get_modbus_tcp_master_list_resultParameter Description:Modbustcpmasterlist.msg
| Parameter | Type | Description |
|---|---|---|
page_num | uint8 | Page number. |
page_size | uint8 | Page size. |
total_size | uint8 | Length of the list. |
vague_search | string | Vague search keyword. |
master_list | Modbustcpmasterinfo[] | Returns the list of TCP masters that meet the criteria. |
state | bool | Query status, true: Query successful, false: Query failed. The driver terminal returns an error code when failed. |
Read ModbusRTU Coils
Parameter Description:Modbusrtureadparams.msg
| Parameter | Type | Description |
|---|---|---|
address | int32 | Starting address of data. |
device | int32 | Peripheral device address. |
type | int32 | Host type, 0 - Controller-side Modbus host; 1 - Tool-side Modbus host. |
num | int32 | Number of data to read, with data length not exceeding 100. |
Usage Command Demo:
ros2 topic pub /rm_driver/read_modbus_rtu_coils_cmd rm_ros_interfaces/msg/Modbusrtureadparams "{
address: 0,
device: 1,
type: 0,
num: 1
}"Return Command Demo:
ros2 topic echo /rm_driver/read_modbus_rtu_coils_resultParameter Description:Modbusreaddata.msg
| Parameter | Type | Description |
|---|---|---|
read_data | int32[] | Read modbus data. |
state | bool | Feedback query status information, true: Read successful, false: Read failed. The driver terminal returns an error code when failed. |
Write ModbusRTU Coils
Parameter Description:Modbusrtuwriteparams.msg
| Parameter | Type | Description |
|---|---|---|
address | int32 | Starting address of data. |
device | int32 | Peripheral device address. |
type | int32 | Host type, 0 - Controller-side Modbus host; 1 - Tool-side Modbus host. |
num | int32 | Number of data to write, maximum not exceeding 100. |
data | int32[] | Data to be written, with data length corresponding to num. |
Usage Command Demo:
ros2 topic pub /rm_driver/write_modbus_rtu_coils_cmd rm_ros_interfaces/msg/Modbusrtuwriteparams "{
address: 0,
device: 1,
type: 0,
num: 2,
data: [1, 1]
}"Return Command Demo:
ros2 topic echo /rm_driver/write_modbus_rtu_coils_resultRead ModbusRTU Input Status
Parameter Description:Modbusrtureadparams.msg
| Parameter | Type | Description |
|---|---|---|
address | int32 | Starting address of data. |
device | int32 | Peripheral device address. |
type | int32 | Host type, 0 - Controller-side Modbus host; 1 - Tool-side Modbus host. |
num | int32 | Number of data to read, with data length not exceeding 100. |
Usage Command Demo:
ros2 topic pub /rm_driver/read_modbus_rtu_input_status_cmd rm_ros_interfaces/msg/Modbusrtureadparams "{
address: 0,
device: 0,
type: 0,
num: 1
}"Return Command Demo:
ros2 topic echo /rm_driver/read_modbus_rtu_input_status_resultParameter Description:Modbusreaddata.msg
| Parameter | Type | Description |
|---|---|---|
read_data | int32[] | Read Modbus data. |
state | bool | Feedback query status information, true: Read successful, false: Read failed. The driver terminal returns an error code when failed. |
Read ModbusRTU Holding Registers
Parameter Description:Modbusrtureadparams.msg
| Parameter | Type | Description |
|---|---|---|
address | int32 | Starting address of data. |
device | int32 | Peripheral device address. |
type | int32 | Host type, 0 - Controller-side Modbus host; 1 - Tool-side Modbus host. |
num | int32 | Number of data to read, with data length not exceeding 100. |
Usage Command demo:
ros2 topic pub /rm_driver/read_modbus_rtu_holding_registers_cmd rm_ros_interfaces/msg/Modbusrtureadparams "{
address: 0,
device: 0,
type: 0,
num: 1
}"Return command demo:
ros2 topic echo /rm_driver/read_modbus_rtu_holding_registers_resultParameter Description:Modbusreaddata.msg
| Parameter | Type | Description |
|---|---|---|
read_data | int32[] | Read Modbus data. |
state | bool | Feedback query status information, true: Read successful, false: Read failed. The driver terminal returns an error code when failed. |
Write ModbusRTU Registers
Parameter Description:Modbusrtuwriteparams.msg
| Parameter | Type | Description |
|---|---|---|
address | int32 | Starting address of data. |
device | int32 | Peripheral device address. |
type | int32 | Host type, 0 - Controller-side Modbus host; 1 - Tool-side Modbus host. |
num | int32 | Number of data to write, maximum not exceeding 100. |
data | int32[] | Data to be written, with data length corresponding to num. |
Usage Command Demo:
ros2 topic pub /rm_driver/write_modbus_rtu_registers_cmd rm_ros_interfaces/msg/Modbusrtuwriteparams "{
address: 0,
device: 0,
type: 0,
num: 2,
data: [1, 1]
}"Return Command Demo:
ros2 topic echo /rm_driver/write_modbus_rtu_registers_resultRead ModbusRTU Input Registers
Parameter Description:Modbusrtureadparams.msg
| Parameter | Type | Description |
|---|---|---|
address | int32 | Starting address of data. |
device | int32 | Peripheral device address. |
type | int32 | Host type, 0 - Controller-side Modbus host; 1 - Tool-side Modbus host. |
num | int32 | Number of data to read, with data length not exceeding 100. |
Usage Command Demo:
ros2 topic pub /rm_driver/read_modbus_rtu_input_registers_cmd rm_ros_interfaces/msg/Modbusrtureadparams "{
address: 0,
device: 0,
type: 0,
num: 1
}"Return Command Demo:
ros2 topic echo /rm_driver/read_modbus_rtu_input_registers_resultParameter Description:Modbusreaddata.msg
| Parameter | Type | Description |
|---|---|---|
read_data | int32[] | Read Modbus data. |
state | bool | Feedback query status information, true: Read successful, false: Read failed. The driver terminal returns an error code when failed. |
Read ModbusTCP Coils
Parameter Description:Modbustcpreadparams.msg
| Parameter | Type | Description |
|---|---|---|
address | int32 | Starting address of data. |
master_name | string | Modbus master name, maximum length of 15 characters. |
ip | string | IP address connected to the host. |
port | int32 | Port number connected to the host. |
num | int32 | Number of data to read, maximum not exceeding 100. |
Usage Command Demo:
ros2 topic pub /rm_driver/read_modbus_tcp_coils_cmd rm_ros_interfaces/msg/Modbustcpreadparams "{
address: 0,
master_name: '3',
ip: '127.0.0.6',
port: 502,
num: 1
}"Return Command Demo:
ros2 topic echo /rm_driver/read_modbus_tcp_coils_resultParameter Description:Modbusreaddata.msg
| Parameter | Type | Description |
|---|---|---|
read_data | int32[] | Read modbus data. |
state | bool | Feedback query status information, true: Read successful, false: Read failed. The driver terminal returns an error code when failed. |
Write ModbusTCP Coils
Parameter Description:Modbustcpwriteparams.msg
| Parameter | Type | Description |
|---|---|---|
address | int32 | Starting address of data. |
master_name | string | Modbus master name, maximum length of 15 characters. |
ip | string | IP address connected to the host. |
port | int32 | Port number connected to the host. |
num | int32 | Number of data to write, maximum not exceeding 100. |
data | int32[] | Data to be written, with data length corresponding to num. |
Usage Command Demo:
ros2 topic pub /rm_driver/write_modbus_tcp_coils_cmd rm_ros_interfaces/msg/Modbustcpwriteparams "{
address: 0,
master_name: '3',
ip: '127.0.0.6',
port: 502,
num: 2,
data: [1, 1]
}"Return Command Demo:
ros2 topic echo /rm_driver/write_modbus_tcp_coils_resultRead ModbusTCP Input Status
Parameter Description: Modbustcpreadparams.msg
| Parameter | Type | Description |
|---|---|---|
address | int32 | Starting address of data. |
master_name | string | Modbus master name, maximum length of 15 characters. |
ip | string | IP address connected to the host. |
port | int32 | Port number connected to the host. |
num | int32 | Number of data to read, maximum not exceeding 100. |
Usage Command Demo:
ros2 topic pub /rm_driver/read_modbus_tcp_input_status_cmd rm_ros_interfaces/msg/Modbustcpreadparams "{
address: 0,
master_name: '3',
ip: '127.0.0.6',
port: 502,
num: 1
}"Return Command Demo:
ros2 topic echo /rm_driver/read_modbus_tcp_input_status_resultParameter Description:Modbusreaddata.msg
| Parameter | Type | Description |
|---|---|---|
read_data | int32[] | Read Modbus data. |
state | bool | Feedback query status information, true: Read successful, false: Read failed. The driver terminal returns an error code when failed. |
Read ModbusTCP Holding Registers
Parameter Description:Modbustcpreadparams.msg
| Parameter | Type | Description |
|---|---|---|
address | int32 | Starting address of data. |
master_name | string | Modbus master name, maximum length of 15 characters. |
ip | string | IP address connected to the host. |
port | int32 | Port number connected to the host. |
num | int32 | Number of data to read, maximum not exceeding 100. |
Usage Command Demo:
ros2 topic pub /rm_driver/read_modbus_tcp_holding_registers_cmd rm_ros_interfaces/msg/Modbustcpreadparams "{
address: 0,
master_name: '3',
ip: '127.0.0.6',
port: 502,
num: 1
}"Return Command Demo:
ros2 topic echo /rm_driver/read_modbus_tcp_holding_registers_resultParameter Description:Modbusreaddata.msg
| Parameter | Type | Description |
|---|---|---|
read_data | int32[] | Read Modbus data. |
state | bool | Feedback query status information, true: Read successful, false: Read failed. The driver terminal returns an error code when failed. |
Write ModbusTCP Holding Registers Modbustcpwriteparams.msg
Parameter Description:
| Parameter | Type | Description |
|---|---|---|
address | int32 | Starting address of data. |
master_name | string | Modbus master name, maximum length of 15 characters. |
ip | string | IP address connected to the host. |
port | int32 | Port number connected to the host. |
num | int32 | Number of data to write, maximum not exceeding 100. |
data | int32[] | Data to be written, with data length corresponding to num. |
Usage Command Demo:
ros2 topic pub /rm_driver/write_modbus_tcp_registers_cmd rm_ros_interfaces/msg/Modbustcpwriteparams "{
address: 0,
master_name: '3',
ip: '127.0.0.6',
port: 502,
num: 2,
data: [1, 1]
}"Return Command Demo:
ros2 topic echo /rm_driver/write_modbus_tcp_registers_resultRead ModbusTCP Input Registers
Parameter Description:Modbustcpreadparams.msg
| Parameter | Type | Description |
|---|---|---|
address | int32 | Starting address of data. |
master_name | string | Modbus master name, maximum length of 15 characters. |
ip | string | IP address connected to the host. |
port | int32 | Port number connected to the host. |
num | int32 | Number of data to read, maximum not exceeding 100. |
Usage Command Demo:
ros2 topic pub /rm_driver/read_modbus_tcp_input_registers_cmd rm_ros_interfaces/msg/Modbustcpreadparams "{
address: 0,
master_name: '3',
ip: '127.0.0.6',
port: 502,
num: 1
}"Return Command Demo:
ros2 topic echo /rm_driver/read_modbus_tcp_input_registers_resultParameter Description:Modbusreaddata.msg
| Parameter | Type | Description |
|---|---|---|
read_data | int32[] | Read Modbus data. |
state | bool | Feedback query status information, true: Read successful, false: Read failed. The driver terminal returns an error code when failed. |
End effector IO configuration
Set the tool power output std_msgs
| Parameter | Type | Description |
|---|---|---|
data | uint16 | Power output type, 0: 0 V, 2: 12 V, 3: 24 V. |
Usage command demo:
ros2 topic pub --once /rm_driver/set_tool_voltage_cmd std_msgs/msg/UInt16 "data: 0"Return command demo:
ros2 topic echo /rm_driver/set_tool_voltage_resultParameter description:
| Parameter | Type | Description |
|---|---|---|
std_msgs | bool | true: 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
| Parameter | Type | Description |
|---|---|---|
speed | uint16 | 1−1,000, representing the gripper opening and closing speed, without a unit of measurement. |
force | uint16 | 1−1,000, representing the gripping force of the gripper, with a maximum of 1.5 kg. |
block | uint16 | Blocking/Non-blocking mode, true: blocking mode, false: non-blocking mode. |
timeout | uint16 | The timeout setting for blocking mode, unit: seconds. |
Usage command demo:
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:
ros2 topic echo /rm_driver/set_gripper_pick_resultParameter description:
| Parameter | Type | Description |
|---|---|---|
std_msgs | bool | true: setting succeeded, false: setting failed. Return the error code from the driver terminal. |
Set the continuous force-controlled grasping of the gripper Gripperpick.msg
| Parameter | Type | Description |
|---|---|---|
speed | uint16 | 1−1,000, representing the gripper opening and closing speed, without a unit of measurement. |
force | uint16 | 1−1,000, representing the gripping force of the gripper, with a maximum of 1.5 kg. |
block | bool | Blocking/Non-blocking mode, true: blocking mode, false: non-blocking mode. |
timeout | uint16 | The timeout setting for blocking mode, unit: seconds. |
Usage command demo:
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:
ros2 topic echo /rm_driver/set_gripper_pick_on_resultParameter description:
| Parameter | Type | Description |
|---|---|---|
std_msgs | bool | true: setting succeeded, false: setting failed. Return the error code from the driver terminal. |
Set the gripper to a given position Gripperset.msg
| Parameter | Type | Description |
|---|---|---|
position | uint16 | Gripper target position, range: 1−1,000, representing the gripper opening: 0−70 mm. |
block | bool | Blocking/Non-blocking mode, true: blocking mode, false: non-blocking mode. |
timeout | uint16 | The timeout setting for blocking mode, unit: seconds. |
Usage command demo:
ros2 topic pub --once /rm_driver/set_gripper_position_cmd rm_ros_interfaces/msg/Gripperset "position: 500 block: true timeout: 10"Return command demo:
ros2 topic echo /rm_driver/set_gripper_position_resultParameter description:
| Parameter | Type | Description |
|---|---|---|
std_msgs | bool | true: 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
| Parameter | Type | Description |
|---|---|---|
sensor | uint8 | 0: 1-DoF force, 1: 6-DoF forc. |
mode | uint8 | 0: force control in the base frame, 1: force control in the tool frame. |
direction | uint8 | 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 | int16 | Magnitude of the force, unit: N, accuracy: 0.1 N. |
Usage command demo:
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:
ros2 topic echo /rm_driver/set_force_postion_resultParameter description:
| Parameter | Type | Description |
|---|---|---|
std_msgs | bool | true: setting succeeded, false: setting failed. Return the error code from the driver terminal. |
Stop the force-position hybrid control std_msgs
| Parameter | Type | Description |
|---|---|---|
std_msgs | String | ROS built-in msg. |
Usage command demo:
ros2 topic pub /rm_driver/stop_force_postion_cmd std_msgs/msg/Empty "{}"Return command demo:
ros2 topic echo /rm_driver/clear_force_data_resultParameter description:
| Parameter | Type | Description |
|---|---|---|
std_msgs | bool | true: 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
| Parameter | Type | Description |
|---|---|---|
std_msgs | String | ROS built-in msg. |
Usage command demo:
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:
jsonros2 topic echo /rm_driver/get_force_data_resultSystem external force data:
jsonros2 topic echo /rm_driver/get_zero_force_data_resultWork coordinate system force data:
jsonros2 topic echo /rm_driver/get_work_force_data_resultTool coordinate system force data:
jsonros2 topic echo /rm_driver/get_tool_force_data_result
Clear the 6-DoF force data std_msgs
| Parameter | Type | Description |
|---|---|---|
std_msgs | String | ROS built-in msg. |
Usage command demo:
ros2 topic pub /rm_driver/clear_force_data_cmd std_msgs/msg/Empty "{}"Return command demo:
ros2 topic echo /rm_driver/clear_force_data_resultParameter description:
| Parameter | Type | Description |
|---|---|---|
std_msgs | bool | true: 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.
Setting the angle following of the dexterous hand
| Parameter | Type | Description |
|---|---|---|
hand_angle | int16[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. |
block | bool | whether it is a blocking mode, bool type, true: blocking, false: non-blocking. |
Usage command demo:
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:
ros2 topic echo /rm_driver/set_hand_follow_angle_resultParameter description:
| Parameter | Type | Description |
|---|---|---|
std_msgs | bool | true: setting succeeded, false: setting failed. Return the error code from the driver terminal. |
Setting the posture following of the dexterous hand
| Parameter | Type | Description |
|---|---|---|
hand_angle | int16[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. |
block | bool | whether it is a blocking mode, bool type, true: blocking, false: non-blocking. |
Usage command demo:
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:
ros2 topic echo /rm_driver/set_hand_follow_pos_resultParameter description:
| Parameter | Type | Description |
|---|---|---|
std_msgs | bool | true: 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
| Parameter | Type | Description |
|---|---|---|
speed | int16 | 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 | bool | Blocking/Non-blocking mode, true: blocking mode, false: non-blocking mode. |
Usage command demo:
ros2 topic pub /rm_driver/set_lift_speed_cmd rm_ros_interfaces/msg/Liftspeed "speed: 100 block: true"Return command demo:
ros2 topic echo /rm_driver/set_lift_speed_resultParameter description:
| Parameter | Type | Description |
|---|---|---|
std_msgs | bool | true: 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
| Parameter | Type | Description |
|---|---|---|
height | int16 | Target height, unit: mm. |
speed | int16 | Speed percentage, 1−100. |
block | bool | Blocking/Non-blocking mode, true: blocking mode, false: non-blocking mode. |
Usage command demo:
ros2 topic pub --once /rm_driver/set_lift_height_cmd rm_ros_interfaces/msg/Liftheight "height: 0 speed: 10 block: true"Return command demo:
ros2 topic echo /rm_driver/set_lift_height_resultParameter description:
| Parameter | Type | Description |
|---|---|---|
std_msgs | bool | true: setting succeeded, false: setting failed. Return the error code from the driver terminal. |
Get the state of the lifting mechanism Liftstate.msg
| Parameter | Type | Description |
|---|---|---|
height | int16 | Target height, unit: mm, range: 0−2,600. |
current | int16 | Current current. |
err_flag | uint16 | Drive error code. |
Usage command demo:
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.
ros2 topic echo /rm_driver/get_lift_state_resultEnd 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
| Parameter | Type | Description |
|---|---|---|
data | int32 | 0 - 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:
ros2 topic pub /rm_driver/set_rm_plus_mode_cmd std_msgs/msg/Int32 "data: 0"Return command demo:
ros2 topic echo /rm_driver/set_rm_plus_mode_resultParameter description:
| Parameter | Type | Description |
|---|---|---|
std_msgs | bool | true: setting succeeded, false: setting failed. Return the error code from the driver terminal. |
Querying End Effector Ecosystem Protocol Mode
| Parameter | Type | Description |
|---|---|---|
std_msgs | String | ROS built-in msg. |
Usage command demo:
ros2 topic pub /rm_driver/get_rm_plus_mode_cmd std_msgs/msg/Empty "{}"Return command demo:
ros2 topic echo /rm_driver/get_rm_plus_mode_resultParameter description:
| Parameter | Type | Description |
|---|---|---|
std_msgs | int32 | 0 - 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
| Parameter | Type | Description |
|---|---|---|
data | int32 | 0 - Disable tactile sensor; 1 - Enable tactile sensor (returns processed data); 2 - Enable tactile sensor (returns raw data). |
Usage command demo:
ros2 topic pub /rm_driver/set_rm_plus_touch_cmd std_msgs::msg::Int32 "data: 0"Return command demo:
ros2 topic echo /rm_driver/set_rm_plus_touch_resultParameter description:
| Parameter | Type | Description |
|---|---|---|
std_msgs | bool | true: setting succeeded, false: setting failed. Return the error code from the driver terminal. |
Querying Tactile Sensor Mode
| Parameter | Type | Description |
|---|---|---|
std_msgs | String | ROS built-in msg. |
Usage command demo:
ros2 topic pub /rm_driver/get_rm_plus_touch_cmd std_msgs/msg/Empty "{}"Return command demo:
ros2 topic echo /rm_driver/get_rm_plus_touch_resultParameter description:
| Parameter | Type | Description |
|---|---|---|
std_msgs | int32 | 0 - 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
| Parameter | Type | Description |
|---|---|---|
std_msgs | Empty | Start the pass-through force-position hybrid control compensation mode. |
Usage command demo:
ros2 topic pub /rm_driver/start_force_position_move_cmd std_msgs/msg/Empty "{}"Return command demo:
ros2 topic echo /rm_driver/start_force_position_move_resultParameter description:
| Parameter | Type | Description |
|---|---|---|
std_msgs | bool | true: 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
| Parameter | Type | Description |
|---|---|---|
std_msgs | Empty | Stop the pass-through force-position hybrid control compensation mode. |
Usage command demo:
ros2 topic pub /rm_driver/stop_force_position_move_cmd std_msgs/msg/Empty "{}"Return command demo:
ros2 topic echo /rm_driver/stop_force_position_move_resultParameter description:
| Parameter | Type | Description |
|---|---|---|
std_msgs | bool | true: setting succeeded, false: setting failed. Return the error code from the driver terminal. |
Pass-through force-position hybrid control compensation — joint Forcepositionmovejoint.msg
| Parameter | Type | Description |
|---|---|---|
joint | float32[6] | Target joint radian. |
sensor | uint8 | Sensor type, 0: 1-DoF force, 1: 6-DoF force. |
mode | uint8 | Mode, 0: along the base frame, 1: along the end frame. |
dir | int16 | 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 | float32 | Magnitude of the force, in N. |
follow | bool | Follow state, true: high follow, false: low follow. |
dof | uint8 | Degree 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.
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
| Parameter | Type | Description |
|---|---|---|
pose | float | Target pose, including x, y, z coordinates (in m) + quaternion. |
sensor | uint8 | Sensor type, 0: 1-DoF force, 1: 6-DoF force. |
mode | uint8 | Mode, 0: along the base frame, 1: along the end frame. |
dir | int16 | 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 | float32 | Magnitude of the force, in N. |
follow | bool | Follow 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.
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
| Parameter | Type | Description |
|---|---|---|
cycle | uint16 | Set the broadcast cycle, in multiple of 5 ms (1 by default, i.e., 1*5=5 ms, or 200 Hz). |
port | uint16 | Set the broadcast port number (8089 by default). |
force_coordinate | uint16 | Set the frame for external force data (only supported by robotic arms with force sensors). |
ip | string | Set the custom pushing target IP address (192.168.1.10 by default). |
hand_enable | bool | Whether dexterous hand status reporting is enabled, true is enabled, and false is not enabled. |
aloha_state_enable | bool | Whether to enable aloha main arm status reporting, true to enable, false not to enable. |
arm_current_status_enable | bool | Whether to enable the status report of the robot arm, true to enable, false not to enable. |
expand_state_enable | bool | Whether to enable the report of extended joint related data, true is enabled, false is not enabled. |
joint_speed_enable | bool | Whether joint speed reporting is enabled, true is enabled, and false is not enabled. |
lift_state_enable | bool | Whether lifting joint data reporting is enabled, true is enabled, and false is not enabled. |
plus_base_enable | bool | Basic information of the end-effector device,true is enabled, and false is not enabled. |
plus_state_enable | bool | Real-time information of the end-effector device,true is enabled, and false is not enabled. |
Usage command demo:
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:
ros2 topic echo /rm_driver/set_realtime_push_resultParameter description:
| Parameter | Type | Description |
|---|---|---|
std_msgs | bool | true: 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
| Parameter | Type | Description |
|---|---|---|
std_msgs | String | ROS built-in msg. |
Usage command demo:
ros2 topic pub --once /rm_driver/get_realtime_push_cmd std_msgs/msg/Empty "{}"Return command demo:
ros2 topic echo /rm_driver/get_realtime_push_resultParameter description:
| Parameter | Type | Description |
|---|---|---|
cycle | uint16 | Set the broadcast cycle, in multiple of 5 ms (1 by default, i.e., 1*5=5 ms, or 200 Hz). |
port | uint16 | Set the broadcast port number (8089 by default). |
force_coordinate | uint16 | Set the frame for external force data (only supported by robotic arms with force sensors). |
ip | string | Set the custom pushing target IP address (192.168.1.10 by default). |
hand_enable | bool | Whether dexterous hand status reporting is enabled, true is enabled, and false is not enabled. |
aloha_state_enable | bool | Whether to enable aloha main arm status reporting, true to enable, false not to enable. |
arm_current_status_enable | bool | Whether to enable the status report of the robot arm, true to enable, false not to enable. |
expand_state_enable | bool | Whether to enable the report of extended joint related data, true is enabled, false is not enabled. |
joint_speed_enable | bool | Whether joint speed reporting is enabled, true is enabled, and false is not enabled. |
lift_state_enable | bool | Whether lifting joint data reporting is enabled, true is enabled, and false is not enabled. |
plus_base_enable | bool | Basic information of the end-effector device,true is enabled, and false is not enabled. |
plus_state_enable | bool | Real-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
| Parameter | Type | Description |
|---|---|---|
force_fx | float32 | Magnitude of the force along the X-axis. |
force_fy | float32 | Magnitude of the force along the Y-axis. |
force_fz | float32 | Magnitude of the force along the Z-axis. |
force_mx | float32 | Magnitude of the rotation force along the X-axis. |
force_my | float32 | Magnitude of the rotation force along the Y-axis. |
force_mz | float32 | Magnitude of the rotation force along the Z-axis. |
Usage command demo:
ros2 topic echo /rm_driver/udp_six_forceOne-axis force Oneforce.msg
| Parameter | Type | Description |
|---|---|---|
force_fx | float32 | Magnitude of the force along the X-axis. |
force_fy | float32 | Magnitude of the force along the Y-axis. |
force_fz | float32 | Magnitude of the force along the Z-axis. (only this value is valid) |
force_mx | float32 | Magnitude of the rotation force along the X-axis. |
force_my | float32 | Magnitude of the rotation force along the Y-axis. |
force_mz | float32 | Magnitude of the rotation force along the Z-axis. |
Usage command demo:
ros2 topic echo /rm_driver/udp_one_forceRobotic arm error std_msgs
| Parameter | Type | Description |
|---|---|---|
data | uint16 | Robotic arm error. |
Usage command demo:
ros2 topic echo /rm_driver/udp_arm_errSystem error std_msgs
| Parameter | Type | Description |
|---|---|---|
data | uint16 | System error. |
Usage command demo:
ros2 topic echo /rm_driver/udp_sys_errJoint error Jointerrorcode.msg
| Parameter | Type | Description |
|---|---|---|
joint_error | uint16 | Each joint error. |
dof | uint8 | Degree of freedom of the robotic arm. |
Usage command demo:
ros2 topic echo /rm_driver/udp_joint_error_codeRobotic arm radian data sensor_msgs
| Parameter | Type | Description |
|---|---|---|
sec | int32 | Time, in second. |
nanosec | uint32 | Time, in ns. |
frame_id | string | Frame name. |
name | string | Joint name. |
position | float64 | Joint radian. |
velocity | float64 | Joint velocity. |
effort | float64 | Joint force. |
Usage command demo:
ros2 topic echo /joint_statesPose geometry_msgs
| Parameter | Type | Description |
|---|---|---|
Point position | float64 | Current coordinates of the robotic arm: x, y, z. |
Quaternion orientation | float64 | Current orientation of the robotic arm: x, y, z, w. |
Usage command demo:
ros2 topic echo /rm_driver/udp_arm_positionExternal force data of the 6-DoF force sensor system Sixforce.msg
| Parameter | Type | Description |
|---|---|---|
force_fx | float32 | Magnitude of external force along the X-axis of the current sensor frame. |
force_fy | float32 | Magnitude of external force along the Y-axis of the current sensor frame. |
force_fz | float32 | Magnitude of external force along the Z-axis of the current sensor frame. |
force_mx | float32 | Magnitude of the rotation force along the X-axis of the current sensor frame. |
force_my | float32 | Magnitude of the rotation force along the Y-axis of the current sensor frame. |
force_mz | float32 | Magnitude of the rotation force along the Z-axis of the current sensor frame. |
Usage command demo:
ros2 topic echo /rm_driver/udp_six_zero_forceExternal force data of the one-axis force sensor system Oneforce.msg
| Parameter | Type | Description |
|---|---|---|
force_fx | float32 | Magnitude of external force along the X-axis of the current sensor frame. |
force_fy | float32 | Magnitude of external force along the Y-axis of the current sensor frame. |
force_fz | float32 | Magnitude of external force along the Z-axis of the current sensor frame. (only this data is valid) |
force_mx | float32 | Magnitude of the rotation force along the X-axis of the current sensor frame. |
force_my | float32 | Magnitude of the rotation force along the Y-axis of the current sensor frame. |
force_mz | float32 | Magnitude of the rotation force along the Z-axis of the current sensor frame. |
Usage command demo:
ros2 topic echo /rm_driver/udp_one_zero_forceReference frame for external force data std_msgs
| Parameter | Type | Description |
|---|---|---|
data | uint16 | Frame 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:
ros2 topic echo /rm_driver/udp_arm_coordinateThe current state of dexterous dexterity Handstatus.msg
| Parameter | Type | Description |
|---|---|---|
hand_angle | uint16[6] | Finger angle array,range:0~2000. |
hand_pos | uint16[6] | Finger position array,range:0~1000. |
hand_state | uint16[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_force | uint16[6] | Dexterous hand degree of freedom current,unit mN. |
hand_err | uint16 | Agile Hand System Error,1 indicates an error, 0 indicates no error. |
Usage command demo:
ros2 topic echo /rm_driver/udp_hand_statuscurrent status of the mechanical arm Armcurrentstatus.msg
| Parameter | Type | Description |
|---|---|---|
arm_current_status | uint16 | Mechanical 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:
ros2 topic echo /rm_driver/udp_arm_current_statusCurrent joint current Jointcurrent.msg
| Parameter | Type | Description |
|---|---|---|
joint_current | float32 | Current joint current with accuracy of 0.001mA. |
Usage command demo:
ros2 topic echo /rm_driver/udp_joint_currentThe current joint enabling state Jointenflag.msg
| Parameter | Type | Description |
|---|---|---|
joint_en_flag | bool | The current joint enabling state, where 1 is the upper enabling state and 0 is the lower enabling state. |
Usage command demo:
ros2 topic echo /rm_driver/udp_joint_en_flagEuler angle posture of mechanical arm Jointposeeuler.msg
| Parameter | Type | Description |
|---|---|---|
Euler | float32[3] | Euler angle of current waypoint attitude with accuracy of 0.001rad. |
position | float32[3] | Current waypoint position with accuracy of 0.000001M. |
Usage command demo:
ros2 topic echo /rm_driver/udp_joint_en_flagCurrent joint speed Jointspeed.msg
| Parameter | Type | Description |
|---|---|---|
joint_speed | float32 | Current joint speed with an accuracy of 0.02RPM. |
Usage command demo:
ros2 topic echo /rm_driver/udp_joint_speedCurrent joint temperature Jointtemperature.msg
| Parameter | Type | Description |
|---|---|---|
joint_temperature | float32 | current joint temperature with accuracy of 0.001℃. |
Usage command demo:
ros2 topic echo /rm_driver/udp_joint_temperatureCurrent joint voltage Jointvoltage.msg
| Parameter | Type | Description |
|---|---|---|
joint_voltage | float32 | current joint voltage with accuracy of 0.001V. |
Usage command demo:
ros2 topic echo /rm_driver/udp_joint_voltageReading Basic Information of End-Effector Device Rmplusbase.msg
| Parameter | Type | Description |
|---|---|---|
manu | string | Device manufacturer. |
type | int8 | Device type, including 1 - Two-finger gripper, 2 - Five-finger dexterous hand, 3 - Three-finger gripper. |
hv | string | Hardware version. |
sv | string | Software version. |
bv | string | Bootloader version. |
id | int32 | Device ID. |
dof | int8 | Degrees of freedom. |
check | int8 | Self-check switch. |
bee | int8 | Beeper switch. |
force | bool | Force control support. |
touch | bool | Tactile support. |
touch_num | int8 | Number of tactile sensors. |
touch_sw | int8 | Tactile switch. |
hand | int8 | Hand orientation, including 1 - Left hand, 2 - Right hand. |
pos_up | int32[12] | Position upper limit. |
pos_low | int32[12] | Position lower limit. |
angle_up | int32[12] | Angle upper limit. |
angle_low | int32[12] | Angle lower limit. |
speed_up | int32[12] | Speed upper limit. |
speed_low | int32[12] | Speed lower limit. |
force_up | int32[12] | Force upper limit. |
force_low | int32[12] | Force lower limit. |
Usage command demo:
ros2 topic echo /rm_driver/udp_rm_plus_baseReading Real-Time Information of End-Effector Device Rmplusstate.msg
| Parameter | Type | Description |
|---|---|---|
sys_state | int32 | System status. |
dof_state | int32[12] | Current status of each degree of freedom (DoF). |
dof_err | int32[12] | Error information of each DoF. |
pos | int32[12] | Current position of each DoF. |
speed | int32[12] | Current speed of each DoF. |
angle | int32[12] | Current angles of each DoF. |
current | int32[12] | Current of each DoF. |
normal_force | int32[18] | Normal force of the tactile three-dimensional force of each DoF. |
tangential_force | int32[18] | Tangential force of the tactile three-dimensional force of each DoF. |
tangential_force_dir | int32[18] | Direction of the tangential force of the tactile three-dimensional force of each DoF. |
tsa | int32[12] | Tactile self-approach of each DoF. |
tma | int32[12] | Tactile mutual approach of each DoF. |
touch_data | int32[18] | Raw data from the tactile sensor. |
force | int32[12] | Torque of each DoF. |
Usage command demo:
ros2 topic echo /rm_driver/udp_rm_plus_state
