ROS:
Call Robotic Arm JSON Protocol To facilitate users in controlling the robotic arm through ROS1, RealMan provides a JSON-based ROS1 package, which allows querying and controlling the robotic arm through ROS topics. In actual use of the robotic arm, users can establish communication and control the robotic arm through the Ethernet port.
System error code
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 |
18 | 0x1011 | Circular planning error |
19 | 0x1012 | Self-collision error |
20 | 0x1013 | Electronic fence collision error (reserved) |
21 | 0x5001 | Reserved |
22 | 0x5002 | Reserved |
23 | 0x5003 | Controller over-temperature |
24 | 0x5004 | Reserved |
25 | 0x5005 | Controller overcurrent |
26 | 0x5006 | Controller undercurrent |
27 | 0x5007 | Controller overvoltage |
28 | 0x5008 | Controller undervoltage |
29 | 0x5009 | Real-time layer communication error |
Joint error code
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 |
Set the joint enabling state Joint_Enable.msg
Parameter description:
Parameter | Type | Description |
---|---|---|
joint_num | uint8 | Corresponding joint number, from the base to the robotic arm's gripper. The joint numbers for the 6-DoF are sequentially 1 to 6, and those for the 7-DoF are sequentially 1 to 7. |
state | bool | true: enable, false: disable |
Usage command demo:
rostopic pub /rm_driver/Joint_Enable rm_msgs/Joint_Enable "joint_num: 1 state: true"
Return command demo:
rostopic echo /rm_driver/Joint_En_State_Result
Parameter description:
Parameter | Type | Description |
---|---|---|
std_msgs | bool | true: setting succeeded, false: setting failed. |
Change the current tool frame ChangeTool_Name.msg
Parameter description:
Parameter | Type | Description |
---|---|---|
std_msgs | String | ROS built-in msg. |
Usage command demo:
rostopic pub /rm_driver/ChangeToolName_Cmd rm_msgs/ChangeTool_Name "toolname: '6WM'"
Return command demo:
rostopic echo /rm_driver/ChangeTool_State
Parameter description:
Parameter | Type | Description |
---|---|---|
std_msgs | bool | true: setting succeeded, false: setting failed. |
Change the current work frame ChangeWorkFrame_Name.msg
Parameter description:
Parameter | Type | Description |
---|---|---|
std_msgs | String | ROS built-in msg. |
Usage command demo:
rostopic pub /rm_driver/ChangeWorkFrame_Cmd rm_msgs/ChangeWorkFrame_Name "WorkFrame_name: 'Base'"
Return command demo:
rostopic echo /rm_driver/ChangeWorkFrame_State
Parameter description:
Parameter | Type | Description |
---|---|---|
std_msgs | bool | true: setting succeeded, false: setting failed. |
Get the current work frame
Parameter description:
Parameter | Type | Description |
---|---|---|
std_msgs | Empty | ROS built-in msg. |
Usage command demo:
rostopic pub /rm_driver/GetTotalWorkFrame std_msgs/Empty "{}"
Return value check: check according to the printed information from the rm_driver node.
Get the current joint current of the robotic arm Joint_Current.msg
Parameter description:
Parameter | Type | Description |
---|---|---|
std_msgs | String | ROS built-in msg. |
Usage command demo:
rostopic pub /rm_driver/GetCurrentJointCurrent std_msgs/Empty "{}"
Return command demo:
rostopic echo /rm_driver/Joint_Current
Parameter description:
Parameter | Type | Description |
---|---|---|
joint_current | float32[] | Joint current (in uA) |
Robotic arm motion planning
Joint motion in space MoveJ.msg
Parameter description:
Parameter | Type | Description |
---|---|---|
joint | float32[] | Joint angle, in rad. |
speed | float32 | Speed ratio, 0-1. |
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. |
Usage command demo:
6-DoF robotic arm
rostopic pub /rm_driver/MoveJ_Cmd rm_msgs/MoveJ "joint: [0, 0, 0, 0, 0, 0] speed: 0.2 trajectory_connect: 0"
7-DoF robotic arm
rostopic pub /rm_driver/MoveJ_Cmd rm_msgs/MoveJ "joint: [0, 0, 0, 0, 0, 0, 0] speed: 0.2 trajectory_connect: 0"
Return command demo:
rostopic echo /rm_driver/Plan_State
Parameter description:
Parameter | Type | Description |
---|---|---|
std_msgs | bool | true: setting succeeded, false: setting failed. |
Cartesian-space linear motionMoveL.msg
Parameter description:
Parameter | Type | Description |
---|---|---|
Pose | geometry_msgs/Pose | Robotic arm pose, including x, y, z coordinates (float type, in m) + quaternion. |
speed | float32 | Speed ratio, 0-1. |
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. |
Usage command demo:
rostopic pub /rm_driver/MoveL_Cmd rm_msgs/MoveL "Pose:
position:
x: 0.0
y: 0.0
z: 0.0
orientation:
x: 0.0
y: 0.0
z: 0.0
w: 0.0
speed: 0.2
trajectory_connect: 0"
Return command demo:
rostopic echo /rm_driver/Plan_State
Parameter description:
Parameter | Type | Description |
---|---|---|
std_msgs | bool | true: setting succeeded, false: setting failed. |
Cartesian-space circular motionMoveC.msg
Parameter description:
Parameter | Type | Description |
---|---|---|
Mid_Pose | geometry_msgs/Pose | Middle pose, including x, y, z coordinates (float type, in m) + quaternion. |
End_Pose | geometry_msgs/Pose | End pose, including x, y, z coordinates (float type, in m) + quaternion. |
speed | float32 | Speed ratio, 0-1. |
loop | uint16 | Number of rotations. |
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. |
Usage command demo:
rostopic pub /rm_driver/MoveC_Cmd rm_msgs/MoveC "Mid_Pose:
position:
x: 0.2949
y: 0.1377
z: 0.1048
orientation:
x: 0.05
y: -0.989
z: -0.1359
w: 0.0274
End_Pose:
position:
x: 0.2417
y: 0.0
z: 0.1213
orientation:
x: 0.0136
y: 0.9993
z: 0.0241
w: 0.0261
speed: 0.5
loop: 0
trajectory_connect: 0"
Return command demo:
rostopic echo /rm_driver/Plan_State
Parameter description:
Parameter | Type | Description |
---|---|---|
std_msgs | bool | true: setting succeeded, false: setting failed. |
Joint angle CANFD pass-throughJointPos.msg
Parameter description:
Parameter | Type | Description |
---|---|---|
joint | float32[] | Joint angle, in rad. |
expand | float32 | Expansion angle, in rad. |
Usage command demo: Pass-through requires continuously sending multiple consecutive points to achieve the functionality. Simply relying on the following command will not accomplish the task. Currently, moveit control uses an angle pass-through control method.
rostopic pub /rm_driver/JointPos rm_msgs/JointPos "joint: [0, 0, 0, 0, 0, 0] expand: 0.0"
Return parameter description: Succeeded: no return value; failed: return the error code from the driver terminal.
Custom High-Following Mode Joint Angle CANFD Transparent Transmission JointPosCustom.msg
Parameter description:
Parameter | Type | Description |
---|---|---|
joint | float32[] | Joint angles, unit: radians. |
expand | float32 | Extended joint, unit: radians. |
follow | bool | Motion following effect of the driver, true for high following, false for low following. |
trajectory_mode | uint8 | Under high-following mode, supports multiple modes: 0 - Full transparent transmission mode, 1 - Curve fitting mode, 2 - Filtering mode. |
radio | uint8 | Sets the smoothing coefficient under curve fitting mode (range 0-100) or the filtering parameter under filtering mode (range 0-1000), higher values indicate better smoothing effects. |
Usage command demo: Transparent transmission requires continuous sending of multiple consecutive points to be realized. The function cannot be achieved solely by the following command. The current moveit control uses the angle transparent transmission control method.
rostopic pub /rm_driver/MoveJ_Fd_Custom_Cmd rm_msgs/JointPosCustom
"joint: [0, 0, 0, 0, 0, 0]
expand: 0.0
follow: false
trajectory_mode: 0
radio: 0"
Return parameter description: Succeeded: no return value; failed: return the error code from the driver terminal.
Pose CANFD pass-throughCartePos.msg
Parameter description:
Parameter | Type | Description |
---|---|---|
Pose | geometry_msgs/Pose | Pass-through pose, including x, y, z coordinates (float type, in m) + quaternion. |
Usage command demo: A large number of consecutive points (more than 10) are required. Simply relying on the following command will not accomplish the task. It needs to continuously publish with a cycle of at least 2 ms.
rostopic pub /rm_driver/MoveP_Fd_Cmd rm_msgs/CartePos
"Pose:
position:
x: 0.0
y: 0.0
z: 0.0
orientation:
x: 0.0
y: 0.0
z: 0.0
w: 0.0"
Return parameter description: Succeeded: no return value; failed: return the error code from the driver terminal.
Custom High-Following Mode Pose CANFD Transparent Transmission CartePosCustom.msg
Parameter description:
Parameter | Type | Description |
---|---|---|
Pose | geometry_msgs/Pose | The transparent transmission pose, of type geometry_msgs/Pose, includes x, y, z coordinates (float type, unit: meters) + quaternion. |
follow | bool | Motion following effect of the driver, true for high following, false for low following. |
trajectory_mode | uint8 | Under high-following mode, supports multiple modes: 0 - Full transparent transmission mode, 1 - Curve fitting mode, 2 - Filtering mode. |
radio | uint8 | Sets the smoothing coefficient under curve fitting mode (range 0-100) or the filtering parameter under filtering mode (range 0-1000), higher values indicate better smoothing effects. |
Usage command demo: It requires a large number (more than 10) of continuously positioned points. The function cannot be achieved solely by the following command. It should be published continuously at a period of more than 2ms.
rostopic pub /rm_driver/MoveP_Fd_Custom_Cmd rm_msgs/CartePosCustom
"Pose:
position:
x: 0.0
y: 0.0
z: 0.0
orientation:
x: 0.0
y: 0.0
z: 0.0
w: 0.0
follow: false
trajectory_mode: 0
radio: 0"
Return parameter description: Succeeded: no return value; failed: return the error code from the driver terminal.
Joint space planning to target orientationMoveJ_P.msg
Parameter description:
Parameter | Type | Description |
---|---|---|
Pose | geometry_msgs/Pose | Target pose, including x, y, z coordinates (float type, in m) + quaternion. |
speed | float32 | Speed ratio, 0-1. |
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. |
Usage command demo:
rostopic pub /rm_driver/MoveJ_P_Cmd rm_msgs/MoveJ_P
"Pose:
position:
x: 0.0
y: 0.0
z: 0.0
orientation:
x: 0.0
y: 0.0
z: 0.0
w: 0.0
speed: 0.0
trajectory_connect: 0"
Return command demo:
rostopic echo /rm_driver/Plan_State
Parameter description:
Parameter | Type | Description |
---|---|---|
std_msgs | bool | true: setting succeeded, false: setting failed. |
Robotic arm motion configuration - step command
Joint stepJoint_Step.msg
Parameter description:
Parameter | Type | Description |
---|---|---|
joint_num | uint8 | Joint to be moved. |
step_angle | float32 | Step angle (in °). |
speed | float32 | Motion speed. |
Usage command demo: 6-DoF robotic arm
rostopic pub /rm_driver/SetJointStep rm_msgs/Joint_Step "joint_num: 6 step_angle: 90.0 speed: 0.2"
7-DoF robotic arm
rostopic pub /rm_driver/SetJointStep rm_msgs/Joint_Step "joint_num: 7 step_angle: 90.0 speed: 0.2"
Return command demo:
rostopic echo /rm_driver/Plan_State
Parameter description:
Parameter | Type | Description |
---|---|---|
std_msgs | bool | true: setting succeeded, false: setting failed. |
Robotic arm motion configuration - motion command
Quick stopStop.msg
Parameter description:
Parameter | Type | Description |
---|---|---|
std_msgs | String | / |
Usage command demo:
rostopic pub /rm_driver/Emergency_Stop std_msgs/Empty "{}"
Return command demo:
rostopic echo /rm_driver/Set_Arm_Stop_Result
Parameter description:
Parameter | Type | Description |
---|---|---|
std_msgs | bool | true: setting succeeded, false: setting failed. |
Robotic arm motion configuration - teaching command class
Joint teachingJoint_Teach.msg
Parameter description:
Parameter | Type | Description |
---|---|---|
teach_joint | int16 | Teaching control joint |
direction | string | Joint rotation direction, "pos": positive direction, "neg": negative direction |
v | int16 | Joint rotation speed, 0-100 |
Usage command demo:
rostopic pub /rm_driver/Arm_JointTeach rm_msgs/Joint_Teach "teach_joint: 1 direction: 'pos' v: 20"
Return command demo:
rostopic echo /rm_driver/SetJointTeach_Result
Parameter description:
Parameter | Type | Description |
---|---|---|
std_msgs | bool | true: setting succeeded, false: setting failed. |
Position teachingPos_Teach.msg
Parameter description:
Parameter | Type | Description |
---|---|---|
teach_type | string | Coordinate axis, "x", "y", "z" |
direction | string | Teaching direction, "pos": positive direction, "neg": negative direction |
v | int16 | Joint rotation speed, 0-100 |
Usage command demo:
rostopic pub /rm_driver/Arm_PosTeach rm_msgs/Pos_Teach "teach_type: 'z' direction: 'pos' v: 10"
Return command demo:
rostopic echo /rm_driver/SetPosTeach_Result
Parameter description:
Parameter | Type | Description |
---|---|---|
std_msgs | bool | true: setting succeeded, false: setting failed. |
Orientation teachingOrt_Teach.msg
Parameter description:
Parameter | Type | Description |
---|---|---|
teach_type | string | Rotation axis, "rx", "ry", "rz" |
direction | string | Teaching direction, "pos": positive direction, "neg": negative direction |
v | int16 | Joint rotation speed, 0-100 |
Usage command demo:
rostopic pub /rm_driver/Arm_OrtTeach rm_msgs/Ort_Teach "teach_type: 'rz' direction: 'pos' v: 10"
Return command demo:
rostopic echo /rm_driver/SetOrtTeach_Result
Parameter description:
Parameter | Type | Description |
---|---|---|
std_msgs | bool | true: setting succeeded, false: setting failed. |
Stop teachingStop_Teach.msg
Parameter description:
Parameter | Type | Description |
---|---|---|
command | string | Stop command "set_stop_teach", execute the following command to stop |
Usage command demo:
rostopic pub /rm_driver/Arm_StopTeach rm_msgs/Stop_Teach "command: ''"
Return command demo:
rostopic echo /rm_driver/SetStopTeach_Result
Parameter description:
Parameter | Type | Description |
---|---|---|
std_msgs | bool | true: setting succeeded, false: setting failed. |
System configuration
Control the power on/off of the robotic arm
Parameter description:
Parameter | Type | Description |
---|---|---|
data | Byte | 1: Power on the robotic arm, 0: Power off the robotic arm |
Usage command demo:
rostopic pub /rm_driver/SetArmPower std_msgs/Byte "data: 0"
Return command demo:
rostopic echo /rm_driver/Set_Arm_Power_Result
Parameter description:
Parameter | Type | Description |
---|---|---|
std_msgs | bool | true: setting succeeded, false: setting failed. |
Read the software version number Arm_Software_Version.msg
Parameter description:
Parameter | Type | Description |
---|---|---|
std_msgs | String | ROS built-in msg. |
Usage command demo:
rostopic pub /rm_driver/Get_Arm_Software_Version std_msgs/Empty "{}"
Return command demo:
rostopic echo /rm_driver/Get_Arm_Software_Version_Result
Parameter description:
Parameter | Type | Description |
---|---|---|
Product_version | string | Robotic arm type. |
Plan_version | string | Software version number. |
Clear system errors
Parameter description:
Parameter | Type | Description |
---|---|---|
std_msgs | Empty | ROS built-in msg. |
Usage command demo:
rostopic pub /rm_driver/Clear_System_Err std_msgs/Empty "{}"
Return command demo:
rostopic echo /rm_driver/System_En_State_Result
Parameter description:
Parameter | Type | Description |
---|---|---|
std_msgs | bool | true: setting succeeded, false: setting failed. |
Get the robotic arm state
Get the current joint current of the robotic armJoint_Current.msg
Parameter description:
Parameter | Type | Description |
---|---|---|
std_msgs | Empty | ROS built-in msg. |
Usage command demo:
rostopic pub /rm_driver/GetCurrentJointCurrent std_msgs/Empty "{}"
Return command demo:
rostopic echo /rm_driver/Joint_Current
Parameter description:
Parameter | Type | Description |
---|---|---|
joint_current | float32[] | Joint current (in uA) |
Get the joint angle of the robotic arm
Parameter description:
Parameter | Type | Description |
---|---|---|
std_msgs | Empty msg | ROS built-in msg. |
Usage command demo:
rostopic pub /rm_driver/GetArmJoint_Cmd std_msgs/Empty "{}"
Return command demo:
rostopic echo /joint_states
Parameter description:
Parameter | Type | Description |
---|---|---|
sensor_msgs | JointState | / |
Get the robotic arm state (radian + quaternion)GetArmState_Command.msg
Parameter description:
Parameter | Type | Description |
---|---|---|
command | string | / |
Usage command demo:
rostopic pub /rm_driver/GetArmState_Cmd rm_msgs/GetArmState_Command "command: ''"
Return command demo:
rostopic echo /rm_driver/ArmCurrentState
Parameter description:
Parameter | Type | Description |
---|---|---|
joint | float32[] | Radian of the robotic arm |
Pose | geometry_msgs/Pose | Current pose of the robotic arm (quaternion) |
arm_err | bool | Robotic arm error |
sys_err | bool | System error |
dof | bool | Degree of freedom of the robotic arm |
Get the robotic arm state (angle + Euler angle)GetArmState_Command.msg
Parameter description:
Parameter | Type | Description |
---|---|---|
command | string | / |
Usage command demo:
rostopic pub /rm_driver/GetArmState_Cmd rm_msgs/GetArmState_Command "command: ''"
Return command demo:
rostopic echo /rm_driver/Arm_Current_State
Parameter description:
Parameter | Type | Description |
---|---|---|
joint | float32[] | Angle of the robotic arm |
Pose | float32[6] | Current pose of the robotic arm (Euler angle) |
arm_err | uint16 | Robotic arm error |
sys_err | uint16 | System error |
dof | bool | Degree of freedom of the robotic arm |
Controller IO configuration and acquisition
Set the digital IO output state of the robotic armArm_Digital_Output.msg
Parameter description:
Parameter | Type | Description |
---|---|---|
num | uint8 | IO port number, range: 1-4 |
state | bool | “state”: IO state, 1: high output, 0: low output |
Usage command demo:
rostopic pub /rm_driver/Arm_Digital_Output rm_msgs/Arm_Digital_Output "num: 1 state: true"
Return command demo:
rostopic echo /rm_driver/Set_DO_State_Result
Parameter description:
Parameter | Type | Description |
---|---|---|
std_msgs | Bool | true: setting succeeded, false: setting failed. |
Get all IO input statesIO_Update.msg
Parameter description:
Parameter | Type | Description |
---|---|---|
type | int8 | 1: Get controller IO state; 2: Get tool-end IO state |
Usage command demo:
rostopic pub /rm_driver/IO_Update rm_msgs/IO_Update "type: 1"
Return command demo:
rostopic echo /rm_driver/Arm_IO_State
Parameter description:
Parameter | Type | Description |
---|---|---|
Arm_Digital_Input | nt8[4] | 0: low, 1: high, -1: output |
Tool-end IO configuration and acquisition
Set tool-end digital IO output stateTool_Digital_Output.msg
Parameter description:
Parameter | Type | Description |
---|---|---|
num | uint8 | IO port number, range: 1-4 |
state | bool | “state”: IO state, 1: high output, 0: low output |
Usage command demo:
rostopic pub /rm_driver/Tool_Digital_Output rm_msgs/Tool_Digital_Output "num: 1 state: true"
Return command demo:
rostopic echo /rm_driver/Set_Tool_DO_State_Result
Parameter description:
Parameter | Type | Description |
---|---|---|
std_msgs | Bool | true: setting succeeded, false: setting failed. |
Get tool-end digital IO stateIO_Update.msg
Parameter description:
Parameter | Type | Description |
---|---|---|
type | uint8 | 1: Get controller IO state; 2: Get tool-end IO state |
Usage command demo:
rostopic pub /rm_driver/IO_Update rm_msgs/IO_Update "type: 2"
Return command demo:
rostopic echo /rm_driver/Tool_IO_State
Parameter description:
Parameter | Type | Description |
---|---|---|
Tool_IO_Mode | bool[2] | Digital I/O input/output state, 0: input mode, 1: output mode |
Tool_IO_State | bool[2] | Digital I/O level state 0: Low, 1: High |
Control of the end effector gripper (optional)
The RealMan robotic arm is equipped with the INSPIRE-ROBOTS EG2-4C2 gripper at the end effector. To facilitate user operation of the gripper, the robotic arm controller has adapted the gripper for ROS-based control.
Set the continuous force-controlled grasping of the gripper Gripper_Pick.msg
The gripper controls the gripping force at a set speed, and stops moving when the applied force exceeds the preset limit
Parameter description:
Parameter | Type | Description |
---|---|---|
speed | uint16 | Range: 1-1000, representing the gripper opening and closing speed, without unit of measurement |
force | uint16 | Range: 1-1000, representing the gripping force of the gripper, with a maximum of 1.5 kg |
Usage command demo:
rostopic pub /rm_driver/Gripper_Pick_On rm_msgs/Gripper_Pick "speed: 100 force: 100"
Return command demo:
rostopic echo /rm_driver/Set_Gripper_Result
Parameter description:
Parameter | Type | Description |
---|---|---|
std_msgs | Bool | true: setting succeeded, false: setting failed. |
Set the force-controlled grasping of the gripper Gripper_Pick.msg
The gripper controls the gripping force at a set speed, and stops moving when the applied force exceeds the preset limit.
Parameter description:
Parameter | Type | Description |
---|---|---|
speed | uint16 | Range: 1-1000, representing the gripper opening and closing speed, without unit of measurement |
force | uint16 | Range: 1-1000, representing the gripping force of the gripper, with a maximum of 1.5 kg |
Usage command demo:
rostopic pub /rm_driver/Gripper_Pick rm_msgs/Gripper_Pick "speed: 100 force: 100"
Return command demo:
rostopic echo /rm_driver/Set_Gripper_Result
Parameter description:
Parameter | Type | Description |
---|---|---|
std_msgs | Bool | true: setting succeeded, false: setting failed. |
Set the gripper to a given positionGripper_Set.msg
Set the gripper to a fixed position. The gripper should stop either once it reaches the position or when the force exceeds the threshold.
Parameter description:
Parameter | Type | Description |
---|---|---|
position | uint16 | Gripper target position, range: 1-1.000, representing the gripper opening: 0-70 mm |
Usage command demo:
rostopic pub /rm_driver/Gripper_Set rm_msgs/Gripper_Set "position: 100"
Return command demo:
rostopic echo /rm_driver/Set_Gripper_Result
Parameter description:
Parameter | Type | Description |
---|---|---|
std_msgs | Bool | true: setting succeeded, false: setting failed. |
Use of end effector s6-DoF force sensor (optional)
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.
Get the 6-DoF force data Six_Force.msg
Parameter description:
Parameter | Type | Description |
---|---|---|
std_msgs | Empty msg | ROS built-in msg. |
Usage command demo:
rostopic pub /rm_driver/GetSixForce_Cmd std_msgs/Empty "{}"
Return command demo:
rostopic echo /rm_driver/GetSixForce #Original 6-DoF force state
rostopic echo /rm_driver/SixZeroForce #6-DoF force state in the sensor frame
rostopic echo /rm_driver/WorkZeroForce #Sensor data in the work frame
rostopic echo /rm_driver/ToolZeroForce #Sensor data in the tool frame
Parameter description:
Parameter | Type | Description |
---|---|---|
force_Fx | float32 | / |
force_Fy | float32 | / |
force_Fz | float32 | / |
force_Mx | float32 | / |
force_My | float32 | / |
force_Mz | float32 | / |
Clear the 6-DoF force data
Parameter description:
Parameter | Type | Description |
---|---|---|
std_msgs | Empty | / |
Usage command demo:
rostopic pub /rm_driver/ClearForceData_Cmd std_msgs/Empty "{}"
Return command demo:
rostopic echo /rm_driver/ClearForceData_Result
Parameter description:
Parameter | Type | Description |
---|---|---|
std_msgs | Bool | true: setting succeeded, false: setting failed. |
Automatically set 6-DoF force center of gravity parameters
Parameter description:
Parameter | Type | Description |
---|---|---|
std_msgs | Empty | ROS built-in msg. |
Usage command demo:
rostopic pub /rm_driver/SetForceSensor_Cmd std_msgs/Empty "{}"
Return command demo:
rostopic echo /rm_driver/ForceSensorSet_Result
Parameter description:
Parameter | Type | Description |
---|---|---|
std_msgs | Bool | true: setting succeeded, false: setting failed. |
Manually calibrate 6-DoF force data Manual_Set_Force_Pose.msg
Parameter description:
Parameter | Type | Description |
---|---|---|
pose | string | Pose 1 joint angle; Pose 2 joint angle; Pose 3 joint angle; Pose 4 joint angle. |
joint | int64[] | Accuracy: 0.001°, e.g., 90°: 90000. |
Warning
The four poses must be issued in sequence. Once pose4 is set, the robotic arm will move to the given pose.
Usage command demo:
rostopic pub /rm_driver/ManualSetForcePose_Cmd rm_msgs/Manual_Set_Force_Pose "pose: ' pose1' joint: [0, 0, 0, 0, 90000, 0]"
Return command demo:
rostopic echo /rm_driver/ForceSensorSet_Result
Parameter description:
Parameter | Type | Description |
---|---|---|
std_msgs | Bool | true: setting succeeded, false: setting failed. |
Stop calibrating the center of gravity of the force sensor
Parameter description:
Parameter | Type | Description |
---|---|---|
std_msgs | Empty | ROS built-in msg. |
Usage command demo:
rostopic pub /rm_driver/StopSetForceSensor_Cmd std_msgs/Empty "{}"
Return command demo:
rostopic echo /rm_driver/StopSetForceSensor_Result
Parameter description:
Parameter | Type | Description |
---|---|---|
std_msgs | Bool | true: setting succeeded, false: setting failed. |
Drag teaching
Stop the drag teaching
Parameter description:
Parameter | Type | Description |
---|---|---|
std_msgs | Empty | ROS built-in msg. |
Usage command demo:
rostopic pub /rm_driver/StartMultiDragTeach_result std_msgs/Empty "{}"
Return command demo:
rostopic echo /rm_driver/StopDragTeach_Result
Parameter description:
Parameter | Type | Description |
---|---|---|
std_msgs | Bool | true: setting succeeded, false: setting failed. |
Enable multiple drag teaching Start_Multi_Drag_Teach.msg
Parameter description:
Parameter | Type | Description |
---|---|---|
mode | uint8 | 0: current loop mode. 1: position-only drag in the 6-DoF force mode, 2: orientation-only drag in the 6-DoF force mode, 3: position-orientation drag in the 6-DoF force mode |
Usage command demo:
rostopic pub /rm_driver/StartMultiDragTeach_Cmd rm_msgs/Start_Multi_Drag_Teach "mode: 0"
Return command demo:
rostopic echo /rm_driver/StartMultiDragTeach_Result
Parameter description:
Parameter | Type | Description |
---|---|---|
std_msgs | Bool | true: setting succeeded, false: setting failed. |
Force-position hybrid controlSet_Force_Position.msg
Parameter description:
Parameter | Type | Description |
---|---|---|
sensor | uint8 | Sensor, 0: 1-DoF force, 1: 6-DoF force |
mode | uint8 | 0: force control in the work 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 force, unit 0.1N |
Usage command demo:
rostopic pub /rm_driver/SetForcePosition_Cmd rm_msgs/Set_Force_Position "sensor: 0 mode: 0 direction: 0 N: 0"
Return command demo:
rostopic echo /rm_driver/SetForcePosition_Result
Parameter description:
Parameter | Type | Description |
---|---|---|
std_msgs | Bool | true: setting succeeded, false: setting failed. |
Stop the force-position hybrid control
Parameter description:
Parameter | Type | Description |
---|---|---|
std_msgs | Empty | ROS built-in msg. |
Usage command demo:
rostopic pub /rm_driver/StopForcePostion_Cmd std_msgs/Empty "{}"
Return command demo:
rostopic echo /rm_driver/StopForcePostion_Result
Parameter description:
Parameter | Type | Description |
---|---|---|
std_msgs | Bool | true: setting succeeded, false: setting failed. |
Modbus Mode Configuration and Register Read/Write
Setting RS485 Baud Rate
Parameter description:
Parameter | Type | Description |
---|---|---|
data | uint32 | Available baud rates: 9600, 19200, 38400, 115200, and 460800. If the user sets any other value, the controller will default to 460800. |
Usage command demo:
rostopic pub /rm_driver/Set_RS485 std_msgs/UInt32 "data: 115200"
Querying Controller RS485 Mode (Gen 3 Controller)Controller_RS485_Mode.msg
Parameter description:
Parameter | Type | Description |
---|---|---|
std_msgs | Empty | ROS built-in msg. |
Usage command demo:
rostopic pub /rm_driver/Get_Controller_RS485_Mode std_msgs/Empty "{}"
Return command demo:
rostopic echo /rm_driver/Get_Controller_RS485_Mode_Result
Parameter description:
Parameter | Type | Description |
---|---|---|
controller_RS485_mode | uint8 | Controller RS485 mode: 0 for default RS485 serial communication, 1 for Modbus-RTU master mode, 2 for Modbus-RTU slave mode. |
tool_RS485_mode | uint8 | Tool end RS485 mode, currently invalid. |
baudrate | uint32 | Baud rate. |
modbus_timeout | uint32 | Modbus protocol timeout time, in units of 100ms. This field is only provided in Modbus-RTU mode. |
Querying Tool End RS485 Mode (Gen 3 Controller) Tool_RS485_Mode.msg
Parameter description:
Parameter | Type | Description |
---|---|---|
std_msgs | Empty | ROS built-in msg. |
Usage command demo:
rostopic pub /rm_driver/Get_Tool_RS485_Mode std_msgs/Empty "{}"
Return command demo:
rostopic echo /rm_driver/Get_Tool_RS485_Mode_Result
Parameter description:
Parameter | Type | Description |
---|---|---|
controller_RS485_mode | uint8 | Controller RS485 mode, currently invalid. |
tool_RS485_mode | uint8 | Tool end RS485 mode: 0 for default RS485 serial communication, 1 for Modbus-RTU master mode, 2 for Modbus-RTU slave mode. |
baudrate | uint32 | Baud rate. |
modbus_timeout | uint32 | Modbus protocol timeout time, in units of 100ms. This field is only provided in Modbus-RTU mode. |
Configuring Communication Port for ModbusRTU Mode Set_Modbus_Mode.msg
Parameter description:
Parameter | Type | Description |
---|---|---|
port | uint8 | Communication port: 0 - Controller RS485 port as RTU master, 1 - End-effector interface board RS485 port as RTU master, 2 - Controller RS485 port as RTU slave. |
baudrate | uint32 | Baud rate, supports three common baud rates: 9600, 115200, 460800. |
timeout | uint32 | Timeout time, in units of 100ms. For all read/write commands to Modbus devices, if no response data is returned within the specified timeout period, a timeout error message will be returned. The timeout time cannot be 0; if set to 0, the robot arm will be configured as 1. |
ip | string | Currently invalid. |
Usage command demo:
rostopic pub /rm_driver/Set_Modbus_Mode rm_msgs/Set_Modbus_Mode "{port: 0, baudrate: 9600, timeout: 1, ip: '192.168.1.100'}"
Return command demo:
rostopic echo /rm_driver/Set_Modbus_Mode_Result
Parameter description:
Parameter | Type | Description |
---|---|---|
std_msgs | Bool | true : Configuration successful; false : Configuration failed. |
Closing Communication Port for ModbusRTU Mode
Parameter description:
Parameter | Type | Description |
---|---|---|
data | uint8 | Communication port: 0 - Controller RS485 port as RTU master, 1 - End-effector interface board RS485 port as RTU master, 2 - Controller RS485 port as RTU slave. |
Usage command demo:
rostopic pub /rm_driver/Close_Modbus_Mode std_msgs/UInt8 "data: 0"
Return command demo:
rostopic echo /rm_driver/Close_Modbus_Mode_Result
Parameter description:
Parameter | Type | Description |
---|---|---|
std_msgs | Bool | true : Configuration successful; false : Configuration failed. |
Configuring Connection to ModbusTCP Slave (Gen 3 Controller)Set_Modbus_Mode.msg
Parameter description:
Parameter | Type | Description |
---|---|---|
port | uint8 | Slave port number. |
baudrate | uint32 | Currently invalid, baud rate, supports three common baud rates: 9600, 115200, 460800. |
timeout | uint32 | Timeout time, in units of 100ms. For all read/write commands to Modbus devices, if no response data is returned within the specified timeout period, a timeout error message will be returned. The timeout time cannot be 0; if set to 0, the robot arm will be configured as 1. |
ip | string | Slave IP address. |
Usage command demo:
rostopic pub /rm_driver/Set_Modbustcp_Mode rm_msgs/Set_Modbus_Mode
"port: 502
baudrate: 0 #(not effective)
timeout: 1
ip: '192.168.1.18'"
Return command demo:
rostopic echo /rm_driver/Set_Modbustcp_Mode_Result
Parameter description:
Parameter | Type | Description |
---|---|---|
std_msgs | Bool | true : Configuration successful; false : Configuration failed. |
Closing Connection to ModbusTCP Slave (Gen 3 Controller)
Parameter description:
Parameter | Type | Description |
---|---|---|
std_msgs | Empty | ROS built-in msg. |
Usage command demo:
rostopic pub /rm_driver/Close_Modbustcp_Mode std_msgs/Empty "{}"
Return command demo:
rostopic echo /rm_driver/Close_Modbustcp_Mode_Result
Parameter description:
Parameter | Type | Description |
---|---|---|
std_msgs | Bool | true : Configuration successful; false : Configuration failed. |
Reading Coils Read_Register.msg
Parameter description:
Parameter | Type | Description |
---|---|---|
port | uint8 | Communication port: 0 - Controller RS485 port, 1 - End-effector interface board RS485 port, 3 - Controller ModbusTCP connection to external slave port. |
address | uint32 | Starting address of the coil. |
num | uint32 | Number of coils to read. This command supports reading up to 8 coils at once, meaning the returned data will not exceed one byte. |
device | uint32 | Peripheral device address. |
Usage command demo:
rostopic pub /rm_driver/Read_Coils rm_msgs/Read_Register "port: 0 address: 0 num: 1 device: 1"
Return command demo:
rostopic echo /rm_driver/Read_Coils_Result
Parameter description:
Parameter | Type | Description |
---|---|---|
data | uint16[] | Returned data. |
state | bool | Status information. |
Reading Multiple Coils Read_Register.msg
Parameter description:
Parameter | Type | Description |
---|---|---|
port | uint8 | Communication port: 0 - Controller RS485 port, 1 - End-effector interface board RS485 port, 3 - Controller ModbusTCP connection to external slave port. |
address | uint32 | Starting address of the coil. |
num | uint32 | Number of coils to read, 8 <= num <= 120. This command supports reading up to 120 coils at once, meaning 15 bytes of data. |
device | uint32 | Peripheral device address. |
Usage command demo:
rostopic pub /rm_driver/Read_Multiple_Coils rm_msgs/Read_Register "port: 0 address: 0 num: 0 device: 0"
Return command demo:
rostopic echo /rm_driver/ Read_Multiple_Coils_Result
Parameter description:
Parameter | Type | Description |
---|---|---|
data | uint16[] | Returned data. |
state | bool | Status information. |
Writing a Single Coil Write_Register.msg
Parameter description:
Parameter | Type | Description |
---|---|---|
port | uint8 | Communication port: 0 - Controller RS485 port, 1 - End-effector interface board RS485 port, 3 - Controller ModbusTCP connection to external slave port. |
address | uint32 | Starting address of the coil. |
num | uint32 | (Not effective for single coil) Number of coils to write, the number of coils written each time should not exceed 160. |
data | uint16[] | Data to be written to the coil, data type: byte. If the number of coils is not greater than 8, the data written is one byte; otherwise, it is an array of multiple data points. |
device | uint32 | Peripheral device address. |
Usage command demo:
rostopic pub /rm_driver/Write_Single_Coil rm_msgs/Write_Register "port: 0 address: 0 num: 0 data: [0] device: 1"
Return command demo:
rostopic echo /rm_driver/Write_Single_Coil_Result
Parameter description:
Parameter | Type | Description |
---|---|---|
std_msgs | Bool | true : Configuration successful; false : Configuration failed. |
Writing Multiple Coils Write_Register.msg
Parameter description:
Parameter | Type | Description |
---|---|---|
port | uint8 | Communication port: 0 - Controller RS485 port, 1 - End-effector interface board RS485 port, 3 - Controller ModbusTCP connection to external slave port. |
address | uint32 | Starting address of the coil. |
num | uint32 | (Not effective for single coil) Number of coils to write, the number of coils written each time should not exceed 160. |
data | uint16[] | Data to be written to the coil, data type: byte. If the number of coils is not greater than 8, the data written is one byte; otherwise, it is an array of multiple data points. |
device | uint32 | Peripheral device address. |
Usage command demo:
rostopic pub /rm_driver/Write_Coils rm_msgs/Write_Register "port: 0 address: 0 num: 10 data: [1,0] device: 1"
Return command demo:
rostopic echo /rm_driver/Write_Coils_Result
Parameter description:
Parameter | Type | Description |
---|---|---|
std_msgs | Bool | true : Configuration successful; false : Configuration failed. |
Reading Discrete Inputs Read_Register.msg
Parameter description:
Parameter | Type | Description |
---|---|---|
port | uint8 | Communication port: 0 - Controller RS485 port, 1 - End-effector interface board RS485 port, 3 - Controller ModbusTCP connection to external slave port. |
address | uint32 | Starting address of the data. |
num | uint32 | Number of discrete inputs to read. This command supports reading up to 8 discrete inputs at once, meaning the returned data will not exceed one byte. |
device | uint32 | Peripheral device address. |
Usage command demo:
rostopic pub /rm_driver/Read_Input_Status rm_msgs/Read_Register "port: 0 address: 0 num: 2 device: 1"
Return command demo:
rostopic echo /rm_driver/Read_Input_Status_Result
Parameter description:
Parameter | Type | Description |
---|---|---|
data | uint16[] | Returned data. |
state | bool | Status information. |
Reading Holding Registers Register_Data.msg
Parameter description:
Parameter | Type | Description |
---|---|---|
port | uint8 | Communication port: 0 - Controller RS485 port, 1 - End-effector interface board RS485 port, 3 - Controller ModbusTCP connection to external slave port. |
address | uint32 | Starting address of the data. |
num | uint32 | (Not effective) Number of registers to read. This command supports reading up to 8 register data at once, meaning the returned data will not exceed one byte. |
device | uint32 | Peripheral device address. |
Usage command demo:
rostopic pub /rm_driver/Read_Holding_Registers rm_msgs/Read_Register "port: 0 address: 0 num: 0 device: 1"
Return command demo:
rostopic echo / rm_driver/Read_Holding_Registers_Result
Parameter description:
Parameter | Type | Description |
---|---|---|
data | uint16[] | Returned data. |
state | bool | Status information. |
Writing to a Single Register Write_Register.msg
Parameter description:
Parameter | Type | Description |
---|---|---|
port | uint8 | Communication port: 0 - Controller RS485 port, 1 - End-effector interface board RS485 port, 3 - Controller ModbusTCP connection to external slave port. |
address | uint32 | Starting address of the data. |
num | uint32 | (Not effective) Number of registers to write, the number of registers written each time should not exceed 10. |
data | uint16[] | Data to be written to the register, data type: int16. |
device | uint32 | Peripheral device address. |
Usage command demo:
rostopic pub /rm_driver/Write_Single_Register rm_msgs/Write_Register "port: 0 address: 0 num: 0 data: [1000] device: 1"
Return command demo:
rostopic echo /rm_driver/Write_Single_Register_Result
Parameter description:
Parameter | Type | Description |
---|---|---|
std_msgs | Bool | true : Configuration successful; false : Configuration failed. |
Writing to Multiple Registers Write_Register.msg
Parameter description:
Parameter | Type | Description |
---|---|---|
port | uint8 | Communication port: 0 - Controller RS485 port, 1 - End-effector interface board RS485 port, 3 - Controller ModbusTCP connection to external slave port. |
address | uint32 | Starting address of the data. |
num | uint32 | Number of registers to write, the number of registers written each time should not exceed 10. |
data | uint16[] | Data to be written to the register, data type: int16. |
device | uint32 | Peripheral device address. |
Usage command demo:
rostopic pub /rm_driver/Write_Registers rm_msgs/Write_Register "port: 0 address: 10 num: 2 data: [15,20,25,30] device: 1"
Return command demo:
rostopic echo /rm_driver/Write_Registers_Result
Parameter description:
Parameter | Type | Description |
---|---|---|
std_msgs | Bool | true : Configuration successful; false : Configuration failed. |
Reading Multiple Holding Registers Register_Data.msg
Parameter description:
Parameter | Type | Description |
---|---|---|
port | uint8 | Communication port: 0 - Controller RS485 port, 1 - End-effector interface board RS485 port, 3 - Controller ModbusTCP connection to external slave port. |
address | uint32 | Starting address of the data. |
num | uint32 | Number of registers to read, 2 < num < 13. This command supports reading up to 12 register data at once, meaning 24 bytes of data. |
device | uint32 | Peripheral device address. |
Usage command demo:
rostopic pub /rm_driver/Read_Multiple_Holding_Registers rm_msgs/Read_Register "port: 0 address: 0 num: 5 device: 1"
Return command demo:
rostopic echo /rm_driver/Read_Multiple_Holding_Registers_Result
Parameter description:
Parameter | Type | Description |
---|---|---|
data | uint16[] | Returned data. |
state | bool | Status information. |
Reading Input Registers Register_Data.msg
Parameter description:
Parameter | Type | Description |
---|---|---|
port | uint8 | Communication port: 0 - Controller RS485 port, 1 - End-effector interface board RS485 port, 3 - Controller ModbusTCP connection to external slave port. |
address | uint32 | Starting address of the data. |
num | uint32 | (Not effective) |
device | uint32 | Peripheral device address. |
Usage command demo:
rostopic pub /rm_driver/Read_Input_Registers rm_msgs/Read_Register "port: 0 address: 10 num: 0 device: 1"
Return command demo:
rostopic echo /rm_driver/Read_Input_Registers_Result
Parameter description:
Parameter | Type | Description |
---|---|---|
data | uint16[] | Returned data. |
state | bool | Status information. |
Reading Multiple Input Registers Register_Data.msg
Parameter description:
Parameter | Type | Description |
---|---|---|
port | uint8 | Communication port: 0 - Controller RS485 port, 1 - End-effector interface board RS485 port, 3 - Controller ModbusTCP connection to external slave port. |
address | uint32 | Starting address of the data. |
num | uint32 | Number of registers to read, 2 < num < 13. This command supports reading up to 12 register data at once, meaning 24 bytes of data. |
device | uint32 | Peripheral device address. |
Usage command demo:
rostopic pub /rm_driver/Read_Multiple_Input_Registers rm_msgs/Read_Register "port: 0 address: 0 num: 5 device: 1"
Return command demo:
rostopic echo /rm_driver/Read_Multiple_Input_Registers_Result
Parameter description:
Parameter | Type | Description |
---|---|---|
data | uint16[] | Returned data. |
state | bool | Status information. |
Control of end effector five-fingered dexterous hand (optional)
The RealMan 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 handHand_Posture.msg
Parameter description:
Parameter | Type | Description |
---|---|---|
posture_num | uint16 | #Gesture sequence number pre-stored in the dexterous hand, range: 1-40 |
Usage command demo:
rostopic pub /rm_driver/Hand_SetPosture rm_msgs/Hand_Posture "posture_num: 0"
Return command demo:
rostopic echo /rm_driver/Set_Hand_Posture_Result
Parameter description:
Parameter | Type | Description |
---|---|---|
std_msgs | Bool | true: setting succeeded, false: setting failed. |
Set the action sequence of the dexterous handHand_Seq.msg
Parameter description:
Parameter | Type | Description |
---|---|---|
seq_num | uint16 | Sequence number pre-stored in the dexterous hand, range: 1-40 |
Usage command demo:
rostopic pub /rm_driver/Hand_SetSeq rm_msgs/Hand_Seq "seq_num: 0"
Return command demo:
rostopic echo /rm_driver/Set_Hand_Seq_Result
Parameter description:
Parameter | Type | Description |
---|---|---|
std_msgs | Bool | true: setting succeeded, false: setting failed. |
Set the angles of the dexterous handHand_Angle.msg
Set the angles of the dexterous hand, which has 6 degrees of freedom: 1. Little finger, 2. Ring finger, 3. Middle finger, 4. Index finger, 5. Thumb bending, 6. Thumb rotation.
Parameter description:
Parameter | Type | Description |
---|---|---|
hand_angle | uint16 | Array of finger angles, range: 0-1,000. (Subject to the actual product, for example) Additionally, -1 indicates that no action will be performed for this degree of freedom, and the current state will be maintained |
Usage command demo:
rostopic pub /rm_driver/Hand_SetAngle rm_msgs/Hand_Angle "hand_angle: [0, 0, 0, 0, 0, 0]"
Return command demo:
rostopic echo /rm_driver/Set_Hand_Angle_Result
Parameter description:
Parameter | Type | Description |
---|---|---|
std_msgs | Bool | true: setting succeeded, false: setting failed. |
Set the speed of the dexterous handHand_Speed.msg
Parameter description:
Parameter | Type | Description |
---|---|---|
hand_speed | uint16 | Finger speed, range: 1−1,000 |
Usage command demo:
rostopic pub /rm_driver/Hand_SetSpeed rm_msgs/Hand_Speed "hand_speed: 0"
Return command demo:
rostopic echo /rm_driver/Set_Hand_Speed_Result
Parameter description:
Parameter | Type | Description |
---|---|---|
std_msgs | Bool | true: setting succeeded, false: setting failed. |
Set the force threshold of the dexterous handHand_Force.msg
Parameter description:
Parameter | Type | Description |
---|---|---|
hand_Force | uint16 | Finger force, range: 1−1,000 |
Usage command demo:
rostopic pub /rm_driver/Hand_SetForce rm_msgs/Hand_Force "hand_force: 0"
Return command demo:
rostopic echo /rm_driver/Set_Hand_Force_Result
Parameter description:
Parameter | Type | Description |
---|---|---|
std_msgs | Bool | true: setting succeeded, false: setting failed. |
Setting Dextrous Hand Angle Hand_Angle.msg
Set the angle of the dextrous hand. The dextrous hand has 6 degrees of freedom, numbered from 1 to 6, representing the little finger, ring finger, middle finger, index finger, thumb bending, and thumb rotation, respectively.
Parameter description:
Parameter | Type | Description |
---|---|---|
hand_angle | uint16 | Finger angle array (subject to the actual product, for example), range: 0~2000. Additionally, -1 indicates that no operation is performed on this degree of freedom and the current state is maintained. |
Usage command demo:
rostopic pub /rm_driver/Hand_FollowAngle rm_msgs/Hand_Angle "hand_angle: [0, 0, 0, 0, 0, 0]"
Return command demo:
rostopic echo /rm_driver/Set_Hand_Follow_Angle_Result
Parameter description:
Parameter | Type | Description |
---|---|---|
std_msgs | Bool | true : setting succeeded, false : setting failed. |
Setting Dextrous Hand Pose Following Hand_Angle.msg
Set the angle of the dextrous hand. The dextrous hand has 6 degrees of freedom, numbered from 1 to 6, representing the little finger, ring finger, middle finger, index finger, thumb bending, and thumb rotation, respectively.
Parameter description:
Parameter | Type | Description |
---|---|---|
hand_angle | int16[6] | Finger pose array (subject to the actual product, for example), range: 0~1000. |
Usage command demo:
rostopic pub /rm_driver/Hand_FollowPos rm_msgs/Hand_Angle "hand_angle: [0, 0, 0, 0, 0, 0]"
Return command demo:
rostopic echo /rm_driver/Set_Hand_Follow_Pos_Result
Parameter description:
Parameter | Type | Description |
---|---|---|
std_msgs | Bool | true : setting succeeded, false : setting failed. |
Pass-through force-position hybrid control compensation mode
For RealMan robotic arms with both 1-DoF and 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.
Enable the pass-through force-position hybrid control compensation mode
Parameter description:
Parameter | Type | Description |
---|---|---|
std_msgs | Empty msg | ROS built-in msg. |
Usage command demo:
rostopic pub /rm_driver/StartForcePositionMove_Cmd std_msgs/Empty "{}"
Return command demo:
rostopic echo /rm_driver/StartForcePositionMove_Result
Parameter description:
Parameter | Type | Description |
---|---|---|
std_msgs | Bool | true: setting succeeded, false: setting failed. |
Pass-through force-position hybrid control compensation (pose)Force_Position_Move_Pose.msg
Parameter description:
Parameter | Type | Description |
---|---|---|
Pose | geometry_msgs/Pose | Quaternion |
sensor | uint8 | Type of sensor used, 0: 1-DoF force, 1: 6-DoF force |
mode | uint8 | Mode, 0: along the work frame, 1: along the tool frame |
dir | uint8 | 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 | int16 | Magnitude of the force, accuracy: 0.1 N or 0.1 N.m |
Usage command demo:
rostopic pub /rm_driver/ForcePositionMovePose_Cmd rm_msgs/Force_Position_Move_Pose "Pose: position: {x: 0.0, y: 0.0, z: 0.0} orientation: {x: 0.0, y: 0.0, z: 0.0, w: 0.0} sensor: 1 mode: 0 dir: 0 force: 0"
Parameter description:
Succeeded: no return value, failed: return error message in the rm_driver node.
Custom High-Following Mode Force and Position Hybrid Control Compensation (Pose) Force_Position_Move_Pose_Custom.msg
Parameter description:
Parameter | Type | Description |
---|---|---|
Pose | geometry_msgs/Pose | Quaternion information. |
sensor | uint8 | Type of sensor used, 0: 1-DoF force, 1: 6-DoF force. |
mode | uint8 | Mode, 0: along the work frame, 1: along the tool frame. |
dir | uint8 | 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 | int16 | Magnitude of the force, accuracy: 0.1 N or 0.1 N.m. |
follow | bool | Motion following effect of the driver, true for high following, false for low following. |
trajectory_mode | uint8 | Under high-following mode, supports multiple modes: 0 - Full transparent transmission mode, 1 - Curve fitting mode, 2 - Filtering mode. |
radio | uint8 | Sets the smoothing coefficient under curve fitting mode (range 0-100) or the filtering parameter under filtering mode (range 0-1000), higher values indicate better smoothing effects. |
Usage command demo:
rostopic pub /rm_driver/ForcePositionMovePoseCustom_Cmd rm_msgs/Force_Position_Move_Pose_Custom
"Pose:
position: {x: 0.0, y: 0.0, z: 0.0}
orientation: {x: 0.0, y: 0.0, z: 0.0, w: 0.0}
sensor: 1
mode: 0
dir: 0
force: 0
follow: false
trajectory_mode: 0
radio: 0"
Parameter description:
Succeeded: no return value, failed: return error message in the rm_driver node.
Pass-through force-position hybrid control compensation (radian)Force_Position_Move_Joint.msg
Parameter description:
Parameter | Type | Description |
---|---|---|
joint | float32[] | Radian. |
sensor | uint8 | Type of sensor used, 0: 1-DoF force, 1: 6-DoF force. |
mode | uint8 | Mode, 0: along the work frame, 1: along the tool frame. |
dir | uint8 | 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 | int16 | Magnitude of the force, accuracy: 0.1 N or 0.1 N.m. |
dof | uint8 | Degree of freedom of the robotic arm. |
Usage command demo:
rostopic pub /rm_driver/ForcePositionMoveJiont_Cmd rm_msgs/Force_Position_Move_Joint "joint: [0, 0, 0, 0, 0, 0] sensor: 0 mode: 0 dir: 0 force: 0 dof: 0"
Parameter description:
Succeeded: no return value, failed: return error message in the rm_driver node
Disable the pass-through force-position hybrid control compensation mode
Parameter description:
Parameter | Type | Description |
---|---|---|
std_msgs | Empty | ROS built-in msg. |
Usage command demo:
rostopic pub /rm_driver/StopForcePositionMove_Cmd std_msgs/Empty "{}"
Return command demo:
rostopic echo /rm_driver/StopForcePositionMove_Result
Parameter description:
Parameter | Type | Description |
---|---|---|
std_msgs | Bool | true: setting succeeded, false: setting failed. |
Lifting mechanism
The RealMan robotic arm can integrate a self-developed lifting mechanism.
Set the open-loop speed control of the lifting mechanismLift_Speed.msg
Parameter description:
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. |
Usage command demo:
rostopic pub /rm_driver/Lift_SetSpeed rm_msgs/Lift_Speed "speed: 0"
Return command demo:
rostopic echo /rm_driver/Set_Lift_Speed_Result
Parameter description:
Parameter | Type | Description |
---|---|---|
std_msgs | Bool | true: setting succeeded, false: setting failed. |
Set the closed-loop position control of the lifting mechanismLift_Height.msg
The lifting mechanism runs to the specified height. Parameter description:
Parameter | Type | Description |
---|---|---|
height | uint16 | Target height, in mm, range: 0-2,600. |
speed | uint16 | Speed percentage, 1−100. |
Usage command demo:
rostopic pub /rm_driver/Lift_SetHeight rm_msgs/Lift_Height "height: 0 speed: 0"
Return command demo:
rostopic echo /rm_driver/Plan_State
Parameter description:
Parameter | Type | Description |
---|---|---|
std_msgs | Bool | true: setting succeeded, false: setting failed. |
Get the state of the lifting mechanism LiftState.msg
Parameter description:
Parameter | Type | Description |
---|---|---|
std_msgs | Empty msg | ROS built-in msg. |
Usage command demo:
rostopic pub /rm_driver/Lift_GetState std_msgs/Empty "{}"
Return command demo:
rostopic echo /rm_driver/LiftState
Parameter description:LiftState.msg
Parameter | Type | Description |
---|---|---|
height | int16 | Current height. |
current | int16 | Current current. |
err_flag | uint16 | Drive error code. |
mode | byte | Current lifting state 0: idle 1: forward speed motion 2: forward position motion 3: backward speed motion 4: backward position motion. |
Robotic arm state active reporting
Set the UDP robotic arm state active reporting configurationSet_Realtime_Push.msg
Parameter description:
Parameter | Type | Description |
---|---|---|
cycle | uint16 | Set the broadcast cycle, which is a 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 reporting target IP address (192.168.1.10 by default). |
hand_enable | bool | Enable the active reporting of the dextrous hand status. |
aloha_state_enable | bool | ALOHA main arm status. |
arm_current_status_enable | bool | Current status of the robotic arm. |
expand_state_enable | bool | Extended joint information. |
joint_acc_enable | bool | Joint acceleration. |
joint_speed_enable | bool | Joint speed. |
lift_state_enable | bool | Lifting joint information. |
tail_end_enable | bool | 1. |
rm_plus_base_enable | bool | Basic information of the end-effector. |
rm_plus_state_enable | bool | Real-time information of the end-effector. |
Usage command demo:
rostopic pub /rm_driver/Set_Realtime_Push rm_msgs/Set_Realtime_Push
"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_acc_enable: false
joint_speed_enable: false
lift_state_enable: false
rm_plus_base_enable: false
rm_plus_state_enable: false"
Return command demo:
rostopic echo /rm_driver/Set_Realtime_Push_Result
Parameter description:
Parameter | Type | Description |
---|---|---|
std_msgs | Bool | true: setting succeeded, false: setting failed. |
Get the UDP robotic arm state active reporting configuration Set_Realtime_Push.msg
Parameter description:
Parameter | Type | Description |
---|---|---|
std_msgs | Empty | ROS built-in msg. |
Usage command demo:
rostopic pub /rm_driver/Get_Realtime_Push std_msgs/Empty "{}"
Return command demo:
rostopic echo /rm_driver/Get_Realtime_Push_Result
Parameter description:
Parameter | Type | Description |
---|---|---|
cycle | uint16 | Set the broadcast cycle, which is a 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 reporting target IP address (192.168.1.10 by default). |
hand_enable | bool | Enable the active reporting of the dextrous hand status. |
aloha_state_enable | bool | ALOHA main arm status. |
arm_current_status_enable | bool | Current status of the robotic arm. |
expand_state_enable | bool | Extended joint information. |
joint_acc_enable | bool | Joint acceleration. |
joint_speed_enable | bool | Joint speed. |
lift_state_enable | bool | Lifting joint information. |
rm_plus_base_enable | bool | Basic information of the end-effector. |
rm_plus_state_enable | bool | Real-time information of the end-effector. |
End-Effector Ecosystem Command Set
Setting the End-Effector Protocol Mode
Parameter description:
Parameter | Type | Description |
---|---|---|
data | uint32 | 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:
rostopic pub /rm_driver/Set_Rm_Plus_Mode std_msgs/UInt32 "data: 9600"
Return command demo:
rostopic echo /rm_driver/Set_Rm_Plus_Mode_Result
Parameter description:
Parameter | Type | Description |
---|---|---|
std_msgs | Bool | true: Setting successful; false: Setting failed. |
Querying the End-Effector Protocol Mode
Parameter description:
Parameter | Type | Description |
---|---|---|
std_msgs | Empty | ROS built-in msg. |
Usage command demo:
rostopic pub /rm_driver/Get_Rm_Plus_Mode std_msgs/Empty "{}"
Return command demo:
rostopic echo /rm_driver/Get_Rm_Plus_Mode_Result
Parameter description:
Parameter | Type | Description |
---|---|---|
data | uint32 | 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 the Tactile Sensor Mode
Parameter description:
Parameter | Type | Description |
---|---|---|
data | uint32 | 0 - Disable tactile sensor; 1 - Enable tactile sensor (return processed data); 2 - Enable tactile sensor (return raw data). |
Usage command demo:
rostopic pub /rm_driver/Set_Rm_Plus_Mode std_msgs/UInt32 "data: 1"
Return command demo:
rostopic echo /rm_driver/Set_Rm_Plus_Touch_Result
Parameter description:
Parameter | Type | Description |
---|---|---|
std_msgs | Bool | true: Setting successful; false: Setting failed. |
Querying the Tactile Sensor Mode
Parameter description:
Parameter | Type | Description |
---|---|---|
std_msgs | Empty | ROS built-in msg. |
Usage command demo:
rostopic pub /rm_driver/Get_Rm_Plus_Touch std_msgs/Empty "{}"
Return command demo:
rostopic echo /rm_driver/Get_Rm_Plus_Touch_Result
Parameter description:
Parameter | Type | Description |
---|---|---|
data | uint32 | 0 - Disable tactile sensor; 1 - Enable tactile sensor (return processed data); 2 - Enable tactile sensor (return raw data). |
UDP robotic arm state active reporting
6-DoF forceSix_Force.msg
Parameter description:
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 rotation force along the x-axis. |
force_my | float32 | Magnitude of rotation force along the y-axis. |
force_mz | float32 | Magnitude of rotation force along the z-axis. |
Usage command demo:
rostopic echo /rm_driver/UdpSixForce
One-axis Force Six_Force.msg
Parameter description:
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 rotation force along the x-axis. |
force_my | float32 | Magnitude of rotation force along the y-axis. |
force_mz | float32 | Magnitude of rotation force along the z-axis. |
Usage command demo:
rostopic echo /rm_driver/UdpSixForce
Robotic arm error
Parameter description:
Parameter | Type | Description |
---|---|---|
data | uint16 | Robotic arm error. |
Usage command demo:
rostopic echo /rm_driver/ArmError
System error
Parameter description:
Parameter | Type | Description |
---|---|---|
data | uint16 | System error. |
Usage command demo:
rostopic echo /rm_driver/SysError
Joint errorJoint_Error_Code.msg
Parameter description:
Parameter | Type | Description |
---|---|---|
joint_error | uint16[] | Each joint error |
Usage command demo:
rostopic echo /rm_driver/JointErrorCode
Robot arm radian data
Parameter description:
Parameter | Type | Description |
---|---|---|
sec | uint32 | Time, in s. |
nanosec | class | Time, in ns. |
frame_id | string | Frame name. |
name | string[] | Joint name. |
position | float64[] | Joint radian. |
velocity | float64[] | Joint velocity. (Not currently in use) |
effort | float64[] | Joint force. (Not currently in use) |
Usage command demo:
rostopic echo /joint_states
Function description | Robotic arm radian data |
---|---|
Parameter description | sensor_msgs::msg::JointState builtin_interfaces/Time stamp int32 sec: time, in s. uint32 nanosec: time, in ns. string frame_id: frame name. string[] name: joint name. float64[] position: joint radian. float64[] velocity: joint velocity. (Not currently in use) float64[] effort: Joint force. (Not currently in use) |
Subscription command | rostopic echo /joint_states |
Pose information
Parameter description:
Parameter | Type | Description |
---|---|---|
position.x | float64 | Current coordinates of the robotic arm. |
position.y | float64 | Current coordinates of the robotic arm. |
position.z | float64 | Current coordinates of the robotic arm. |
Quaternion orientation.x | float64 | Current orientation of the robotic arm. |
Quaternion orientation.y | float64 | Current orientation of the robotic arm. |
Quaternion orientation.z | float64 | Current orientation of the robotic arm. |
Quaternion orientation.w | float64 | Current orientation of the robotic arm. |
Usage command demo:
rostopic echo /rm_driver/Pose_State
Current external force data of the 6-DoF force sensor systemSix_Force.msg
Parameter description:
Parameter | Type | Description |
---|---|---|
force_fx | float32 | Magnitude of external force along the x-axis of the current sensor. |
force_fy | float32 | Magnitude of external force along the y-axis of the current sensor. |
force_fz | float32 | Magnitude of external force along the z-axis of the current sensor. |
force_mx | float32 | Magnitude of rotation force along the x-axis. |
force_my | float32 | Magnitude of rotation force along the y-axis. |
force_mz | float32 | Magnitude of rotation force along the z-axis. |
Usage command demo:
rostopic echo /rm_driver/UdpSixZeroForce
Current external force data of the One-axis Force sensor systemSix_Force.msg
Parameter description:
Parameter | Type | Description |
---|---|---|
force_fx | float32 | Magnitude of external force along the x-axis of the current sensor. |
force_fy | float32 | Magnitude of external force along the y-axis of the current sensor. |
force_fz | float32 | Magnitude of external force along the z-axis of the current sensor. (Only this value is valid) |
force_mx | float32 | Magnitude of rotation force along the x-axis. |
force_my | float32 | Magnitude of rotation force along the y-axis. |
force_mz | float32 | Magnitude of rotation force along the z-axis. |
Usage command demo:
rostopic echo /rm_driver/UdpSixZeroForce
Reference frame for external force data
Parameter description:
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 coordinate system for the external force data of the 1-DoF force and 6-DoF force sensor systems. |
Usage command demo:
rostopic echo /rm_driver/Udp_Coordinate
Current Status of the Dextrous Hand Hand_Status.msg
Parameter description:
Parameter | Type | Description |
---|---|---|
hand_angle | uint16[6] | Array of finger angles, range: 0~2000. |
hand_pos | uint16[6] | Array of finger positions, range: 0~1000. |
hand_state | uint16[6] | Finger status: 0 - Releasing, 1 - Grasping, 2 - Position reached and stopped, 3 - Force reached and stopped, 5 - Current protection stop, 6 - Motor blockage stop, 7 - Motor fault stop. |
hand_force | uint16[6] | Current of the dextrous hand's degrees of freedom, unit: mN. |
hand_err | uint16 | System error of the dextrous hand, 1 indicates an error, 0 indicates no error. |
Usage command demo:
rostopic echo /rm_driver/Udp_Hand_Status
Current Status of the Robotic Arm Arm_Current_Status.msg
Parameter description:
Parameter | Type | Description |
---|---|---|
arm_current_status | string | Current status of the robotic arm. |
Usage command demo:
rostopic echo /rm_driver/Udp_Arm_Current_status
Joint Current of the Robotic Arm Joint_Current.msg
Parameter description:
Parameter | Type | Description |
---|---|---|
joint_current | float32[] | Joint current. |
Usage command demo:
rostopic echo /rm_driver/Udp_Joint_Current
Joint Enable Flag of the Robotic Arm Joint_En_Flag.msg
Parameter description:
Parameter | Type | Description |
---|---|---|
joint_en_flag | bool[] | Joint enable flag. |
Usage command demo:
rostopic echo /rm_driver/Udp_Joint_En_Flag
Joint Speed of the Robotic Arm Joint_Speed.msg
Parameter description:
Parameter | Type | Description |
---|---|---|
joint_speed | float32[] | Joint speed. |
Usage command demo:
rostopic echo /rm_driver/Udp_Joint_Speed
Joint Temperature of the Robotic Arm Joint_Temperature.msg
Parameter description:
Parameter | Type | Description |
---|---|---|
Joint_temperature | float32[] | Joint temperature. |
Usage command demo:
rostopic echo /rm_driver/Udp_Joint_Temperature
Joint Voltage of the Robotic Arm Joint_Voltage.msg
Parameter description:
Parameter | Type | Description |
---|---|---|
joint_voltage | float32[] | Joint voltage. |
Usage command demo:
rostopic echo /rm_driver/Udp_Joint_Voltage
Euler Angle Pose of the Robotic Arm Joint_PoseEuler.msg
Parameter description:
Parameter | Type | Description |
---|---|---|
euler | float32[3] | Euler angles. |
position | float32[3] | End-effector position. |
Usage command demo:
rostopic echo /rm_driver/Udp_Joint_PoseEuler
Real-Time Information of the End-Effector Rm_Plus_State.msg
Parameter description:
Parameter | Type | Description |
---|---|---|
sys_state | int32 | System state. |
sys_err | int32 | System error. |
dof_state | int32[] | Current state of each degree of freedom. |
dof_err | int32[] | Error information of each degree of freedom. |
pos | int32[] | Current position of each degree of freedom. |
speed | int32[] | Current speed of each degree of freedom. |
angle | int32[] | Current angle of each degree of freedom. |
current | int32[] | Current current of each degree of freedom. |
normal_force | int32[] | Normal force of the tactile three-dimensional force of each degree of freedom. |
tangential_force | int32[] | Tangential force of the tactile three-dimensional force of each degree of freedom. |
tangential_force_dir | int32[] | Direction of the tangential force of the tactile three-dimensional force of each degree of freedom. |
tsa | uint32[] | Tactile self-approach of each degree of freedom. |
tma | uint32[] | Tactile mutual approach of each degree of freedom. |
touch_data | int32[] | Raw data of the tactile sensor. |
force | int32[] | Torque of each degree of freedom. |
Usage command demo:
rostopic echo /rm_driver/Udp_Plus_State
Basic Information of the End-Effector Rm_Plus_Base.msg
Parameter description:
Parameter | Type | Description |
---|---|---|
manu | string | Device manufacturer. |
type | int8 | Device type: 1 - Two-finger gripper, 2 - Five-finger dextrous hand, 3 - Three-finger gripper. |
hv | string | Hardware version. |
sv | string | Software version. |
bv | string | Boot 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 direction: 1 - Left hand, 2 - Right hand. |
pos_up | int32[] | Position upper limit, unit: dimensionless. |
pos_low | int32[] | Position lower limit, unit: dimensionless. |
angle_up | int32[] | Angle upper limit, unit: 0.01 degrees. |
angle_low | int32[] | Angle lower limit, unit: 0.01 degrees. |
speed_up | int32[] | Speed upper limit, unit: dimensionless. |
speed_low | int32[] | Speed lower limit, unit: dimensionless. |
force_up | int32[] | Force upper limit, unit: 0.001N. |
force_low | int32[] | Force lower limit, unit: 0.001N. |
Usage command demo:
rostopic echo /rm_driver/Udp_Plus_Base