Skip to content

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

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

Error description

Type of the system error

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

Type of the joint error

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

Type of the API error

S/NError Code (Hexadecimal)Description
10x0000Normal system
20x0001Request return: FALSE
30x0002Uninitialized robotic arm or invalid type input
40x0003Illegal timeout
50x0004Socket initialization failed
60x0005Socket connection failed
70x0006Socket transmission failed
80x0007Socket communication timeout
90x0008Unknown error
100x0009Incomplete data
110x000AArray length error
120x000BData type error
130x000CType error
140x000DCallback function missing
150x000EAbnormal robotic arm stop
160x000FExcessively long name of the trajectory file
170x0010Trajectory file verification failed
180x0011Trajectory file read failed
190x0012The controller is busy, please try again later
200x0013Invalid input
210x0014Full data queue
220x0015Computation failed
230x0016File open failed
240x0017Manual stop of the force control calibration
250x0018No savable trajectory

Joint configuration

Clear the joint error code Jointerrclear.msg

Parameter description:

ParameterTypeDescription
joint_numuint8Corresponding joint number, 1−6 from the base to the robotic arm's gripper.
blockboolBlocking/Non-blocking mode, true: blocking mode, false: non-blocking mode.

Usage command demo:

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

Return command demo:

json
ros2 topic echo /rm_driver/set_joint_err_clear_result

Parameter description:

ParameterTypeDescription
std_msgsbooltrue: setting succeeded, false: setting failed.

Work frame setting

Change the current work frame

Parameter description:

ParameterTypeDescription
std_msgsStringROS built-in msg.

Usage command demo:

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

Return command demo:

json
ros2 topic echo /rm_driver/change_work_frame_result

Parameter description:

ParameterTypeDescription
std_msgsbooltrue: setting succeeded, false: setting failed.

Frame getting

Get the current tool frame

Parameter description:

ParameterTypeDescription
std_msgsEmptyROS built-in msg.

Usage command demo:

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

Return command demo: Name of the current tool frame.

json
ros2 topic echo /rm_driver/get_current_tool_frame_result

Get the names of all tool frames

Parameter description:

ParameterTypeDescription
std_msgsEmptyROS built-in msg.

Usage command demo:

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

Return command demo: Names of all tool frames.

json
ros2 topic echo /rm_driver/get_all_tool_frame_result

Get the current work frame

Parameter description:

ParameterTypeDescription
std_msgsEmptyROS built-in msg.

Usage command demo:

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

Return command demo:

json
ros2 topic echo /rm_driver/get_curr_workFrame_result

Parameter description:

ParameterTypeDescription
std_msgsbooltrue: setting succeeded, false: setting failed.

Get the names of all work frames

Parameter description:

ParameterTypeDescription
std_msgsEmptyROS built-in msg.

Usage command demo:

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

Return command demo: Names of all work frames.

json
ros2 topic echo /rm_driver/get_all_work_frame_result

Robotic arm state getting

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

Parameter description:

ParameterTypeDescription
std_msgsEmptyROS built-in msg.

Usage command demo:

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

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

json
ros2 topic echo /rm_driver/get_current_arm_original_state_result

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

Parameter description:

ParameterTypeDescription
std_msgsEmptyROS built-in msg.

Usage command demo:

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

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

json
ros2 topic echo /rm_driver/get_current_arm_state_result

Robotic arm motion planning

Joint motion

Parameter description:

ParameterTypeDescription
jointfloat32[6]Joint angle, in rad.
speeduint8Speed percentage, 0−100.
blockboolBlocking/Non-blocking mode, true: blocking mode, false: non-blocking mode.

Usage command demo: 6-DoF robotic arm:

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

7-DoF robotic arm:

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

Return command demo:

json
ros2 topic echo /rm_driver/movej_result

Parameter description:

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

Cartesian-space linear motion Movel.msg

Parameter description:

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

Usage command demo: Firstly, execute the MoveJ_P:

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

Then, execute the MoveL:

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

Return command demo:

json
ros2 topic echo /rm_driver/movel_result

Parameter description:

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

Cartesian-space circular motion Movec.msg

ParameterTypeDescription
pose_midgeometry_msgs/PoseMiddle pose of the robotic arm, including x, y, z coordinates (float type, in m) + quaternion.
pose_endgeometry_msgs/PoseEnd pose of the robotic arm, including x, y, z coordinates (float type, in m) + quaternion.
speeduint8Speed percentage, 0−100.
blockboolBlocking/Non-blocking mode, true: blocking mode, false: non-blocking mode.

Usage command demo: Firstly, execute the MoveJ_P:

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

Then, execute the MoveC to reach the given position:

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

Return command demo:

json
ros2 topic echo /rm_driver/movec_result

Joint angle pass-through via CANFD JointPos.msg

ParameterTypeDescription
jointfloat32[6]Joint angle, in rad.
followboolFollow state, true: high follow, false: low follow, default: high follow.
expandfloat32Expansion angle, in rad.
blockboolBlocking/Non-blocking mode, true: blocking mode, false: non-blocking mode.

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

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

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

Pose pass-through via CANFD Jointpos.msg

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

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

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

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

Joint space planning to target pose Movejp.msg

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

Usage command demo:

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

Return command demo:

json
ros2 topic echo /rm_driver/movej_p_result

Parameter description:

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

Quick stop std_msgs

ParameterTypeDescription
databoolQuick/Non-quick stop, true: quick stop, false: non-quick stop.

Usage command demo:

json
ros2 topic pub /rm_driver/move_stop_cmd std_msgs/msg/Bool "data: true"

Return command demo:

json
ros2 topic echo /rm_driver/move_stop_result

Parameter description:

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

Controller configuration

Get the controller version Armsoftversion.msg

ParameterTypeDescription
planversionstringKernel version of the user interface.
ctrlversionstringReal-time kernel version.
kernal1stringReal-time version of kernel 1.
kernal2stringReal-time version of kernel 2.
productversionstringModel of the robotic arm.

Usage command demo:

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

Return command demo:

json
ros2 topic echo /rm_driver/get_arm_software_version_result

Parameter description:

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

End effector IO configuration

Set the tool power output std_msgs

ParameterTypeDescription
datauint16Power output type, range: 0−3, 0: 0 V, 1: 5 V, 2: 12 V, 3: 24 V.

Usage command demo:

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

Return command demo:

json
ros2 topic echo /rm_driver/set_tool_voltage_result

Parameter description:

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

Gripper control

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

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

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

Usage command demo:

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

Return command demo:

json
ros2 topic echo /rm_driver/set_gripper_pick_result

Parameter description:

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

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

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

Usage command demo:

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

Return command demo:

json
ros2 topic echo /rm_driver/set_gripper_pick_on_result

Parameter description:

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

Set the gripper to a given position Gripperset.msg

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

Usage command demo:

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

Return command demo:

json
ros2 topic echo /rm_driver/set_gripper_position_result

Parameter description:

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

Drag teaching and trajectory replay

Set the force-position hybrid control Setforceposition.msg

ParameterTypeDescription
sensoruint80: 1-DoF force, 1: 6-DoF force
uint8 mode: 0: force control in the base frame, 1: force control in the tool frame.
directionuint8Force control direction, 0: along the X-axis, 1: along the Y-axis, 2: along the Z-axis, 3: along the RX orientation, 4: along the RY orientation, 5: along the RZ orientation.
nint16Magnitude of the force, unit: N, accuracy: 0.1 N.
blockboolBlocking/Non-blocking mode, true: blocking mode, false: non-blocking mode.

Usage command demo:

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

Return command demo:

json
ros2 topic echo /rm_driver/set_force_postion_result

Parameter description:

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

Stop the force-position hybrid control std_msgs

ParameterTypeDescription
databoolBlocking/Non-blocking mode, true: blocking mode, false: non-blocking mode.

Usage command demo:

json
ros2 topic pub /rm_driver/stop_force_postion_cmd std_msgs/msg/Bool "data: true"

Return command demo:

json
ros2 topic echo /rm_driver/clear_force_data_result

Parameter description:

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

Use of the 6-DoF force sensor

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

Clear the 6-DoF force data std_msgs

ParameterTypeDescription
databoolBlocking/Non-blocking mode, true: blocking mode, false: non-blocking mode.

Usage command demo:

json
ros2 topic pub /rm_driver/clear_force_data_cmd std_msgs/msg/Bool "data: true"

Return command demo:

json
ros2 topic echo /rm_driver/clear_force_data_result

Parameter description:

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

Control of the five-fingered dexterous hand

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

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

ParameterTypeDescription
posture_numuint16Gesture sequence number pre-stored in the dexterous hand, range: 1−40.
databoolBlocking/Non-blocking mode, true: blocking mode, false: non-blocking mode.

Usage command demo:

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

Return command demo:

json
ros2 topic echo /rm_driver/set_hand_posture_result

Parameter description:

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

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

ParameterTypeDescription
seq_numuint16Action sequence number pre-stored in the dexterous hand, range: 1−40.
databoolBlocking/Non-blocking mode, true: blocking mode, false: non-blocking mode.

Usage command demo:

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

Return command demo:

json
ros2 topic echo /rm_driver/set_hand_seq_result

Parameter description:

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

Set the angles of the dexterous hand Handangle.msg

ParameterTypeDescription
hand_angleint16[6]Array of finger angles, range: 0−1,000.
Additionally, -1 indicates that no action will be performed for this degree of freedom, and the current state will be maintained.
databoolBlocking/Non-blocking mode, true: blocking mode, false: non-blocking mode.

Usage command demo:

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

Return command demo:

json
ros2 topic echo /rm_driver/set_hand_angle_result

Parameter description:

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

Set the speed of the dexterous hand Handspeed.msg

ParameterTypeDescription
hand_speedint16[6]Finger speed, range: 1−1,000.
databoolBlocking/Non-blocking mode, true: blocking mode, false: non-blocking mode.

Usage command demo:

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

Return command demo:

json
ros2 topic echo /rm_driver/set_hand_speed_result

Parameter description:

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

Set the force threshold of the dexterous hand Handforce.msg

ParameterTypeDescription
hand_forceint16Finger force, range: 1−1,000.
databoolBlocking/Non-blocking mode, true: blocking mode, false: non-blocking mode.

Usage command demo:

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

Return command demo:

json
ros2 topic echo /rm_driver/set_hand_force_result

Parameter description:

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

Lifting mechanism

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

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

ParameterTypeDescription
speedint16Speed percentage, -100−100, speed<0: lifting mechanism moves down, speed>0: lifting mechanism moves up, speed=0: lifting mechanism stops moving.
databoolBlocking/Non-blocking mode, true: blocking mode, false: non-blocking mode.

Usage command demo:

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

Return command demo:

json
ros2 topic echo /rm_driver/set_lift_speed_result

Parameter description:

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

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

ParameterTypeDescription
heightint16Target height, unit: mm, range: 0−2,600.
speedint16Speed percentage, 1−100.
databoolBlocking/Non-blocking mode, true: blocking mode, false: non-blocking mode.

Usage command demo:

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

Return command demo:

json
ros2 topic echo /rm_driver/set_lift_height_result

Parameter description:

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

Get the state of the lifting mechanism Liftstate.msg

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

Usage command demo:

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

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

json
ros2 topic echo /rm_driver/get_lift_state_result

Pass-through force-position hybrid control compensation mode

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

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

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

Usage command demo:

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

Return command demo:

json
ros2 topic echo /rm_driver/start_force_position_move_result

Parameter description:

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

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

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

Usage command demo:

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

Return command demo:

json
ros2 topic echo /rm_driver/stop_force_position_move_result

Parameter description:

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

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

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

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

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

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

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

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

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

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

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

Robotic arm state active reporting

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

ParameterTypeDescription
cycleuint16Set the broadcast cycle, in multiple of 5 ms (1 by default, i.e., 1*5=5 ms, or 200 Hz).
portuint16Set the broadcast port number (8089 by default).
force_coordinateuint16Set the frame for external force data (only supported by robotic arms with force sensors).
ipstringSet the custom pushing target IP address (192.168.1.10 by default).
forcefloat32Magnitude of the force, in N.
followboolFollow state, true: high follow, false: low follow.

Usage command demo:

json
ros2 topic pub --once /rm_driver/set_realtime_push_cmd rm_ros_interfaces/msg/Setrealtimepush "cycle: 1<br>port: 8089 force_coordinate: 0 ip: '192.168.1.10'"

Return command demo:

json
ros2 topic echo /rm_driver/set_realtime_push_result

Parameter description:

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

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

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

Usage command demo:

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

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

json
ros2 topic echo /rm_driver/get_realtime_push_result

UDP robotic arm state active reporting

6-DoF force Sixforce.msg

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

Usage command demo:

json
ros2 topic echo /rm_driver/udp_six_force

Robotic arm error std_msgs

ParameterTypeDescription
datauint16Robotic arm error.

Usage command demo:

json
ros2 topic echo /rm_driver/udp_six_force

System error std_msgs

ParameterTypeDescription
datauint16System error.

Usage command demo:

json
ros2 topic echo /rm_driver/udp_sys_err

Joint error Jointerrorcode.msg

ParameterTypeDescription
joint_erroruint16Each joint error.
dofuint8Degree of freedom of the robotic arm.

Usage command demo:

json
ros2 topic echo /rm_driver/udp_joint_error_code

Robotic arm radian data sensor_msgs

ParameterTypeDescription
stampint32sec: second.
nanosecuint32Time, in ns.
frame_idstringFrame name.
namestringJoint name.
positionfloat64Joint radian.
velocityfloat64Joint velocity.
effortfloat64Joint force.

Usage command demo:

json
ros2 topic echo /joint_states

Pose geometry_msgs

ParameterTypeDescription
Point positionfloat64Current coordinates of the robotic arm: x, y, z.
Quaternion orientationfloat64Current orientation of the robotic arm: x, y, z, w.

Usage command demo:

json
ros2 topic echo /rm_driver/udp_arm_position

External force data of the current 6-DoF force sensor frame Sixforce.msg

ParameterTypeDescription
force_fxfloat32Magnitude of external force along the X-axis of the current sensor frame.
force_fyfloat32Magnitude of external force along the Y-axis of the current sensor frame.
force_fzfloat32Magnitude of external force along the Z-axis of the current sensor frame.
force_mxfloat32Magnitude of the rotation force along the X-axis of the current sensor frame.
force_myfloat32Magnitude of the rotation force along the Y-axis of the current sensor frame.
force_mzfloat32Magnitude of the rotation force along the Z-axis of the current sensor frame.

Usage command demo:

json
ros2 topic echo /rm_driver/udp_six_zero_force

Reference frame for external force data std_msgs

ParameterTypeDescription
datauint16Frame for external force data, 0: sensor frame, 1: current work frame, 2: current tool frame. This data will affect the reference frame for the external force data of the 6-DoF force sensor.

Usage command demo:

json
ros2 topic echo /rm_driver/udp_arm_coordinate