Skip to content

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/NError Code (Hexadecimal)Description
10x0000Normal system
20x1001Abnormal joint communication
30x1002Target angle out of limit
40x1003Point unreachable as a singularity
50x1004Real-time kernel communication error
60x1005Joint communication bus error
70x1006Planning layer kernel error
80x1007Joint overspeed
90x1008End interface board disconnected
100x1009Speed out of limit
110x100AAcceleration out of limit
120x100BJoint brake release failed
130x100COverspeed during drag teaching
140x100DRobotic arm collision
150x100ENull work frame
160x100FNull tool frame
170x1010Joint disabling error
180x1011Circular planning error
190x1012Self-collision error
200x1013Electronic fence collision error (reserved)
210x5001Reserved
220x5002Reserved
230x5003Controller over-temperature
240x5004Reserved
250x5005Controller overcurrent
260x5006Controller undercurrent
270x5007Controller overvoltage
280x5008Controller undervoltage
290x5009Real-time layer communication error

Joint error code

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

Set the joint enabling state

Parameter description:Joint_Enable.msg performs the enabling operation on the specified joint

ParameterTypeDescription
joint_numuint8Corresponding 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.
statebooltrue: enable, false: disable

Usage command demo:

json
rostopic pub /rm_driver/Joint_Enable rm_msgs/Joint_Enable "joint_num: 1 state: true"

Return command demo:

json
rostopic echo /rm_driver/Joint_En_State_Result

Parameter description:

ParameterTypeDescription
std_msgsbooltrue: setting succeeded, false: setting failed.

Change the current tool frame

Parameter description:

ParameterTypeDescription
std_msgsStringROS built-in msg

Usage command demo:

json
rostopic pub /rm_driver/ChangeToolName_Cmd rm_msgs/ChangeTool_Name "toolname: '6WM'"

Return command demo:

json
rostopic echo /rm_driver/ChangeTool_State

Parameter description:

ParameterTypeDescription
std_msgsbooltrue: setting succeeded, false: setting failed.

Change the current work frame

Parameter description:

ParameterTypeDescription
std_msgsStringROS built-in msg

Usage command demo:

json
rostopic pub /rm_driver/ChangeWorkFrame_Cmd rm_msgs/ChangeWorkFrame_Name "WorkFrame_name: 'Base'"

Return command demo:

json
rostopic echo /rm_driver/ChangeWorkFrame_State

Parameter description:

ParameterTypeDescription
std_msgsbooltrue: setting succeeded, false: setting failed.

Get the current work frame

Parameter description:

ParameterTypeDescription
std_msgsEmptyROS built-in msg

Usage command demo:

json
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

Parameter description:

ParameterTypeDescription
std_msgsStringROS built-in msg

Usage command demo:

json
rostopic pub /rm_driver/GetCurrentJointCurrent std_msgs/Empty "{}"

Return command demo:

json
rostopic echo /rm_driver/Joint_Current

Parameter description:Joint_Current.msg

ParameterTypeDescription
joint_currentfloat32[]Joint current (in uA)

Robotic arm motion planning

Joint motion in spaceMoveJ.msg

Parameter description:

ParameterTypeDescription
jointfloat32[]Joint angle, in rad.
speedfloat32Speed ratio, 0-1.
trajectory_connectuint8Optional, indicating whether to plan the motion together with the next trajectory. 0: The motion is planned immediately, 1: It is planned together with the next trajectory. When set to 1, the trajectory will not execute immediately.

Usage command demo:

6-DoF robotic arm

json
rostopic pub /rm_driver/MoveJ_Cmd rm_msgs/MoveJ "joint: [0, 0, 0, 0, 0, 0] speed: 0.2"

7-DoF robotic arm

json
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:

json
rostopic echo /rm_driver/Plan_State

Parameter description:

ParameterTypeDescription
std_msgsbooltrue: setting succeeded, false: setting failed.

Cartesian-space linear motionMoveL.msg

Parameter description:

ParameterTypeDescription
Posegeometry_msgs/PoseRobotic arm pose, including x, y, z coordinates (float type, in m) + quaternion.
speedfloat32Speed ratio, 0-1.
trajectory_connectuint8Optional, indicating whether to plan the motion together with the next trajectory. 0: The motion is planned immediately, 1: It is planned together with the next trajectory. When set to 1, the trajectory will not execute immediately.

Usage command demo:

json
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:

json
rostopic echo /rm_driver/Plan_State

Parameter description:

ParameterTypeDescription
std_msgsbooltrue: setting succeeded, false: setting failed.

Cartesian-space circular motionMoveC.msg

Parameter description:

ParameterTypeDescription
Mid_Posegeometry_msgs/PoseMiddle pose, including x, y, z coordinates (float type, in m) + quaternion.
End_Posegeometry_msgs/PoseEnd pose, including x, y, z coordinates (float type, in m) + quaternion.
speedfloat32Speed ratio, 0-1.
trajectory_connectuint8Optional, indicating whether to plan the motion together with the next trajectory. 0: The motion is planned immediately, 1: It is planned together with the next trajectory. When set to 1, the trajectory will not execute immediately.

Usage command demo:

json
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
trajectory_connect: 0"

Return command demo:

json
rostopic echo /rm_driver/Plan_State

Parameter description:

ParameterTypeDescription
std_msgsbooltrue: setting succeeded, false: setting failed.

Joint angle CANFD pass-throughJointPos.msg

Parameter description:

ParameterTypeDescription
jointfloat32[]Joint angle, in rad.
expandfloat32Expansion 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.

json
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.

Pose CANFD pass-throughCartePos.msg

Parameter description:

ParameterTypeDescription
Posegeometry_msgs/PosePass-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.

json
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.

Joint space planning to target orientationMoveJ_P.msg

Parameter description:

ParameterTypeDescription
Mid_Posegeometry_msgs/PoseTarget pose, including x, y, z coordinates (float type, in m) + quaternion.
speedfloat32Speed ratio, 0-1.
trajectory_connectuint8Optional, indicating whether to plan the motion together with the next trajectory. 0: The motion is planned immediately, 1: It is planned together with the next trajectory. When set to 1, the trajectory will not execute immediately.

Usage command demo:

json
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:

json
rostopic echo /rm_driver/Plan_State

Robotic arm motion configuration - step command

Joint stepJoint_Step.msg

Parameter description:

ParameterTypeDescription
joint_numuint8Joint to be moved.
step_anglefloat32Step angle (in °).
speedfloat32Motion speed.

Usage command demo: 6-DoF robotic arm

json
rostopic pub /rm_driver/SetJointStep rm_msgs/Joint_Step "joint_num: 6 step_angle: 90.0  speed: 0.2"

7-DoF robotic arm

json
rostopic pub /rm_driver/SetJointStep rm_msgs/Joint_Step "joint_num: 7 step_angle: 90.0 speed: 0.2"

Return command demo:

json
rostopic echo /rm_driver/Plan_State

Parameter description:

ParameterTypeDescription
std_msgsbooltrue: setting succeeded, false: setting failed.

Robotic arm motion configuration - motion command

Quick stopStop.msg

Parameter description:

ParameterTypeDescription
statetooltrue: valid, false: invalid

Usage command demo:

json
rostopic pub /rm_driver/Emergency_Stop rm_msgs/Stop "state: true"

Return command demo:

json
rostopic echo /rm_driver/Set_Arm_Stop_Result

Parameter description:

ParameterTypeDescription
std_msgsbooltrue: setting succeeded, false: setting failed.

Robotic arm motion configuration - teaching command class

Joint teachingJoint_Teach.msg

Parameter description:

ParameterTypeDescription
teach_jointint16Teaching control joint
directionstringJoint rotation direction, "pos": positive direction, "neg": negative direction
vint16Joint rotation speed, 0-100

Usage command demo: 6-DoF robotic arm

json
rostopic pub /rm_driver/Arm_JointTeach rm_msgs/Joint_Teach "teach_joint: 1 direction: 'pos' v: 20"

Return command demo:

json
rostopic echo /rm_driver/SetJointTeach_Result

Parameter description:

ParameterTypeDescription
std_msgsbooltrue: setting succeeded, false: setting failed.

Position teachingPos_Teach.msg

Parameter description:

ParameterTypeDescription
teach_typestringCoordinate axis, "x", "y", "z"
directionstringTeaching direction, "pos": positive direction, "neg": negative direction
vint16Joint rotation speed, 0-100

Usage command demo:

json
rostopic pub /rm_driver/Arm_PosTeach rm_msgs/Pos_Teach "teach_type: 'z' direction: 'pos' v: 10"

Return command demo:

json
rostopic echo /rm_driver/SetPosTeach_Result

Parameter description:

ParameterTypeDescription
std_msgsbooltrue: setting succeeded, false: setting failed.

Orientation teachingOrt_Teach.msg

Parameter description:

ParameterTypeDescription
joint_numstringRotation axis, "rx", "ry", "rz"
step_anglestringTeaching direction, "pos": positive direction, "neg": negative direction
vint16Joint rotation speed, 0-100

Usage command demo:

json
rostopic pub /rm_driver/Arm_OrtTeach rm_msgs/Ort_Teach "teach_type: 'rz' direction: 'pos' v: 10"

Return command demo:

json
rostopic echo /rm_driver/SetOrtTeach_Result

Parameter description:

ParameterTypeDescription
std_msgsbooltrue: setting succeeded, false: setting failed.

Stop teachingStop_Teach.msg

Parameter description:

ParameterTypeDescription
commandstringStop command "set_stop_teach", execute the following command to stop

Usage command demo:

json
rostopic pub /rm_driver/Arm_StopTeach rm_msgs/Stop_Teach "command: ''"

Return command demo:

json
rostopic echo /rm_driver/SetStopTeach_Result

Parameter description:

ParameterTypeDescription
std_msgsbooltrue: setting succeeded, false: setting failed.

System configuration

Control the power on/off of the robotic arm

Parameter description:

ParameterTypeDescription
std_msgsByte msg1: Power on the robotic arm, 0: Power off the robotic arm

Usage command demo:

json
rostopic pub /rm_driver/SetArmPower std_msgs/Byte "data: 0"

Return command demo:

json
rostopic echo /rm_driver/Set_Arm_Power_Result

Parameter description:

ParameterTypeDescription
std_msgsbooltrue: setting succeeded, false: setting failed.

Read the software version number

Parameter description:

ParameterTypeDescription
std_msgsByte msg1: Power on the robotic arm, 0: Power off the robotic arm

Usage command demo:

json
rostopic pub /rm_driver/Get_Arm_Software_Version std_msgs/Empty "{}"

Return command demo:

json
rostopic echo /rm_driver/Get_Arm_Software_Version_Result

Parameter description:

ParameterTypeDescription
Arm_Software_Version.msgstringProduct_version # Robotic arm type Plan_version #Software version number

Clear system errors

Parameter description:

ParameterTypeDescription
std_msgsEmpty msg/

Usage command demo:

json
rostopic pub /rm_driver/Clear_System_Err std_msgs/Empty "{}"

Return command demo:

json
rostopic echo /rm_driver/System_En_State_Result

Parameter description:

ParameterTypeDescription
std_msgsbooltrue: setting succeeded, false: setting failed.

Get the robotic arm state

Get the current joint current of the robotic armJoint_Current.msg

Parameter description:

ParameterTypeDescription
std_msgsEmptyROS built-in msg

Usage command demo:

json
rostopic pub /rm_driver/GetCurrentJointCurrent std_msgs/Empty "{}"

Return command demo:

json
rostopic echo /rm_driver/Joint_Current

Parameter description:

ParameterTypeDescription
joint_currentfloat32[]Joint current (in uA)

Get the joint angle of the robotic arm

Parameter description:

ParameterTypeDescription
std_msgsEmpty msg/

Usage command demo:

json
rostopic pub /rm_driver/GetArmJoint_Cmd std_msgs/Empty "{}"

Return command demo:

json
rostopic echo /joint_states

Parameter description:

ParameterTypeDescription
sensor_msgsJointState/

Get the robotic arm state (radian + quaternion)GetArmState_Command.msg

Parameter description:

ParameterTypeDescription
commandstring/

Usage command demo:

json
rostopic pub /rm_driver/GetArmState_Cmd rm_msgs/GetArmState_Command "command: ''"

Return command demo:

json
rostopic echo /rm_driver/ArmCurrentState

Parameter description:ArmState.msg

ParameterTypeDescription
jointfloat32[]Radian of the robotic arm
PoseboolCurrent pose of the robotic arm (quaternion)
arm_errboolRobotic arm error
sys_errboolSystem error
dofboolDegree of freedom of the robotic arm

Get the robotic arm state (angle + Euler angle)GetArmState_Command.msg

Parameter description:

ParameterTypeDescription
commandstring/

Usage command demo:

json
rostopic pub /rm_driver/GetArmState_Cmd rm_msgs/GetArmState_Command "command: ''"

Return command demo:

json
rostopic echo /rm_driver/Arm_Current_State

Parameter description:Arm_Current_State.msg

ParameterTypeDescription
jointfloat32[]Angle of the robotic arm
PoseboolCurrent pose of the robotic arm (Euler angle)
arm_errboolRobotic arm error
sys_errboolSystem error
dofboolDegree 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:

ParameterTypeDescription
numuint8IO port number, range: 1-4
statebool“state”: IO state, 1: high output, 0: low output

Usage command demo:

json
rostopic pub /rm_driver/Arm_Digital_Output rm_msgs/Arm_Digital_Output "num: 1 state: true"

Return command demo:

json
rostopic echo /rm_driver/Set_DO_State_Result

Parameter description:

ParameterTypeDescription
std_msgsBooltrue: setting succeeded, false: setting failed.

Get all IO input statesIO_Update.msg

Parameter description:

ParameterTypeDescription
typeint81: Get controller IO state; 2: Get tool-end IO state

Usage command demo:

json
rostopic pub /rm_driver/IO_Update rm_msgs/IO_Update "type: 1"

Return command demo:

json
rostopic echo /rm_driver/Arm_IO_State

Parameter description:Arm_IO_State.msg

ParameterTypeDescription
Arm_Digital_Inputnt8[4]1: high, -1: output

Tool-end IO configuration and acquisition

Set tool-end digital IO output stateTool_Digital_Output.msg

Parameter description:

ParameterTypeDescription
numuint8IO port number, range: 1-4
statebool“state”: IO state, 1: high output, 0: low output

Usage command demo:

json
rostopic pub /rm_driver/Tool_Digital_Output rm_msgs/Tool_Digital_Output "num: 1 state: true"

Return command demo:

json
rostopic echo /rm_driver/Set_Tool_DO_State_Result

Parameter description:

ParameterTypeDescription
std_msgsBooltrue: setting succeeded, false: setting failed.

Get tool-end digital IO stateIO_Update.msg

Parameter description:

ParameterTypeDescription
typeuint81: Get controller IO state; 2: Get tool-end IO state

Usage command demo:

json
rostopic pub /rm_driver/IO_Update rm_msgs/IO_Update "type: 2"

Return command demo:

json
rostopic echo /rm_driver/Tool_IO_State

Parameter description:Tool_IO_State.msg

ParameterTypeDescription
Tool_IO_Modebool[2]Digital I/O input/output state, 0: input mode, 1: output mode
Tool_IO_Statebool[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:

ParameterTypeDescription
speeduint161-1000, representing the gripper opening and closing speed, without unit of measurement
forceuint161-1000, representing the gripping force of the gripper, with a maximum of 1.5 kg

Usage command demo:

json
rostopic pub /rm_driver/Gripper_Pick_On rm_msgs/Gripper_Pick "speed: 100 force: 100"

Return command demo:

json
rostopic echo /rm_driver/Set_Gripper_Result

Parameter description:

ParameterTypeDescription
std_msgsBooltrue: 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:

ParameterTypeDescription
speeduint161-1000, representing the gripper opening and closing speed, without unit of measurement
forceuint161-1000, representing the gripping force of the gripper, with a maximum of 1.5 kg

Usage command demo:

json
rostopic pub /rm_driver/Gripper_Pick rm_msgs/Gripper_Pick "speed: 100 force: 100"

Return command demo:

json
rostopic echo /rm_driver/Set_Gripper_Result

Parameter description:

ParameterTypeDescription
std_msgsBooltrue: 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:

ParameterTypeDescription
positionuint16Gripper target position, range: 1-1.000, representing the gripper opening: 0-70 mm

Usage command demo:

json
rostopic pub /rm_driver/Gripper_Set rm_msgs/Gripper_Set "position: 100"

Return command demo:

json
rostopic echo /rm_driver/Set_Gripper_Result

Parameter description:

ParameterTypeDescription
std_msgsBooltrue: 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

Parameter description:

ParameterTypeDescription
std_msgsEmpty msg/

Usage command demo:

json
rostopic pub /rm_driver/GetSixForce_Cmd std_msgs/Empty "{}"

Return command demo:

json
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:Six_Force.msg

ParameterTypeDescription
force_Fxfloat32/
force_Fyfloat32/
force_Fzfloat32/
force_Mxfloat32/
force_Myfloat32/
force_Mzfloat32/

Clear the 6-DoF force data

Parameter description:

ParameterTypeDescription
std_msgsEmpty/

Usage command demo:

json
rostopic pub /rm_driver/ClearForceData_Cmd std_msgs/Empty "{}"

Return command demo:

json
rostopic echo /rm_driver/ClearForceData_Result

Parameter description:

ParameterTypeDescription
std_msgsBooltrue: setting succeeded, false: setting failed.

Automatically set 6-DoF force center of gravity parameters

Parameter description:

ParameterTypeDescription
std_msgsEmpty/

Usage command demo:

json
rostopic pub /rm_driver/SetForceSensor_Cmd std_msgs/Empty "{}"

Return command demo:

json
rostopic echo /rm_driver/ForceSensorSet_Result

Parameter description:

ParameterTypeDescription
std_msgsBooltrue: setting succeeded, false: setting failed.

Manually calibrate 6-DoF force data

Parameter description:

Manual_Set_Force_Pose.msg

ParameterTypeDescription
pose1stringPose 1 joint angle;
pose2stringPose 2 joint angle;
pose3stringPose 3 joint angle;
pose4stringPose 4 joint angle;
jointint64[]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:

json
rostopic pub /rm_driver/ManualSetForcePose_Cmd rm_msgs/Manual_Set_Force_Pose "pose: ' pose1' joint:  [0, 0, 0, 0, 90000, 0]"

Return command demo:

json
rostopic echo /rm_driver/ForceSensorSet_Result

Parameter description:

ParameterTypeDescription
std_msgsBooltrue: setting succeeded, false: setting failed.

Stop calibrating the center of gravity of the force sensor

Parameter description:

ParameterTypeDescription
std_msgsEmpty/

Usage command demo:

json
rostopic pub /rm_driver/StopSetForceSensor_Cmd std_msgs/Empty "{}"

Return command demo:

json
rostopic echo /rm_driver/StopSetForceSensor_Result

Parameter description:

ParameterTypeDescription
std_msgsBooltrue: setting succeeded, false: setting failed.

Drag teaching

Stop the drag teaching

Parameter description:

ParameterTypeDescription
std_msgsEmpty/

Usage command demo:

json
rostopic pub /rm_driver/StartMultiDragTeach_result std_msgs/Empty "{}"

Return command demo:

json
rostopic echo /rm_driver/StopDragTeach_Result

Parameter description:

ParameterTypeDescription
std_msgsBooltrue: setting succeeded, false: setting failed.

Enable multiple drag teaching

Parameter description:Start_Multi_Drag_Teach.msg

ParameterTypeDescription
modeuint80: 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:

json
rostopic pub /rm_driver/StartMultiDragTeach_Cmd rm_msgs/Start_Multi_Drag_Teach "mode: 0"

Return command demo:

json
rostopic echo /rm_driver/StartMultiDragTeach_Result

Parameter description:

ParameterTypeDescription
std_msgsBooltrue: setting succeeded, false: setting failed.

Force-position hybrid controlSet_Force_Position.msg

Parameter description:

ParameterTypeDescription
modesensorSensor, 0: 1-DoF force, 1: 6-DoF force
modeuint80: force control in the work frame, 1: force control in the tool frame
directionuint8Force control direction0: along the X-axis1: along the Y-axis2: along the Z-axis3: along the RX orientation4: along the RY orientation5: along the RZ orientation

Usage command demo:

json
rostopic pub /rm_driver/SetForcePosition_Cmd rm_msgs/Set_Force_Position "sensor: 0 mode: 0 direction: 0 N: 0"

Return command demo:

json
rostopic echo /rm_driver/SetForcePosition_Result

Parameter description:

ParameterTypeDescription
std_msgsBooltrue: setting succeeded, false: setting failed.

Stop the force-position hybrid control

Parameter description:

ParameterTypeDescription
std_msgsEmpty/

Usage command demo:

json
rostopic pub /rm_driver/StopForcePostion_Cmd std_msgs/Empty "{}"

Return command demo:

json
rostopic echo /rm_driver/StopForcePostion_Result

Parameter description:

ParameterTypeDescription
std_msgsBooltrue: setting succeeded, false: setting failed.

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:

ParameterTypeDescription
posture_numuint16#Gesture sequence number pre-stored in the dexterous hand, range: 1-40

Usage command demo:

json
rostopic pub /rm_driver/Hand_SetPosture rm_msgs/Hand_Posture "posture_num: 0"

Return command demo:

json
rostopic echo /rm_driver/Set_Hand_Posture_Result

Parameter description:

ParameterTypeDescription
std_msgsBooltrue: setting succeeded, false: setting failed.

Set the action sequence of the dexterous handHand_Seq.msg

Parameter description:

ParameterTypeDescription
seq_numuint16Sequence number pre-stored in the dexterous hand, range: 1-40

Usage command demo:

json
rostopic pub /rm_driver/Hand_SetSeq rm_msgs/Hand_Seq "seq_num: 0"

Return command demo:

json
rostopic echo /rm_driver/Set_Hand_Seq_Result

Parameter description:

ParameterTypeDescription
std_msgsBooltrue: 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:

ParameterTypeDescription
hand_angleuint16Array of finger angles, range: 0-1,000.
Additionally, -1 indicates that no action will be performed for this degree of freedom, and the current state will be maintained

Usage command demo:

json
rostopic pub /rm_driver/Hand_SetAngle rm_msgs/Hand_Angle "hand_angle: [0, 0, 0, 0, 0, 0]"

Return command demo:

json
rostopic echo /rm_driver/Set_Hand_Angle_Result

Parameter description:

ParameterTypeDescription
std_msgsBooltrue: setting succeeded, false: setting failed.

Set the speed of the dexterous handHand_Speed.msg

Parameter description:

ParameterTypeDescription
hand_speeduint16Finger speed, range: 1−1,000

Usage command demo:

json
rostopic pub /rm_driver/Hand_SetSpeed rm_msgs/Hand_Speed "hand_speed: 0"

Return command demo:

json
rostopic echo /rm_driver/Set_Hand_Speed_Result

Parameter description:

ParameterTypeDescription
std_msgsBooltrue: setting succeeded, false: setting failed.

Set the force threshold of the dexterous handHand_Force.msg

Parameter description:

ParameterTypeDescription
hand_Forceuint16Finger force, range: 1−1,000

Usage command demo:

json
rostopic pub /rm_driver/Hand_SetForce rm_msgs/Hand_Force "hand_force: 0"

Return command demo:

json
rostopic echo /rm_driver/Set_Hand_Force_Result

Parameter description:

ParameterTypeDescription
std_msgsBooltrue: 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:

ParameterTypeDescription
std_msgsEmpty msg/

Usage command demo:

json
rostopic pub /rm_driver/StartForcePositionMove_Cmd std_msgs/Empty "{}"

Return command demo:

json
rostopic echo /rm_driver/StartForcePositionMove_Result

Parameter description:

ParameterTypeDescription
std_msgsBooltrue: setting succeeded, false: setting failed.

Pass-through force-position hybrid control compensation (pose)Force_Position_Move_Pose.msg

Parameter description:

ParameterTypeDescription
Posegeometry_msgs/Pose#Quaternion
sensorgeometry_msgs/Pose#Type of sensor used, 0: 1-DoF force, 1: 6-DoF force
modegeometry_msgs/Pose#Mode, 0: along the work frame, 1: along the tool frame
dirgeometry_msgs/Pose#Force control direction, 0−5: X/Y/Z/Rx/Ry/Rz. For the 1-DoF force type, the default direction is the Z-axis
forcegeometry_msgs/Pose#Magnitude of the force, accuracy: 0.1 N or 0.1 N.m

Usage command demo:

json
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.

Pass-through force-position hybrid control compensation (radian)Force_Position_Move_Joint.msg

Parameter description:

ParameterTypeDescription
jointfloat32[]Radian.
sensorgeometry_msgs/PoseType of sensor used, 0: 1-DoF force, 1: 6-DoF force.
modegeometry_msgs/PoseMode, 0: along the work frame, 1: along the tool frame.
dirgeometry_msgs/PoseForce control direction, 0−5: X/Y/Z/Rx/Ry/Rz. For the 1-DoF force type, the default direction is the Z-axis.
forcegeometry_msgs/PoseMagnitude of the force, accuracy: 0.1 N or 0.1 N.m.
dofuint8Degree of freedom of the robotic arm.

Usage command demo:

json
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

Enable the pass-through force-position hybrid control compensation mode

Parameter description:

ParameterTypeDescription
std_msgsEmpty/

Usage command demo:

json
rostopic pub /rm_driver/StopForcePositionMove_Cmd std_msgs/Empty "{}"

Return command demo:

json
rostopic echo /rm_driver/StopForcePositionMove_Result

Parameter description:

ParameterTypeDescription
std_msgsBooltrue: 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:

ParameterTypeDescription
speedint16Speed percentage, -100 to 100Speed < 0: Lifting mechanism moves downSpeed > 0: Lifting mechanism moves upSpeed = 0: Lifting mechanism stops moving.

Usage command demo:

json
rostopic pub /rm_driver/Lift_SetSpeed rm_msgs/Lift_Speed "speed: 0"

Return command demo:

json
rostopic echo /rm_driver/Set_Lift_Speed_Result

Parameter description:

ParameterTypeDescription
std_msgsBooltrue: 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:

ParameterTypeDescription
heightuint16Target height, in mm, range: 0-2,600.
speeduint16Speed percentage, 1−100.

Usage command demo:

json
rostopic pub /rm_driver/Lift_SetHeight rm_msgs/Lift_Height "height: 0 speed: 0"

Return command demo:

json
rostopic echo /rm_driver/Plan_State

Parameter description:

ParameterTypeDescription
std_msgsBooltrue: setting succeeded, false: setting failed.

Get the state of the lifting mechanism

Parameter description:

ParameterTypeDescription
std_msgsEmpty msg/

Usage command demo:

json
rostopic pub /rm_driver/Lift_GetState std_msgs/Empty "{}"

Return command demo:

json
rostopic echo /rm_driver/LiftState

Parameter description:LiftState.msg

ParameterTypeDescription
heightint16Current height.
currentint16Current current.
err_flaguint16Drive error code.
modebyteCurrent lifting state0: idle1: forward speed motion2: forward position motion3: backward speed motion4: backward position motion.

Robotic arm state active reporting

Set the UDP robotic arm state active reporting configurationSet_Realtime_Push.msg

Parameter description:

ParameterTypeDescription
cycleuint16Set the broadcast cycle, which is a multiple of 5 ms (1 by default, i.e., 1*5=5 ms, or 200 Hz).
portuint16Set the broadcast port number (8089 by default).
force_coordinateuint16Set the frame for external force data (only supported by robotic arms with force sensors).
ipstringSet the custom reporting target IP address (192.168.1.10 by default).

Usage command demo:

json
rostopic pub /rm_driver/Set_Realtime_Push rm_msgs/Set_Realtime_Push "cycle: 1 port: 8089 force_coordinate: 0 ip: '192.168.1.10'"

Return command demo:

json
rostopic echo /rm_driver/Set_Realtime_Push_Result

Parameter description:

ParameterTypeDescription
std_msgsBooltrue: setting succeeded, false: setting failed.

Get the UDP robotic arm state active reporting configuration

Parameter description:

ParameterTypeDescription
std_msgsEmpty/

Usage command demo:

json
rostopic pub /rm_driver/Get_Realtime_Push std_msgs/Empty "{}"

Return command demo:

json
rostopic echo /rm_driver/Get_Realtime_Push_Result

Parameter description:

ParameterTypeDescription
std_msgsBooltrue: setting succeeded, false: setting failed.

UDP robotic arm state active reporting

6-DoF forceSix_Force.msg

Parameter description:

ParameterTypeDescription
force_fxfloat32Magnitude of the force along the x-axis.
force_fyfloat32Magnitude of the force along the y-axis.
force_fzfloat32Magnitude of the force along the z-axis.
force_mxfloat32Magnitude of rotation force along the x-axis.
force_myfloat32Magnitude of rotation force along the y-axis.
force_mzfloat32Magnitude of rotation force along the z-axis.

Usage command demo:

json
rostopic echo /rm_driver/UdpSixForce

Robotic arm errorstd_msgs::msg::UInt16

Parameter description:

ParameterTypeDescription
datauint16Robotic arm error.

Usage command demo:

json
rostopic echo /rm_driver/ArmError

System errorstd_msgs::msg::UInt16

Parameter description:

ParameterTypeDescription
datauint16System error.

Usage command demo:

json
rostopic echo/rm_driver/SysError

Joint errorJoint_Error_Code.msg

Parameter description:

ParameterTypeDescription
joint_erroruint16[]Each joint error

Usage command demo:

json
rostopic echo /rm_driver/JointErrorCode

Robot arm radian datasensor_msgs::msg::JointState

Parameter description:

ParameterTypeDescription
header.sequint32Time, in s.
header.stampclassTime, in s.
header.frame_idstringFrame name.
namestring[]Joint name.
positionfloat64[]Joint radian.
velocityfloat64[]Joint velocity. (Not currently in use)
secfloat64[]Joint force. (Not currently in use)

Usage command demo:

json
rostopic echo /joint_states
Function descriptionRobotic arm radian data
Parameter descriptionsensor_msgs::msg::JointStatebuiltin_interfaces/Time stampint32 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 commandrostopic echo /joint_states

Pose informationgeometry_msgs::msg::Pose Point

Parameter description:

ParameterTypeDescription
position.xfloat64Current coordinates of the robotic arm.
position.yfloat64Current coordinates of the robotic arm.
position.zfloat64Current coordinates of the robotic arm.
Quaternion orientation.xfloat64Current orientation of the robotic arm.
Quaternion orientation.yfloat64Current orientation of the robotic arm.
Quaternion orientation.zfloat64Current orientation of the robotic arm.
Quaternion orientation.wfloat64Current orientation of the robotic arm.

Usage command demo:

json
rostopic echo /rm_driver/Pose_State

Current external force data of the 6-DoF force sensor systemSix_Force.msg

Parameter description:

ParameterTypeDescription
force_fxfloat32Magnitude of external force along the x-axis of the current sensor.
force_fyfloat32Magnitude of external force along the y-axis of the current sensor.
force_fzfloat32Magnitude of external force along the z-axis of the current sensor.
force_mxfloat32Magnitude of rotation force along the x-axis.
force_myfloat32Magnitude of rotation force along the y-axis.
force_mzfloat32Magnitude of rotation force along the z-axis.

Usage command demo:

json
rostopic echo /rm_driver/UdpSixZeroForce

Reference frame for external force datastd_msgs::UInt16

Parameter description:

ParameterTypeDescription
force_fxfloat32Magnitude of the force along the x-axis.
datauint16Frame for external force data0: sensor frame1: current work frame2: current tool frameThis 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:

json
rostopic echo /rm_driver/Udp_Coordinate