更换为实际的机械臂型号,可选择的机械臂型号有65、63、eco65、eco63、75、gen72。
+底层驱动启动成功后,将显示以下画面。
+
+### 功能包进阶使用
+当我们的机械臂IP被改变后我们的启动指令就失效了,再直接使用如上指令就无法成功连接到机械臂了,我们可以通过修改如下配置文件,重新建立连接。
+该配置文件位于我们的rm_driver功能包下的config文件夹下。
+
+其配置文件内容如下:
+
+```
+rm_driver:
+ ros__parameters:
+ #robot param
+ arm_ip: "192.168.1.18" #设置TCP连接时的IP
+ tcp_port: 8080 #设置TCP连接时的端口
+
+ arm_type: "RM_65" #机械臂型号设置
+ arm_dof: 6 #机械臂自由度设置
+
+ udp_ip: "192.168.1.10" #设置udp主动上报IP
+ udp_cycle: 5 #udp主动上报周期,需要是5的倍数
+ udp_port: 8089 #设置udp主动上报端口
+ udp_force_coordinate: 0 #设置系统受力时六维力的基准坐标,0为传感器坐标系 1为当前工作坐标系 2为当前工具坐标系
+ udp_hand: false #设置灵巧手udp主动上报使能
+ udp_plus_base: false #设置末端设备基础信息udp主动上报使能
+ udp_plus_state: false #设置末端设备实时信息udp主动上报使能
+
+ trajectory_mode: 0 #设置高跟随模式下,支持多种模式,0-完全透传模式、1-曲线拟合模式、2-滤波模式
+ radio: 0 #设置曲线拟合模式下平滑系数(范围0-100)或者滤波模式下的滤波参数(范围0-1000),数值越大表示平滑效果越好
+ arm_joints: ["joint1", "joint2", "joint3", "joint4", "joint5", "joint6"]
+```
+
+其中主要有以下几个参数。
+* arm_ip:改参数代表机械臂当前的IP
+* tcp_port:设置TCP连接时的端口。
+* arm_type:该参数代表机械臂当前的型号,可以选择的参数有RM_65(65系列)、RM_eco65(ECO65系列)、RM_eco63(ECO63系列)、RML_63(63系列)、RM_75(75系列)、GEN_72(GEN72系列)。
+* arm_dof: 机械臂自由度设置。6为6自由度,7为7自由度。
+* udp_ip: 设置udp主动上报目标IP。
+* udp_cycle:udp主动上报周期,需要是5的倍数。
+* udp_port:设置udp主动上报端口。
+* udp_force_coordinate:设置系统受力时六维力的基准坐标,0为传感器坐标系(原始数据) 1为当前工作坐标系 2为当前工具坐标系。
+* trajectory_mode:设置高跟随模式下,支持多种模式,0-完全透传模式、1-曲线拟合模式、2-滤波模式
+* radio:设置曲线拟合模式下平滑系数(范围0-100)或者滤波模式下的滤波参数(范围0-1000),数值越大表示平滑效果越好
+* 在实际使用时,我们选择对应的launch文件启动时会自动选择正确的型号,若有特殊要求可在此处进行相应的参数修改,修改之后需要在工作空间目录下进行重新编译,之后修改的配置才会生效。
+* 在工作空间目录运行colcon build指令。
+
+```
+rm@rm-desktop: ~/ros2_ws$ colcon build
+```
+
+* 编译成功后可按如上指令进行功能包启动。
+## rm_driver功能包架构说明
+### 功能包文件总览
+当前rm_driver功能包的文件构成如下。
+
+```
+├── CMakeLists.txt #编译规则文件
+├── config #配置文件夹
+│ ├── rm_63_config.yaml #63配置文件
+│ ├── rm_65_config.yaml #65配置文件
+│ ├── rm_75_config.yaml #75配置文件
+│ ├── rm_eco65_config.yaml #eco65配置文件
+│ ├── rm_eco63_config.yaml #eco63配置文件
+│ └── rm_gen72_config.yaml #gen725配置文件
+├── doc
+│ ├── RealMan Robotic Arm rm_driver Topic Detailed Description (ROS2).md
+│ ├── rm_driver1.png
+│ ├── rm_driver2.png
+│ ├── rm_driver3.png
+│ ├── rm_driver4.png
+│ └── 睿尔曼机械臂ROS2rm_driver话题详细说明.md
+├── include #依赖头文件文件夹
+│ └── rm_driver
+│ ├── cJSON.h #API头文件
+│ ├── constant_define.h #API头文件
+│ ├── rman_int.h #API头文件
+│ ├── rm_base_global.h #API头文件
+│ ├── rm_base.h #API头文件
+│ ├── rm_define.h #API头文件
+│ ├── rm_driver.h #rm_driver.cpp头文件
+│ ├── rm_praser_data.h #API头文件
+│ ├── rm_queue.h #API头文件
+│ ├── rm_service_global.h #API头文件
+│ ├── rm_service.h #API头文件
+│ └── robot_define.h #API头文件
+├── launch
+│ ├── rm_63_driver.launch.py #63启动文件
+│ ├── rm_65_driver.launch.py #65启动文件
+│ ├── rm_75_driver.launch.py #75启动文件
+│ ├── rm_eco65_driver.launch.py #eco65启动文件
+│ ├── rm_eco63_driver.launch.py #eco63启动文件
+│ └── rm_gen72_driver.launch.py #gen72启动文件
+├── lib
+│ ├── libRM_Service.so -> libRM_Service.so.1.0.0 #API库文件
+│ ├── libRM_Service.so.1 -> libRM_Service.so.1.0.0 #API库文件
+│ ├── libRM_Service.so.1.0 -> libRM_Service.so.1.0.0 #API库文件
+│ ├── libRM_Service.so.1.0.0 #API库文件
+│ ├── linux_arm_service_release_v4.3.7.t7.tar.bz2 #API库文件
+│ └── linux_x86_service_release_v4.3.7.t7.tar.bz2 #API库文件
+├── package.xml #依赖声明文件
+├── README_CN.md
+├── README.md
+└── src
+ └── rm_driver.cpp #驱动代码源文件
+```
+
+## rm_driver话题说明
+rm_driver的话题较多,可以通过如下指令了解其话题信息。
+
+
+主要为套用API实现的一些机械臂本体的功能,其详细介绍和使用在此不详细展开,可以通过专门的文档《[睿尔曼机械臂ROS2话题详细说明](https://github.com/RealManRobot/ros2_rm_robot/blob/humble/rm_driver/doc/%E7%9D%BF%E5%B0%94%E6%9B%BC%E6%9C%BA%E6%A2%B0%E8%87%82ROS2rm_driver%E8%AF%9D%E9%A2%98%E8%AF%A6%E7%BB%86%E8%AF%B4%E6%98%8E.md)》进行查看。
diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_driver/config/rm_65_config.yaml b/HiveCoreR0/src/ros2_rm_robot-humble/rm_driver/config/rm_65_config.yaml
new file mode 100755
index 0000000..815b723
--- /dev/null
+++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_driver/config/rm_65_config.yaml
@@ -0,0 +1,21 @@
+rm_driver:
+ ros__parameters:
+ #robot param
+ arm_ip: "192.168.1.18" #设置TCP连接时的IP
+ tcp_port: 8080 #设置TCP连接时的端口
+
+ arm_type: "RM_65" #机械臂型号设置
+ arm_dof: 6 #机械臂自由度设置
+
+ udp_ip: "192.168.1.10" #设置udp主动上报IP
+ udp_cycle: 5 #udp主动上报周期,需要是5的倍数。
+ udp_port: 8089 #设置udp主动上报端口
+ udp_force_coordinate: 0 #设置系统受力时六维力的基准坐标,0为传感器坐标系 1为当前工作坐标系 2为当前工具坐标系
+ udp_hand: false #设置灵巧手udp主动上报使能
+ udp_plus_base: false #设置末端设备基础信息udp主动上报使能
+ udp_plus_state: false #设置末端设备实时信息udp主动上报使能
+
+ trajectory_mode: 0 #设置高跟随模式下,支持多种模式,0-完全透传模式、1-曲线拟合模式、2-滤波模式
+ radio: 0 #设置曲线拟合模式下平滑系数(范围0-100)或者滤波模式下的滤波参数(范围0-1000),数值越大表示平滑效果越好
+
+ arm_joints: ["joint1", "joint2", "joint3", "joint4", "joint5", "joint6"]
diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_driver/doc/RealMan Robotic Arm rm_driver Topic Detailed Description (ROS2).md b/HiveCoreR0/src/ros2_rm_robot-humble/rm_driver/doc/RealMan Robotic Arm rm_driver Topic Detailed Description (ROS2).md
new file mode 100755
index 0000000..1e62f46
--- /dev/null
+++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_driver/doc/RealMan Robotic Arm rm_driver Topic Detailed Description (ROS2).md
@@ -0,0 +1,1128 @@
+
+
+[中文简体](https://github.com/RealManRobot/ros2_rm_robot/blob/humble/rm_driver/doc/%E7%9D%BF%E5%B0%94%E6%9B%BC%E6%9C%BA%E6%A2%B0%E8%87%82ROS2rm_driver%E8%AF%9D%E9%A2%98%E8%AF%A6%E7%BB%86%E8%AF%B4%E6%98%8E.md)|
+[English](https://github.com/RealManRobot/ros2_rm_robot/blob/humble/rm_driver/doc/RealMan%20Robotic%20Arm%20rm_driver%20Topic%20Detailed%20Description%20(ROS2).md)
+
+
+
+
+
+# RealMan Robotic Arm rm_driver Topic Detailed Description (ROS2) V1.1.6
+
+RealMan Intelligent Technology (Beijing) Co., Ltd.
+
+Revision History:
+
+|No. | Date | Comment |
+| :---: | :---- | :---: |
+|V1.0 | 2024-2-18 | Draft |
+|V1.1 | 2024-7-8 | Amend(Add teaching instructions3.6) |
+|V1.1.1| 2024-8-13| Amend(Add six-axis topic) |
+|V1.1.2| 2024-9-25| Amend(revise coordinate topic description)|
+|V1.1.3| 2024-10-31|Amend(Add Agile Hand UDP Adaptation,Follow Adaptation)|
+|V1.1.4| 2024-12-25|Amend(Modify UDP report content)|
+|V1.1.5| 2025-02-19|Amend(API2 Adaptation; add end ecosystem protocol interface; update UDP interface) |
+|V1.1.6| 2025-05-26|Revision (adapted to fourth generation controllers, added version query interface, added Cartesian space linear offset motion interface, added Modbus interface, added trajectory list interface)|
+
+
+
+## Content
+
+* 1.[Introduction](#Introduction)
+* 2.[Error Description](#Error_Description)
+* 2.1[Controller error type](#Controller_error_type)
+* 2.2[Joint error type](#Joint_error_type)
+* 2.3[API error type](#API_error_type)
+* 3.[ROS Function Package Robotic Arm Instructions](#ROS_Function_Package_Robotic_Arm_Instructions)
+* 3.1[Joint Configuration](#Joint_Configuration)
+* 3.1.1[Clear the joint's error code](#Clear_the_joint's_error_code)
+* 3.2[Get version](#Get_version)
+* 3.2.1[Get basic information of robotic arm](#Get_basic_information_of_robotic_arm)
+* 3.2.2[Get the software information of the robotic arm](#Get_the_software_information_of_the_robotic_arm)
+* 3.2.3[Get the joint software version](#Get_the_joint_software_version)
+* 3.2.4[Get the software version of the end interface board](#Get_the_software_version_of_the_end_interface_board)
+* 3.3[Functions related to the work coordinate system settings](#Functions_related_to_the_work_coordinate_system_settings)
+* 3.3.1[Change the current work coordinate system](#Change_the_current_work_coordinate_system)
+* 3.4[Coordinate system query](#Coordinate_system_query)
+* 3.4.1[Get the current tool coordinate system](#Get_the_current_tool_coordinate_system)
+* 3.4.2[Get all tool coordinate system names](#Get_all_tool_coordinate_system_names)
+* 3.4.3[Get the current work coordinate system](#Get_the_current_work_coordinate_system)
+* 3.4.4[Get all work coordinate system names](#Get_all_work_coordinate_system_names)
+* 3.5[Functions related to the arm state query](#Functions_related_to_the_arm_state_query)
+* 3.5.1[Get the current state of the robot arm - return each joint angle + Euler angle](#Get_the_current_state_of_the_robot_arm-return_each_joint_angle_and_Euler_angle)
+* 3.5.2[Get the current state of the robotic arm - return each joint radians + quaternion](#Get_the_current_state_of_the_robotic_arm-return_each_joint_radians_and_quaternion)
+* 3.6[Functions related to motion planning of the robotic arm](#Functions_related_to_motion_planning_of_the_robotic_arm)
+* 3.6.1[Joint Space Motion](#Joint_Space_Motion)
+* 3.6.2[Linear motion in Cartesian space](#Linear_motion_in_Cartesian_space)
+* 3.6.3[Cartesian space linear offset motion](#Cartesian_space_linear_offset_motion)
+* 3.6.4[Circular motion in Cartesian space](#Circular_motion_in_Cartesian_space)
+* 3.6.5[Joint angle CANFD transmission](#Joint_angle_CANFD_transmission)
+* 3.6.6[Customize high following mode joint angle CANFD transmission](#Customize_high_following_mode_joint_angle_CANFD_transmission)
+* 3.6.7[Pose CANFD transmission](#Pose_CANFD_transmission)
+* 3.6.8[Customize high following mode pose CANFD transmission](#Customize_high_following_mode_pose_CANFD_transmission)
+* 3.6.9[Joint space planning to target pose](#Joint_space_planning_to_target_pose)
+* 3.6.10[Trajectory emergency stop](#Trajectory_emergency_stop)
+* 3.6.11[Emergency stop](#Emergency_stop)
+* 3.7[Teaching instructions](#Teaching_instructions)
+* 3.7.1[Joint teaching](#Joint_teaching)
+* 3.7.2[Position teaching](#Position_teaching)
+* 3.7.3[Attitude teaching](#Attitude_teaching)
+* 3.7.4[Stop teaching](#Stop_teaching)
+* 3.8[Trajectory File](#Trajectory_File)
+* 3.8.1[Query Trajectory List ](#Query_Trajectory_List)
+* 3.8.2[Start Running Specified Trajectory](#Start_Running_Specified_Trajectory)
+* 3.8.3[Delete Specified Trajectory File](#Delete_Specified_Trajectory_File)
+* 3.8.4[Save Trajectory File](#Save_Trajectory_File)
+* 3.8.5[Query Flowchart Program Run State](#Query_Flowchart_Program_Run_State)
+* 3.9[Modbus Configuration](#Modbus_Configuration)
+* 3.9.1[Set Controller RS485 Mode](#Set_Controller_RS485_Mode)
+* 3.9.2[Get Controller RS485 Mode](#Get_Controller_RS485_Mode)
+* 3.9.3[Set Tool End RS485 Mode](#Set_Tool_End_RS485_Mode)
+* 3.9.4[Get Tool End RS485 Mode](#Get_Tool_End_RS485_Mode)
+* 3.10[ModbusTCP Master](#ModbusTCP_Master)
+* 3.10.1[Add Modbus TCP Master](#Add_Modbus_TCP_Master)
+* 3.10.2[Update Modbus TCP Master](#Update_Modbus_TCP_Master)
+* 3.10.3[Delete Modbus TCP Master](#Delete_Modbus_TCP_Master)
+* 3.10.4[Get Specified Modbus TCP Master](#Get_Specified_Modbus_TCP_Master)
+* 3.10.5[Get Modbus TCP Master List](#Get_Modbus_TCP_Master_List)
+* 3.11[Tool end controller end RTU Modbus protocol reads and writes data](#Tool_end_controller_end_RTU_Modbus_protocol_reads_and_writes_data)
+* 3.11.1[Modbus RTU Protocol Read Coils](#Modbus_RTU_Protocol_Read_Coils)
+* 3.11.2[Modbus RTU Protocol Write Coils](#Modbus_RTU_Protocol_Write_Coils)
+* 3.11.3[Modbus RTU Protocol Read Discrete Inputs](#Modbus_RTU_Protocol_Read_Discrete_Inputs)
+* 3.11.4[Modbus RTU Protocol Read Holding Registers](#Modbus_RTU_Protocol_Read_Holding_Registers)
+* 3.11.5[Modbus RTU Protocol Write Holding Registers](#Modbus_RTU_Protocol_Write_Holding_Registers)
+* 3.11.6[Modbus RTU Protocol Read Input Registers](#Modbus_RTU_Protocol_Read_Input_Registers)
+* 3.12[Controller Modbus TCP protocol reads and writes data](#Controller_Modbus_TCP_protocol_reads_and_writes_data)
+* 3.12.1[Modbus TCP Protocol Read Coils](#Modbus_TCP_Protocol_Read_Coils)
+* 3.12.2[Modbus TCP Protocol Write Coils](#Modbus_TCP_Protocol_Write_Coils)
+* 3.12.3[Modbus TCP Protocol Read Discrete Inputs](#Modbus_TCP_Protocol_Read_Discrete_Inputs)
+* 3.12.4[Modbus TCP Protocol Read Holding Registers](#Modbus_TCP_Protocol_Read_Holding_Registers)
+* 3.12.5[Modbus TCP Protocol Write Holding Registers](#Modbus_TCP_Protocol_Write_Holding_Registers)
+* 3.12.5[Modbus TCP Protocol Read Input Registers](#Modbus_TCP_Protocol_Read_Input_Registers)
+* 3.13[Functions related to the IO configuration of the end tool](#Functions_related_to_the_IO_configuration_of_the_end_tool)
+* 3.13.1[Setting the tool voltage output](#Setting_the_tool_voltage_output)
+* 3.14[Functions related to the control of the end gripper - optional](#Functions_related_to_the_control_of_the_end_gripper)
+* 3.14.1[Setting the Gripper Pick](#Setting_the_Gripper_Pick)
+* 3.14.2[Setting the gripper pick-on](#Setting_the_gripper_pick-on)
+* 3.14.3[Setting the gripper to the given position](#Setting_the_gripper_to_the_given_position)
+* 3.15[Functions related to the drag teach and trajectory reproduction](#Functions_related_to_the_drag_teach_and_trajectory_reproduction)
+* 3.15.1[Set the force-position mixing control](#Set_the_force-position_mixing_control)
+* 3.15.2[Stop the force-position mixing control](#Stop_the_force-position_mixing_control)
+* 3.16[Functions related to the use of six-axis force sensors at the end - optional](#Functions_related_to_the_use_of_six-axis_force_sensors_at_the_end)
+* 3.16.1[Query the six-axis force data](#Query_the_six-axis_force_data)
+* 3.16.2[Clearing the six-axis force Data](#Clearing_the_six-axis_force_Data)
+* 3.17[Functions related to the control of the five-finger dexterous hand - optional](#Functions_related_to_the_control_of_the_five-finger_dexterous_hand)
+* 3.17.1[Setting the serial number of the dexterous hand posture](#Setting_the_serial_number_of_the_dexterous_hand_posture)
+* 3.17.2[Set the dexterous hand action sequence number](#Set_the_dexterous_hand_action_sequence_number)
+* 3.17.3[Setting the angles of various degrees of freedom for the dexterous hand](#Setting_the_angles_of_various_degrees_of_freedom_for_the_dexterous_hand)
+* 3.17.4[Setting the dexterous hand speed](#Setting_the_dexterous_hand_speed)
+* 3.17.5[Setting the force threshold of the dexterous hand](#Setting_the_force_threshold_of_the_dexterous_hand)
+* 3.17.6[Setting the angle following of the dexterous hand](#Setting_the_angle_following_of_the_dexterous_hand)
+* 3.17.7[Setting the posture following of the dexterous hand](#Setting_the_posture_following_of_the_dexterous_hand)
+* 3.18[Lifting mechanism](#Lifting_mechanism)
+* 3.18.1[Speed open-loop control of the lifting mechanism](#Speed_open-loop_control_of_the_lifting_mechanism)
+* 3.18.2[Position closed-loop control of the lifting mechanism](#Position_closed-loop_control_of_the_lifting_mechanism)
+* 3.18.3[Get the lifting mechanism state](#Get_the_lifting_mechanism_state)
+* 3.19[End-Effector Ecosystem Command Set](#End_Effector_Ecosystem_Command_Set)
+* 3.19.1[Setting End-Effector Ecosystem Protocol Mode](#Setting_End_Effector_Ecosystem_Protocol_Mode)
+* 3.19.2[Querying End-Effector Ecosystem Protocol Mode](#Querying_End_Effector_Ecosystem_Protocol_Mode)
+* 3.19.3[Setting Tactile Sensor Mode](#Setting_Tactile_Sensor_Mode)
+* 3.19.4[Querying Tactile Sensor Mode](#Querying_Tactile_Sensor_Mode)
+* 3.20[Functions related to the transmissive force-position compensation Mode](#Functions_related_to_the_transmissive_force-position_compensation_Mode)
+* 3.20.1[Starting the transmissive force-position mixing control compensation mode](#Starting_the_transmissive_force-position_mixing_control_compensation_mode)
+* 3.20.2[Stopping the transmissive force-position mixing control compensation mode](#Stopping_the_transmissive_force-position_mixing_control_compensation_mode)
+* 3.20.3[Transmissive force-position mixing control compensation - joint](#Transmissive_force-position_mixing_control_compensation-joint)
+* 3.20.4[Transmissive force-position mixing control compensation - pose](#Transmissive_force-position_mixing_control_compensation-pose)
+* 3.21[Robotic arm state active reporting](#Robotic_arm_state_active_reporting)
+* 3.21.1[Setting UDP robotic arm state active reporting configuration](#Setting_UDP_robotic_arm_state_active_reporting_configuration)
+* 3.21.2[Getting UDP robotic arm state active reporting configuration](#Getting_UDP_robotic_arm_state_active_reporting_configuration)
+* 3.21.3[UDP robotic arm state active reporting](#UDP_robotic_arm_state_active_reporting)
+
+## Introduction
+
+RealMan provides ROS2 function packages based on API to help users control the robotic arm using ROS2. If you want to learn more about controlling the robotic arm, you can refer to the API documentation and instructions. In practical use, the user can establish communication with the robotic arm through the Ethernet port and control the robotic arm.
+
+## Error_Description
+
+### Controller_error_type
+
+| Serial No. | Error code (hexadecimal) | Error content |
+| :---: | :---- | :---: |
+| 1 | 0x0000 | System is normal |
+| 2 | 0x1001 | Joint communication is abnormal |
+| 3 | 0x1002 | The target angle exceeds the limit |
+| 4 | 0x1003 | This position is inaccessible and is a singular point |
+| 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 | The end interface board cannot be connected |
+| 10 | 0x1009 | Overspeed limit |
+| 11 | 0x100A | Overacceleration limit |
+| 12 | 0x100B | Joint brake is not opened |
+| 13 | 0x100C | Overspeed during drag teach |
+| 14 | 0x100D | Robotic arm collision |
+| 15 | 0x100E | No work coordinate system is available |
+| 16 | 0x100F | No tool coordinate system is available |
+| 17 | 0x1010 | Joint failure enabling error |
+
+### Joint_error_type
+
+| Serial No. | Error code (hexadecimal) | Error content |
+| :---: | :---- | :---: |
+| 1 | 0x0000 | Joint is normal |
+| 2 | 0x0001 | FOC error |
+| 3 | 0x0002 | Overvoltage |
+| 4 | 0x0004 | Undervoltage |
+| 5 | 0x0008 | Overtemperature |
+| 6 | 0x0010 | Start failed |
+| 7 | 0x0020 | Encoder error |
+| 8 | 0x0040 | Overcurrent |
+| 9 | 0x0080 | Software error |
+| 10 | 0x0100 | Temperature sensor error |
+| 11 | 0x0200 | Position limit-out error |
+| 12 | 0x0400 | Illegal joint ID |
+| 13 | 0x0800 | Position tracking error |
+| 14 | 0x1000 | Current detection error |
+| 15 | 0x2000 | Brake opening failed |
+| 16 | 0x4000 | Position command step warning |
+| 17 | 0x8000 | Multi-coil joint's coil lost the number |
+| 18 | 0xF000 | Communication frame loss |
+
+### API_error_type
+
+| Error Code (int) | Description | Resolution |
+| :---: | :---- | :--- |
+| 0 | System operating normally. | - |
+| 1 | Message request returned FALSE. |- Verify JSON command:
① Enable API DEBUG logs to capture raw JSON data.
② Check JSON syntax: Ensure correct formatting of brackets, quotes, commas, etc. (use a JSON validation tool).
③ Refer to API documentation to validate parameter names, data types, and value ranges.
④ After fixing issues, resend the command and check the status code and business data returned by the controller.
- Check robot arm status:
① Review real-time error messages in the robot arm controller or logs (e.g., hardware failures, limits exceeded), and reset, calibrate, or troubleshoot hardware issues as indicated.
② After resolving issues, resend the command and check the status code and business data returned by the controller.|
+| -1 | Data send failure, communication issue during transmission. | Check network connectivity:
Use tools like ping/telnet to test the communication link with the controller.|
+| -2 | Data receive failure, communication issue during transmission or controller timeout without response.|- Check network connectivity:
Use tools like ping/telnet to test the communication link with the controller.
- Verify version compatibility:
① Confirm that the controller firmware version supports the current API functionality. Refer to the [version change notes](https://develop.realman-robotics.com/robot4th/releaseNotes/releaseNotesfour/) for specific version compatibility.
② If the version is too low, upgrade the controller or use a compatible API version.
- When calling ModbusTCP interface: Applicable only when reading/writing to the controller's ModbusTCP device. After creating the robot arm control handle, you must call the rm_set_modbustcp_mode() interface, otherwise, no return value will be received.|
+| -3 | Return value parsing failure, received data format is incorrect or incomplete.|Verify version compatibility:
① Confirm that the controller firmware version supports the current API functionality. Refer to the [version change notes](https://develop.realman-robotics.com/robot4th/releaseNotes/releaseNotesfour/) for specific version compatibility.
② If the version is too low, upgrade the controller or use a compatible API version.|
+| -4 | Current device validation failed, i.e., the current device is not a joint/elevator/gripper/dexterous hand.| - Check for concurrent control of multiple devices: Ensure no other devices are sending motion commands to the robot arm, including movements of the robot arm, gripper, dexterous hand, and elevator.
- Real-time monitoring of command events: Register the callback function rm_get_arm_event_call_back:
① Capture device arrival events (e.g., motion completion, timeout);
② Use the device parameter in the callback to determine the specific type of device that triggered the event. |
+| -5 | Single-threaded blocking mode timed out without receiving a response, ensure the timeout setting is reasonable.| - Check timeout duration settings: In single-threaded blocking mode, you can configure the timeout for waiting for device motion completion. Ensure the timeout setting is greater than the device motion time.
- Check network connectivity:
Use tools like ping/telnet to test the communication link with the controller.|
+
+## ROS_Function_Package_Robotic_Arm_Instructions
+
+This section describes how to query and control the robotic arm through the topic of ROS.
+
+### Joint_Configuration
+
+#### Clear_the_joint's_error_code
+
+| Function description | Clear_the_joint's_error_code |
+| :---: | :---- |
+| Parameter description | Jointerrclear.msg
uint8 joint_num: The corresponding joint number, from the base to the end-effector of the robotic arm. For a 6-DoF arm, the joint numbers are sequentially 1 to 6. For a 7-DoF arm, the joint numbers are sequentially 1 to 7. |
+| Command example | ros2 topic pub /rm_driver/set_joint_err_clear_cmd rm_ros_interfaces/msg/Jointerrclear "joint_num: 1 " |
+| Return value | true-set successfully,false-set failed |
+| Return example | ros2 topic echo /rm_driver/set_joint_err_clear_result |
+
+### Get_version
+
+#### Get_basic_information_of_robotic_arm
+
+| Function description | Get_basic_information_of_robotic_arm |
+| :---: | :---- |
+| Parameter description | std_msgs::msg::Empty. |
+| Command example | ros2 topic pub --once /rm_driver/get_robot_info_cmd std_msgs/msg/Empty "{}" |
+| Return value | RobotInfo.msg
uint8 arm_dof: The degrees of freedom of the robotic arm (number of joints)
uint8 arm_model: The model of the robotic arm. Examples: 0=RM_65, 1=RM_75, 2=RML_63I (deprecated), 3=RML_63II, 4=RML_63III, 5=ECO_65, 6=ECO_62, 7=GEN_72, 8=ECO63, 9=Generic Robot
uint8 force_type: The version of the end-effector force sensor. Examples: 0=Standard, 1=One-Dimensional Force, 2=Six-Dimensional Force, 3=Integrated Six-Dimensional Force
uint8 robot_controller_version: The version of the robotic arm controller (3: Third Generation, 4: Fourth Generation)
bool state: Whether the reading was successful. |
+| Return example | ros2 topic echo /rm_driver/get_robot_info_result |
+
+#### Get_the_software_information_of_the_robotic_arm
+
+| Function description | Get_the_software_information_of_the_robotic_arm |
+| :---: | :---- |
+| Parameter description | std_msgs::msg::Empty. |
+| Command example | ros2 topic pub --once /rm_driver/get_arm_software_version_cmd std_msgs/msg/Empty "{}" |
+| Return value | Armsoftversion.msg
string product_version: The model of the robotic arm
string controller_version: The version of the robotic arm controller. If it is a fourth-generation controller, this field will be "4.0"
string algorithm_info: Algorithm library information
Softwarebuildinfo ctrl_info: Software information for the control layer
string dynamic_info: Dynamics version (third generation)
Softwarebuildinfo plan_info: Software information for the planning layer (third generation)
Softwarebuildinfo com_info: Software information for the communication module (fourth generation)
Softwarebuildinfo program_info: Software information for the flowchart programming module (fourth generation)
bool state: Query status - true for success, false for failure |
+| Return example | ros2 topic echo /rm_driver/get_arm_software_version_result |
+
+#### Get_the_joint_software_version
+
+| Function description | Get_the_joint_software_version |
+| :---: | :---- |
+| Parameter description | std_msgs::msg::Empty. |
+| Command example | ros2 topic pub --once /rm_driver/get_joint_software_version_cmd std_msgs/msg/Empty "{}" |
+| Return value | Jointversion.msg
string[7] joint_version: An array of software version numbers for each joint obtained. These need to be converted to hexadecimal. For example, if a joint version obtained is 54536, converting it to hexadecimal gives D508, which means the current joint version is Vd5.0.8 (for third-generation controllers).
bool state: Acquisition status - true for successful acquisition, false for failed acquisition. |
+| Return example | ros2 topic echo /rm_driver/get_joint_software_version_result |
+
+#### Get_the_software_version_of_the_end_interface_board
+
+| Function description | Get_the_software_version_of_the_end_interface_board |
+| :---: | :---- |
+| Parameter description | std_msgs::msg::Empty. |
+| Command example | ros2 topic pub --once /rm_driver/get_tool_software_version_cmd std_msgs/msg/Empty "{}" |
+| Return value | Toolsoftwareversionv4.msg
string tool_version: The software version number of the end-effector interface board
bool state: Query status, returns true for success, false for failure |
+| Return example | ros2 topic echo /rm_driver/get_tool_software_version_result |
+
+### Functions_related_to_the_work_coordinate_system_settings
+
+#### Change_the_current_work_coordinate_system
+
+| Function description | Change_the_current_work_coordinate_system |
+| :---: | :---- |
+| Parameter description | ROS msg std_msgs::msg::String |
+| Command example | ros2 topic pub /rm_driver/change_work_frame_cmd std_msgs/msg/String "data: 'Base'" |
+| Return value | true-set successfully,false-set failed |
+| Return example | ros2 topic echo /rm_driver/change_work_frame_result |
+
+### Coordinate_system_query
+
+#### Get_the_current_tool_coordinate_system
+
+| Function description | Get_the_current_tool_coordinate_system |
+| :---: | :---- |
+| Parameter description | ROS msg std_msgs::msg::Empty |
+| Command example | ros2 topic pub --once /rm_driver/get_current_tool_frame_cmd std_msgs/msg/Empty "{}" |
+| Return value | Current tool coordinate system name |
+| Return example | ros2 topic echo /rm_driver/get_current_tool_frame_result |
+
+#### Get_all_tool_coordinate_system_names
+
+| Function description | Get_all_tool_coordinate_system_names |
+| :---: | :---- |
+| Parameter description | ROS msg std_msgs::msg::Empty |
+| Command example | ros2 topic pub /rm_driver/get_all_tool_frame_cmd std_msgs/msg/Empty "{}" |
+| Return value | All names of the current tool coordinate system |
+| Return example | ros2 topic echo /rm_driver/get_all_tool_frame_result |
+
+#### Get_the_current_work_coordinate_system
+
+| Function description | Get_the_current_work_coordinate_system |
+| :---: | :---- |
+| Parameter description | ROS msg std_msgs::msg::Empty |
+| Command example | ros2 topic pub --once /rm_driver/get_curr_workFrame_cmd std_msgs/msg/Empty "{}" |
+| Return value | true-set successfully,false-set failed |
+| Return example | ros2 topic echo /rm_driver/get_curr_workFrame_result |
+
+#### Get_all_work_coordinate_system_names
+
+| Function description | Get_all_work_coordinate_system_names |
+| :---: | :---- |
+| Parameter description | ROS msg std_msgs::msg::Empty |
+| Command example | ros2 topic pub --once /rm_driver/get_all_work_frame_cmd std_msgs/msg/Empty "{}" |
+| Return value | All work coordinate system names |
+| Return example | ros2 topic echo /rm_driver/get_all_work_frame_result |
+
+### Functions_related_to_the_arm_state_query
+
+#### Get_the_current_state_of_the_robot_arm-return_each_joint_angle_and_Euler_angle
+
+| Function description | Retrieve the current state of the robotic arm |
+| :---: | :---- |
+| Parameter description | ROS msg std_msgs::msg::Empty |
+| Command example | ros2 topic pub --once /rm_driver/get_current_arm_state_cmd std_msgs/msg/Empty "{}" |
+| Return value | The current robotic arm joint state (angle) + pose information (Euler angle) + error information |
+| Return example | ros2 topic echo /rm_driver/get_current_arm_original_state_result |
+
+#### Get_the_current_state_of_the_robotic_arm-return_each_joint_radians_and_quaternion
+
+| Function description | Retrieve the current state of the robotic arm |
+| :---: | :---- |
+| Parameter description | ROS msg std_msgs::msg::Empty |
+| Command example | ros2 topic pub --once /rm_driver/get_current_arm_state_cmd std_msgs/msg/Empty "{}" |
+| Return value | The current robotic arm joint state (radians) + pose information (quaternion) + error information |
+| Return example | ros2 topic echo /rm_driver/get_current_arm_state_result |
+
+### Functions_related_to_motion_planning_of_the_robotic_arm
+
+#### Joint_Space_Motion
+
+| Function description | Joint space move MOVEJ |
+| :---: | :---- |
+| Parameter description | Movej.msg
float32[6] joint: joint angle, unit: radians.
uint8 speed: speed percentage ratio coefficient, 0~100.
bool block: whether it is a blocking mode,bool type,true:blocking,false:non-blocking. |
+| Command example | 6-degree of freedom
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-degree of freedom
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 value | Successful return: true; failure returns: false, the driver terminal returns an error code. |
+| Return example | ros2 topic echo /rm_driver/movej_result |
+
+#### Linear_motion_in_Cartesian_space
+
+| Function description | Linear motion in Cartesian space MOVEL |
+| :---: | :---- |
+| Parameter description | Movel.msg
geometry_msgs/Pose pose: robotic arm pose,geometry_msgs/Pose type,x, y, z coordinates (float type, unit: m) + quaternion.
uint8 speed: speed percentage ratio coefficient, 0~100。
bool : whether it is a blocking mode, bool type, true: blocking, false: non-blocking. |
+| Command example | First, use MoveJP
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"
Then use MoveL
ros2 topic pub --once /rm_driver/movel_cmd rm_ros_interfaces/msg/Movel "pose:
position:
x: -0.317239
y: 0.120903
z: 0.295765
orientation:
x: -0.983404
y: -0.178432
z: 0.032271
w: 0.006129
speed: 20
trajectory_connect: 0
block: true" |
+| Return value | Successful return: true; failure returns: false, and the driver terminal returns an error code. |
+| Return example | ros2 topic echo /rm_driver/movel_result |
+
+#### Cartesian_space_linear_offset_motion
+
+| Function description | Cartesian_space_linear_offset_motion |
+| :---: | :---- |
+| Parameter description | Moveloft.msg
geometriy_msgs/Pose pose: Position and attitude offset, position unit: meters, attitude unit: radians
int32 speed: velocity percentage coefficient, 1-100
int32 r: blending radius percentage coefficient, 0-100.
Bool trajectory_connect: Trajectory connection flag, 0 immediately plans and executes the trajectory, without connecting to subsequent trajectories. 1: Plan the current trajectory together with the next trajectory, but do not execute it immediately. In blocking mode, even if the transmission is successful, it will immediately return.
Bool frame_type: reference coordinate system type, 0 working coordinates, 1 tool coordinates
bool block: block setting. In multi-threaded mode, 0 represents non blocking mode, which returns immediately after sending an instruction; 1 represents blocking mode, waiting for the robotic arm to reach the target position or planning failure before returning. In single threaded mode, 0 represents non blocking mode, which returns immediately after sending an instruction; When using other values, block the mode and set a timeout based on the movement time, in seconds. |
+| Command example | First, use MoveJP
ros2 topic pub --once /rm_driver/movej_p_cmd rm_ros_interfaces/msg/Movejp "{pose: {position: {x: -0.317239, y: 0.120903, z: 0.255765}, orientation: {x: -0.983404, y: -0.178432, z: 0.032271, w: 0.006129}},speed: 20, trajectory_connect: 0, block: true}"
Then use Movel_offset
ros2 topic pub --once /rm_driver/movel_offset_cmd rm_ros_interfaces/msg/Moveloffset "{pose: {position: {x: -0.317239, y: 0.120903, z: 0.295765}, orientation: {x: -0.983404, y: -0.178432, z: 0.032271, w: 0.006129}}, speed: 20 ,r: 0 ,trajectory_connect: false, frame_type: false,block: false}" |
+| Return value | Successful return: true; failure returns: false, and the driver terminal returns an error code. |
+| Return example | ros2 topic echo /rm_driver/movel_offset_result |
+
+#### Circular_motion_in_Cartesian_space
+
+| Function description | Circular motion in Cartesian space MOVEC |
+| :---: | :---- |
+| Parameter description | Movec.msg
geometry_msgs/Pose pose_mid: middle pose,geometry_msgs/Pose type,x, y, z coordinates (float type, unit: m) + quaternion.
geometry_msgs/Pose pose_end: end pose,geometry_msgs/Posetype, x, y, z coordinates (float type, unit: m) + quaternion.
uint8 speed: speed percentage ratio coefficient, 0-100.
bool block: whether it is a blocking mode, bool type, true: blocking, false: non-blocking. |
+| Command example | First, use movej_p to reach the specified position
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"
Use movec to reach the specified position
ros2 topic pub --once /rm_driver/movec_cmd rm_ros_interfaces/msg/Movec "pose_mid:
position:
x: 0.324946
y: -0.008786
z: 0.299028
orientation:
x: 0.7071
y: -0.7071
z: 0.0
w: 0.0
pose_end:
position:
x: 0.274946
y: 0.041214
z: 0.299028
orientation:
x: 0.7071
y: -0.7071
z: 0.0
w: 0.0
speed: 20
trajectory_connect: 0
block: false
loop: 0" |
+| Return value | Successful return: true; failure returns: false, and the driver terminal returns an error code. |
+| Return example | ros2 topic echo /rm_driver/movec_result |
+
+#### Joint_angle_CANFD_transmission
+
+| Function description | Joint angle CANFD transmission |
+| :---: | :---- |
+| Parameter description | Jointpos.msg
float32[6] joint: joint angle, unit: radians.
bool follow: follow state, true: high following, false: low following, default high following if not set.
float32 expand: expand joint, unit: radians. |
+| Command example | Transmission needs to send multiple continuous points to achieve, simply by the following command and can not achieve the function, the current moveit2 control using angle transmission control mode.
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 value | Success: no return value; Failure return: the driver terminal returns an error code. |
+
+#### Customize_high_following_mode_joint_angle_CANFD_transmission
+
+| Function description | Customize high following mode joint angle CANFD transmission |
+| :---: | :---- |
+| Parameter description | Jointposcustom.msg
float32[6] joint: joint angle, unit: radians.
bool follow: follow state, true: high following, false: low following, default high following if not set.
float32 expand: expand joint, unit: radians.
uint8 trajectory_mode: When the high following mode is set, multiple modes are supported, including 0- complete transparent transmission mode, 1- curve fitting mode and 2- filtering mode.
uint8 radio: Set the smoothing coefficient in curve fitting mode (range 0-100) or the filter parameter in filtering mode (range 0-1000). The higher the value, the better the smoothing effect.|
+| Command example | Transmission needs to send multiple continuous points to achieve, simply by the following command and can not achieve the function, the current moveit2 control using angle transmission control mode.
ros2 topic pub /rm_driver/movej_canfd_custom_cmd rm_ros_interfaces/msg/Jointposcustom "joint: [0, 0, 0, 0, 0, 0]
follow: false
expand: 0.0
trajectory_mode: 0
radio: 0
dof: 6" |
+| Return value | Success: no return value; Failure return: the driver terminal returns an error code. |
+
+#### Pose_CANFD_transmission
+
+| Function description | Pose CANFD transmission |
+| :---: | :---- |
+| Parameter description | Cartepos.msg
geometry_msgs/Pose pose: transmission pose, geometry_msgs/Pose type, x, y, z coordinates (float type, unit: m) + quaternion.
bool follows: follow state, true: high following, false: low following, default high following if not set. |
+| Command example | It needs to be a large number (10 or more) of continuous position points, simply by the following command and can not achieve the function, with more than a 2ms period continuous release.
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 value | Success: no return value; Failure return: the driver terminal returns an error code. |
+
+#### Customize_high_following_mode_pose_CANFD_transmission
+
+| Function description | Customize high following mode pose CANFD transmission |
+| :---: | :---- |
+| Parameter description | Carteposcustom.msg
geometry_msgs/Pose pose: transmission pose, geometry_msgs/Pose type, x, y, z coordinates (float type, unit: m) + quaternion.
bool follows: follow state, true: high following, false: low following, default high following if not set.
uint8 trajectory_mode: When the high following mode is set, multiple modes are supported, including 0- complete transparent transmission mode, 1- curve fitting mode and 2- filtering mode.
uint8 radio: Set the smoothing coefficient in curve fitting mode (range 0-100) or the filter parameter in filtering mode (range 0-1000). The higher the value, the better the smoothing effect.|
+| Command example | It needs to be a large number (10 or more) of continuous position points, simply by the following command and can not achieve the function, with more than a 2ms period continuous release.
ros2 topic pub /rm_driver/movep_canfd_custom_cmd rm_ros_interfaces/msg/Carteposcustom "pose:
position:
x: 0.0
y: 0.0
z: 0.0
orientation:
x: 0.0
y: 0.0
z: 0.0
w: 1.0
follow: false
trajectory_mode: 0
radio: 0" |
+| Return value | Success: no return value; Failure return: the driver terminal returns an error code. |
+
+#### Joint_space_planning_to_target_pose
+
+| Function description | Joint space planning to target pose MOVEJP |
+| :---: | :---- |
+| Parameter description | Movejp.msg
geometry_msgs/Pose target pose, x, y, z coordinates (float type, unit: m) + quaternion.
uint8 speed: speed percentage ratio coefficient, 0-100.
bool block: whether it is a blocking mode, bool type, true: blocking, false: non-blocking. |
+| Command example | 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 value | Successful return: true; failure returns: false, and the driver terminal returns an error code. |
+| Return example | ros2 topic echo /rm_driver/movej_p_result |
+
+#### Trajectory_emergency_stop
+
+| Function description | Motion planning trajectory emergency stop |
+| :---: | :---- |
+| Parameter description | ROS msg std_msgs::msg::Empty |
+| Command example | ros2 topic pub /rm_driver/move_stop_cmd std_msgs/msg/Empty "{}"|
+| Return value | Successful return: true; failure returns: false, and the driver terminal returns an error code. |
+| Return example | ros2 topic echo /rm_driver/move_stop_result |
+
+#### Emergency_stop
+
+| Function description | Emergency_stop |
+| :---: | :---- |
+| Parameter description | rm_ros_interfaces/Stop Emergency stop status, true: E-stopped, false: Resumed |
+| Command example | ros2 topic pub --once /rm_driver/emergency_stop_cmd rm_ros_interfaces/Stop "state: true" |
+| Return value | Successful return: true; failure returns: false, and the driver terminal returns an error code. |
+| Return example | ros2 topic echo /rm_driver/emergency_stop_result |
+
+### Teaching_instructions
+
+#### Joint_teaching
+
+| Function description | Joint teaching |
+| :---: | :---- |
+| Parameter description | Jointteach.msg
uint8 num:Joint num,1~7
uint8 direction:teach direction,0-negative direction,1-positive direction
uint8 speed:speed percentage ratio coefficient, 0-100. |
+| Command example | ros2 topic pub /rm_driver/set_joint_teach_cmd rm_ros_interfaces/msg/Jointteach "num: 1
direction: 0
speed: 10" |
+| Return value | Successful return: true; failure returns: false, and the driver terminal returns an error code. |
+| Return example | ros2 topic echo /rm_driver/set_joint_teach_result |
+
+#### Position_teaching
+
+| Function description | Position teaching |
+| :---: | :---- |
+| Parameter description | Posteach.msg
uint8 type: Teaching demonstration type: input0:X-axis direction、1:Y-axis direction、2:Z-axis direction
uint8 direction:teach direction,0-negative direction,1-positive direction
uint8 speed:speed percentage ratio coefficient, 0-100.|
+| Command example | ros2 topic pub /rm_driver/set_pos_teach_cmd rm_ros_interfaces/msg/Posteach "type: 2
direction: 0
speed: 10" |
+| Return value | Successful return: true; failure returns: false, and the driver terminal returns an error code. |
+| Return example | ros2 topic echo /rm_driver/set_pos_teach_result |
+
+#### Attitude_teaching
+
+| Function description | Attitude teaching |
+| :---: | :---- |
+| Parameter description | Ortteach.msg.msg
uint8 type: Teaching demonstration type: input0:RX-axis direction、1:RY-axis direction、2:RZ-axis direction
uint8 direction:teach direction,0-negative direction,1-positive direction
uint8 speed:speed percentage ratio coefficient, 0-100. |
+| Command example | ros2 topic pub /rm_driver/set_ort_teach_cmd rm_ros_interfaces/msg/Ortteach "type: 2
direction: 0
speed: 10" |
+| Return value | Successful return: true; failure returns: false, and the driver terminal returns an error code. |
+| Return example | ros2 topic echo /rm_driver/set_ort_teach_result |
+
+#### Stop_teaching
+
+| Function description | Stop teaching |
+| :---: | :---- |
+| Parameter description | ROS msg std_msgs::msg::Empty|
+| Command example | ros2 topic pub /rm_driver/set_stop_teach_cmd std_msgs/msg/Empty "{}" |
+| Return value | Successful return: true; failure returns: false, and the driver terminal returns an error code. |
+| Return example | ros2 topic echo /rm_driver/set_stop_teach_result |
+
+### Trajectory_File
+
+#### Query_Trajectory_List
+
+| Function description | Query_Trajectory_List |
+| :---: | :---- |
+| Parameter description | GettraInjectorylist.msg
int32 page_num: Page number.
Int32 page_size: The size of each page.
String vague_search: Fuzzy search.|
+| Command example | ros2 topic pub --once /rm_driver/get_trajectory_file_list_cmd rm_ros_interfaces/msg/Gettrajectorylist "{page_num: 1,page_size: 10,vague_search: 's'}" |
+| Return value | Trajectorylist.msg
int32 page_num # Page number
int32 page_size # Size per page
int32 total_size # Length of the list
+string vague_search # Fuzzy search
Trajectoryinfo[] tra_list # List of trajectories that match the criteria
bool state # Query status - true for success, false for failure|
+| Return example | ros2 topic echo /rm_driver/get_trajectory_file_list_result |
+
+#### Start_Running_Specified_Trajectory
+
+| Function description | Start_Running_Specified_Trajectory |
+| :---: | :---- |
+| Parameter description | ROS msg std_msgs::msg::String |
+| Command example | ros2 topic pub --once /rm_driver/set_run_trajectory_cmd std_msgs/msg/String "data: 'sss'" |
+| Return value | Successfully returned query trajectory information; Failed with no return, the driver terminal returned an error code. |
+| Return example | ros2 topic echo /rm_driver/set_run_trajectory_result |
+
+#### Delete_Specified_Trajectory_File
+
+| Function description | Delete_Specified_Trajectory_File |
+| :---: | :---- |
+| Parameter description | ROS msg std_msgs::msg::String |
+| Command example | ros2 topic pub --once /rm_driver/delete_trajectory_file_cmd std_msgs/msg/String "data: 'sss'" |
+| Return value | Successfully returned query trajectory information; Failed with no return, the driver terminal returned an error code. |
+| Return example | ros2 topic echo /rm_driver/delete_trajectory_file_result |
+
+#### Save_Trajectory_File
+
+| Function description | Save_Trajectory_File |
+| :---: | :---- |
+| Parameter description | ROS msg std_msgs::msg::String |
+| Command example | ros2 topic pub --once /rm_driver/save_trajectory_file_cmd std_msgs/msg/String "data: 'test'" |
+| Return value | Successfully returned query trajectory information; Failed with no return, the driver terminal returned an error code. |
+| Return example | ros2 topic echo /rm_driver/save_trajectory_file_result |
+
+#### Query_Flowchart_Program_Run_State
+
+| Function description | Query_Flowchart_Program_Run_State |
+| :---: | :---- |
+| Parameter description | ROS msg std_msgs::msg::Empty |
+| Command example | ros2 topic pub --once /rm_driver/get_flowchart_program_run_state_cmd std_msgs/msg/Empty "{}" |
+| Return value | Flowchartrunstate.msg
int run_state; #Running Status 0 Not Started 1 Running 2 Paused
int id;#The current enabled file ID.
char name[32];#The name of the currently enabled file.
int plan_speed;#The current enabled file global planning speed ratio is 1-100.
int step_mode;#Single step mode, 0 is empty, 1 is normal, and 2 is single step.
char modal_id[50];#The ID of the flowchart block that has been run. If it has not been run, no return will be sent. |
+| Return example | ros2 topic echo /rm_driver/get_flowchart_program_run_state_result |
+
+### Modbus_Configuration
+
+#### Set_Controller_RS485_Mode
+
+| Function description | Set_Controller_RS485_Mode |
+| :---: | :---- |
+| Parameter description | RS485params.msg
int32 mode: 0-RS485 serial communication, 1-modbus RTU master mode, 2-Modbus RTU slave mode.
Int32 baudrate: Currently supports 9600 19200 38400 57600 115200 230400 460800. |
+| Command example | ros2 topic pub /rm_driver/set_controller_rs485_mode_cmd rm_ros_interfaces/msg/RS485params "{mode: 0, baudrate: 115200}" |
+| Return value | Successful return: true; failure returns: false, and the driver terminal returns an error code. |
+| Return example | ros2 topic echo /rm_driver/set_controller_rs485_mode_result |
+
+#### Get_Controller_RS485_Mode
+
+| Function description | Get_Controller_RS485_Mode |
+| :---: | :---- |
+| Parameter description | ROS msg std_msgs::msg::Empty |
+| Command example | ros2 topic pub /rm_driv/get_controller_rs485_mode_cmd std_msgs/msg/Empty "{}" |
+| Return value | RS485params.msg
int32 mode: 0-RS485 serial communication, 1-modbus RTU master mode, 2-Modbus RTU slave mode.
Int32 baudrate: Currently supports 9600 19200 38400 57600 115200 230400 460800. |
+| Return example | ros2 topic echo /rm_driver/get_controller_rs485_mode_result |
+
+#### Set_Tool_End_RS485_Mode
+
+| Function description | Set_Tool_End_RS485_Mode |
+| :---: | :---- |
+| Parameter description | RS485params.msg
int32 mode: 0- Set the RS485 port of the tool end to RTU master station, 1- Smart hand mode, 2- Claw mode.
Int32 baudrate: Currently supports 9600 115200 460800. |
+| Command example | ros2 topic pub --once /rm_driver/set_tool_rs485_mode_cmd rm_ros_interfaces/msg/RS485params "{mode: 0, baudrate: 115200}" |
+| Return value | Successful return: true; failure returns: false, and the driver terminal returns an error code. |
+| Return example | ros2 topic echo /rm_driver/set_tool_rs485_mode_result |
+
+#### Get_Tool_End_RS485_Mode
+
+| Function description | Get_Tool_End_RS485_Mode |
+| :---: | :---- |
+| Parameter description | ROS msg std_msgs::msg::Empty |
+| Command example | ros2 topic pub /rm_driver/get_tool_rs485_mode_cmd std_msgs/msg/Empty "{}" |
+| Return value | RS485params.msg
int32 mode: 0- Set the RS485 port of the tool end to RTU master station, 1- Smart hand mode, 2- Claw mode.
Int32 baudrate: Currently supports 9600 115200 460800. |
+| Return example | ros2 topic echo /rm_driver/get_tool_rs485_mode_result |
+
+### ModbusTCP_Master
+
+#### Add_Modbus_TCP_Master
+
+| Function description | Add_Modbus_TCP_Master |
+| :---: | :---- |
+| Parameter description | Modbustcpmasterinfo.msg
string master_name: Modbus master station name.
String ip: TCP master IP address.
Int32 port: TCP primary port number. |
+| Command example | ros2 topic pub /rm_driver/add_modbus_tcp_master_cmd rm_ros_interfaces/msg/Modbustcpmasterinfo "{master_name: '1',ip: '127.0.0.1',port: 502}" |
+| Return value | Successful return: true; failure returns: false, and the driver terminal returns an error code. |
+| Return example | ros2 topic echo /rm_driver/add_modbus_tcp_master_result |
+
+#### Update_Modbus_TCP_Master
+
+| Function description | Update_Modbus_TCP_Master |
+| :---: | :---- |
+| Parameter description | Modbustcpmasterinfo.msg
string master_name: Modbus old master station name.
string new_master_name: Modbus new master station name.
String ip: TCP master IP address.
Int32 port: TCP primary port number. |
+| Command example | ros2 topic pub /rm_driver/update_modbus_tcp_master_cmd rm_ros_interfaces/msg/Modbustcpmasterupdata "{"master_name: '1',new_master_name: '125',ip: '127.0.0.1',port: 502"}" |
+| Return value | Successful return: true; failure returns: false, and the driver terminal returns an error code. |
+| Return example | ros2 topic echo /rm_driver/update_modbus_tcp_master_result |
+
+#### Delete_Modbus_TCP_Master
+
+| Function description | Delete_Modbus_TCP_Master |
+| :---: | :---- |
+| Parameter description | Mastername.msg
string master_name: Modbus master station name. |
+| Command example | ros2 topic pub /rm_driver/delete_modbus_tcp_master_cmd rm_ros_interfaces/msg/Mastername "master_name: '321'" |
+| Return value | Successful return: true; failure returns: false, and the driver terminal returns an error code. |
+| Return example | ros2 topic echo /rm_driver/delete_modbus_tcp_master_result |
+
+#### Get_Specified_Modbus_TCP_Master
+
+| Function description | Get_Specified_Modbus_TCP_Master |
+| :---: | :---- |
+| Parameter description | Mastername.msg
string master_name: Modbus master station name. |
+| Command example | ros2 topic pub /rm_driver/get_modbus_tcp_master_cmd rm_ros_interfaces/msg/Mastername "master_name: '321'" |
+| Return value | Modbustcpmasterinfo.msg
string master_name # Name of the Modbus master station, with a maximum length of 15 characters, not exceeding 15 characters
string ip # IP address of the TCP master station
int32 port # Port number of the TCP master station
bool state # Query status information, false for failure, true for success
On failure, the driver terminal returns an error code. |
+| Return example | ros2 topic echo /rm_driver/get_modbus_tcp_master_result |
+
+#### Get_Modbus_TCP_Master_List
+
+| Function description | Get_Modbus_TCP_Master_List |
+| :---: | :---- |
+| Parameter description | Getmodbustcpmasterlist.msg
int32 page_num: Page number.
Int32 page_size: The size of each page.
String vague_search: Fuzzy search, returns a list of all main sites if the input is empty. |
+| Command example | ros2 topic pub /rm_driver/get_modbus_tcp_master_list_cmd rm_ros_interfaces/msg/Getmodbustcpmasterlist "{page_num: 1,page_size: 10,vague_search: '1'}" |
+| Return value | Modbustcpmasterlist.msg
uint8 page_num # Page number
uint8 page_size # Size per page
uint8 total_size # Length of the list
string vague_search # Fuzzy search
Modbustcpmasterinfo[] master_list # List of TCP master stations that match the criteria
bool state # Query status - true for success, false for failure
On failure, the driver terminal returns an error code |
+| Return example | ros2 topic echo /rm_driver/get_modbus_tcp_master_list_result |
+
+### Tool_end_controller_end_RTU_Modbus_protocol_reads_and_writes_data
+
+#### Modbus_RTU_Protocol_Read_Coils
+
+| Function description | Modbus_RTU_Protocol_Read_Coils |
+| :---: | :---- |
+| Parameter description | Modbusrtureadparams.msg
int32 address: data starting address.
Int32 device: Peripheral device address.
int32 type: 0-Controller end Modbus host; 1. Tool end Modbus host.
Int32 num: The number of data to be read, with a length not exceeding 100. |
+| Command example | ros2 topic pub /rm_driver/read_modbus_rtu_coils_cmd rm_ros_interfaces/msg/Modbusrtureadparams "{address: 0, device: 0, type: 0, num: 1}" |
+| Return value | Modbusreaddata.msg
int32[] read_data # Data read from Modbus
bool state # Feedback query status information, false for failure, true for success
On failure, the driver terminal returns an error code.|
+| Return example | ros2 topic echo /rm_driver/read_modbus_rtu_coils_result |
+
+#### Modbus_RTU_Protocol_Write_Coils
+
+| Function description | Modbus_RTU_Protocol_Write_Coils |
+| :---: | :---- |
+| Parameter description | Modbusrtuwriteparams.msg
int32 address: data starting address.
Int32 device: Address of peripheral device.
Int32 type: 0-Controller side Modbus host; 1. Tool side Modbus host.
Int32 num: The maximum number of data to be written is 100.
Int32 [] data: The data to be written, with a length corresponding to num. |
+| Command example | ros2 topic pub /rm_driver/write_modbus_rtu_coils_cmd rm_ros_interfaces/msg/Modbusrtuwriteparams "{address: 0, device: 0, type: 0, num: 2, data: [1,1]}" |
+| Return value | Successful return: true; failure returns: false, the driver terminal returns an error code. |
+| Return example | ros2 topic echo /rm_driver/write_modbus_rtu_coils_result |
+
+#### Modbus_RTU_Protocol_Read_Discrete_Inputs
+
+| Function description | Modbus_RTU_Protocol_Read_Discrete_Inputs |
+| :---: | :---- |
+| Parameter description | Modbusrtureadparams.msg
int32 address: data starting address.
Int32 device: Peripheral device address.
int32 type: 0-Controller side Modbus host; 1. Tool side Modbus host.
Int32 num: The number of data to be read, with a data length not exceeding 100. |
+| Command example | ros2 topic pub /rm_driver/read_modbus_rtu_input_status_cmd rm_ros_interfaces/msg/Modbusrtureadparams "{address: 0, device: 0, type: 0, num: 1}" |
+| Return value | Modbusreaddata.msg
int32[] read_data # Data read from Modbus
bool state # Feedback query status information, false for failure, true for success
On failure, the driver terminal returns an error code. |
+| Return example | ros2 topic echo /rm_driver/read_modbus_rtu_input_status_result |
+
+#### Modbus_RTU_Protocol_Read_Holding_Registers
+
+| Function description | Modbus_RTU_Protocol_Read_Discrete_Inputs |
+| :---: | :---- |
+| Parameter description | Modbusrtureadparams.msg
int32 address: data starting address.
Int32 device: Peripheral device address.
int32 type: 0-Controller end Modbus host; 1. Tool end Modbus host.
Int32 num: The number of data to be read, with a data length not exceeding 100. |
+| Command example | ros2 topic pub /rm_driver/read_modbus_rtu_holding_registers_cmd rm_ros_interfaces/msg/Modbusrtureadparams "{address: 0, device: 0, type: 0, num: 1}" |
+| Return value | Modbusreaddata.msg
int32[] read_data # The data read from Modbus
bool state # Feedback query status information, false for failure, true for success
On failure, the driver terminal returns an error code. |
+| Return example | ros2 topic echo /rm_driver/read_modbus_rtu_holding_registers_result |
+
+#### Modbus_RTU_Protocol_Write_Holding_Registers
+
+| Function description | Modbus_RTU_Protocol_Write_Holding_Registers |
+| :---: | :---- |
+| Parameter description | Modbusrtuwritableparams.msg
int32 address: data starting address
int32 device: peripheral device address
int32 type: 0-controller end Modbus host; 1. Tool end Modbus host.
Int32 num: The maximum amount of data to be written, not exceeding 100
int32 [] data: The data to be written, with a length corresponding to num. |
+| Command example | ros2 topic pub /rm_driver/write_modbus_rtu_registers_cmd rm_ros_interfaces/msg/Modbusrtuwriteparams "{address: 0, device: 0, type: 0, num: 2, data: [1,1]}" |
+| Return value | Successful return: true; failure returns: false, the driver terminal returns an error code. |
+| Return example | ros2 topic echo /rm_driver/write_modbus_rtu_registers_result |
+
+#### Modbus_RTU_Protocol_Read_Input_Registers
+
+| Function description | Modbus_RTU_Protocol_Read_Input_Registers |
+| :---: | :---- |
+| Parameter description | Modbusrtureadparams.msg
int32 address: data starting address.
Int32 device: Peripheral device address.
int32 type: 0-Controller side Modbus host; 1. Tool side Modbus host..
Int32 num: The number of data to be read, with a data length not exceeding 100. |
+| Command example | ros2 topic pub /rm_driver/read_modbus_rtu_input_registers_cmd rm_ros_interfaces/msg/Modbusrtureadparams "{address: 0, device: 0, type: 0, num: 1}" |
+| Return value | Modbusreaddata.msg
int32[] read_data # Data read from Modbus
bool state # Feedback query status information, false for failure, true for success
On failure, the driver terminal returns an error code. |
+| Return example | ros2 topic echo /rm_driver/read_modbus_rtu_input_registers_result |
+
+### Controller_Modbus_TCP_protocol_reads_and_writes_data
+
+#### Modbus_TCP_Protocol_Read_Coils
+
+| Function description | Modbus_TCP_Protocol_Read_Coils |
+| :---: | :---- |
+| Parameter description | Modbustcpreadparams.msg
int32 address: data starting address.
String master_name: Modbus master name, maximum length of 15 characters.
String ip: The IP address of the host connection.
Int32 port: The port number of the host connection.
Int32 num: Read data quantity, maximum not exceeding 100. |
+| Command example | ros2 topic pub /rm_driver/read_modbus_tcp_coils_cmd rm_ros_interfaces/msg/Modbustcpreadparams "{address: 0,master_name: '3',ip: '127.0.0.6',port: 502,num: 1}" |
+| Return value | Modbusreaddata.msg
int32[] read_data # Data read from Modbus
bool state # Feedback query status information, false for failure, true for success
On failure, the driver terminal returns an error code. |
+| Return example | ros2 topic echo /rm_driver/read_modbus_tcp_coils_result |
+
+#### Modbus_TCP_Protocol_Write_Coils
+
+| Function description | Modbus_TCP_Protocol_Write_Coils |
+| :---: | :---- |
+| Parameter description | Modbustcpwriteparames.msg
int32 address: data starting address.
String master_name: Modbus master name, maximum length of 15 characters.
String ip: The IP address of the host connection.
Int32 port: The port number of the host connection.
Int32 num: Write data quantity, maximum not exceeding 100.
Int32 [] data: The written data has a length corresponding to num. |
+| Command example | ros2 topic pub /rm_driver/write_modbus_tcp_coils_cmd rm_ros_interfaces/msg/Modbustcpwriteparams "{address: 0,master_name: '3',ip: '127.0.0.6',port: 502, num: 2, data: [1,1]}" |
+| Return value | Successful return: true; failure returns: false, the driver terminal returns an error code. |
+| Return example | ros2 topic echo /rm_driver/write_modbus_tcp_coils_result |
+
+#### Modbus_TCP_Protocol_Read_Discrete_Inputs
+
+| Function description | Modbus_TCP_Protocol_Read_Discrete_Inputs |
+| :---: | :---- |
+| Parameter description | Modbustcpreadparams.msg
int32 address: data starting address.
String master_name: Modbus master name, maximum length of 15 characters.
String ip: The IP address of the host connection.
Int32 port: The port number of the host connection.
Int32 num: Read data quantity, maximum not exceeding 100. |
+| Command example | ros2 topic pub /rm_driver/read_modbus_tcp_input_status_cmd rm_ros_interfaces/msg/Modbustcpreadparams "{address: 0,master_name: '3',ip: '127.0.0.6',port: 502,num: 1}" |
+| Return value | Modbusreaddata.msg
int32[] read_data # Data read from Modbus
bool state # Feedback query status information, false for failure, true for success
On failure, the driver terminal returns an error code. |
+| Return example | ros2 topic echo /rm_driver/read_modbus_tcp_input_status_result |
+
+#### Modbus_TCP_Protocol_Read_Holding_Registers
+
+| Function description | Modbus_TCP_Protocol_Read_Holding_Registers |
+| :---: | :---- |
+| Parameter description | Modbustcpreadparams.msg
int32 address: data starting address.
String master_name: Modbus master name, maximum length of 15 characters.
String ip: The IP address of the host connection.
Int32 port: The port number of the host connection.
Int32 num: Read data quantity, maximum not exceeding 100. |
+| Command example | ros2 topic pub /rm_driver/read_modbus_tcp_holding_registers_cmd rm_ros_interfaces/msg/Modbustcpreadparams "{address: 0,master_name: '3',ip: '127.0.0.6',port: 502,num: 1}" |
+| Return value | Modbusreaddata.msg
int32[] read_data # Data read from Modbus
bool state # Feedback query status information, false for failure, true for success
On failure, the driver terminal returns an error code. |
+| Return example | ros2 topic echo /rm_driver/read_modbus_tcp_holding_registers_result |
+
+#### Modbus_TCP_Protocol_Write_Holding_Registers
+
+| Function description | Modbus_TCP_Protocol_Write_Holding_Registers |
+| :---: | :---- |
+| Parameter description | Modbustcpwriteparames.msg
int32 address: data starting address.
String master_name: Modbus master name, maximum length of 15 characters.
String ip: The IP address of the host connection.
Int32 port: The port number of the host connection.
Int32 num: Write data quantity, maximum not exceeding 100.
Int32 [] data: The written data has a length corresponding to num. |
+| Command example | ros2 topic pub /rm_driver/write_modbus_tcp_registers_cmd rm_ros_interfaces/msg/Modbustcpwriteparams "{address: 0,master_name: '3',ip: '127.0.0.6',port: 502, num: 2, data: [1,1]}" |
+| Return value | Successful return: true; failure returns: false, the driver terminal returns an error code. |
+| Return example | ros2 topic echo /rm_driver/write_modbus_tcp_registers_result |
+
+#### Modbus_TCP_Protocol_Read_Input_Registers
+
+| Function description | Modbus_TCP_Protocol_Read_Input_Registers |
+| :---: | :---- |
+| Parameter description | Modbustcpreadparams.msg
int32 address: data starting address.
String master_name: Modbus master name, maximum length of 15 characters.
String ip: The IP address of the host connection.
Int32 port: The port number of the host connection.
Int32 num: Read data quantity, maximum not exceeding 100. |
+| Command example | ros2 topic pub /rm_driver/read_modbus_tcp_input_registers_cmd rm_ros_interfaces/msg/Modbustcpreadparams "{address: 0,master_name: '3',ip: '127.0.0.6',port: 502,num: 1}" |
+| Return value | Modbusreaddata.msg
int32[] read_data # Data read from Modbus
bool state # Feedback query status information, false for failure, true for success
On failure, the driver terminal returns an error code. |
+| Return example | ros2 topic echo /rm_driver/read_modbus_tcp_input_registers_result |
+
+### Functions_related_to_the_IO_configuration_of_the_end_tool
+
+#### Setting_the_tool_voltage_output
+
+| Function description | Setting the tool voltage output |
+| :---: | :---- |
+| Parameter description | ROS msg: std_msgs::msg::UInt16
uint16 data: power output type, range:0~3 0-0V,1-5V,2-12V,3-24V |
+| Command example | ros2 topic pub --once /rm_driver/set_tool_voltage_cmd std_msgs/msg/UInt16 "data: 0" |
+| Return value | Successful return: true; failure returns: false, the driver terminal returns an error code. |
+| Return example | ros2 topic echo /rm_driver/set_tool_voltage_result |
+
+### Functions_related_to_the_control_of_the_end_gripper
+
+The RealMan robotic arm is equipped with an Inspire Robots EG2-4C2 gripper. The robotic arm controller has made the gripper's ROS control mode available to the user to facilitate user operation.
+
+#### Setting_the_Gripper_Pick
+
+| Function description | Setting the gripper pick |
+| :---: | :---- |
+| Parameter description | Gripperpick.msg
uint16 speed: 1~1000,representing the opening and closing speed of the gripper, dimensionless.
uint16 force:representing the gripping force of the gripper, maximum 1.5 kg.
bool block: whether it is a blocking mode, bool type, true: blocking, false: non-blocking. |
+| Command example | ros2 topic pub --once /rm_driver/set_gripper_pick_cmd rm_ros_interfaces/msg/Gripperpick "speed: 200
force: 200
block: true
timeout: 1000" |
+| Return value | Successful return: true; failure returns: false, the driver terminal returns an error code. |
+| Return example | ros2 topic echo /rm_driver/set_gripper_pick_result |
+
+#### Setting_the_gripper_pick-on
+
+| Function description | Setting the gripper pick-on |
+| :---: | :---- |
+| Parameter description | Gripperpick.msg
uint16 speed: 1~1000, representing the opening and closing speed of the gripper, dimensionless.
uint16 force: 1~1000,representing the gripping force of the gripper, maximum 1.5 kg.
bool block: whether it is a blocking mode, bool type, true: blocking, false: non-blocking. |
+| Command example | ros2 topic pub --once /rm_driver/set_gripper_pick_on_cmd rm_ros_interfaces/msg/Gripperpick "speed: 200
force: 200
block: true
timeout: 1000" |
+| Return value | Successful return: true; failure returns: false, the driver terminal returns an error code. |
+| Return example | ros2 topic echo /rm_driver/set_gripper_pick_on_result |
+
+#### Setting_the_gripper_to_the_given_position
+
+| Function description | Setting the gripper to the given position |
+| :---: | :---- |
+| Parameter description | Gripperset.msg
uint16 position: target position of the gripper, range: 1-1000, representing the opening degree of the gripper: 0-70 mm.
bool block: whether it is a blocking mode, bool type, true: blocking, false: non-blocking. |
+| Command example | ros2 topic pub --once /rm_driver/set_gripper_position_cmd rm_ros_interfaces/msg/Gripperset "position: 500
block: true
timeout: 1000" |
+| Return value | Successful return: true; failure returns: false, the driver terminal returns an error code. |
+| Return example | ros2 topic echo /rm_driver/set_gripper_position_result |
+
+### Functions_related_to_the_drag_teach_and_trajectory_reproduction
+
+#### Set_the_force-position_mixing_control
+
+| Function description | Set the force-position mixing control |
+| :---: | :---- |
+| Parameter description | Setforceposition.msg
uint8 sensor: 0 - One-axis force; 1 - Six-axis force
uint8 mode: 0 - Base coordinate system force control; 1 - Tool coordinate system force control
uint8 direction:Force control direction; 0 - Along the X-axis; 1 - Along the Y-axis; 2 - Along the Z-axis; 3 - Along the RX posture direction; 4 - Along the RY posture direction; 5 - Along the RZ posture direction
int16 n: The value of force, unit: N, accuracy: 0.1N |
+| Command example | ros2 topic pub --once /rm_driver/set_force_postion_cmd rm_ros_interfaces/msg/Setforceposition "sensor: 1
mode: 0
direction: 2
n: 3" |
+| Return value | Successful return: true; failure returns: false, the driver terminal returns an error code. |
+| Return example | ros2 topic echo /rm_driver/set_force_postion_result |
+
+#### Stop_the_force-position_mixing_control
+
+| Function description | Stop the force-position mixing control |
+| :---: | :---- |
+| Parameter description | std_msgs::msg::Empty |
+| Command example | ros2 topic pub /rm_driver/stop_force_postion_cmd std_msgs/msg/Empty "{}" |
+| Return value | Successful return: true; failure returns: false, the driver terminal returns an error code. |
+| Return example | ros2 topic echo /rm_driver/clear_force_data_result |
+
+### Functions_related_to_the_use_of_six-axis_force_sensors_at_the_end
+
+The RealMan RM-65F robotic arm has an integrated six-axis force sensor at the end without external wiring. Users can operate the six-axis force through ROS topics.
+
+#### Query_the_six-axis_force_data
+
+| Function description | Query the six-axis force data|
+| :---: | :---- |
+| Parameter description | std_msgs::msg::Empty |
+| Command example | ros2 topic pub rm_driver/get_force_data_cmd std_msgs/msg/Empty "{}" |
+| Return value | Successfully returned six-axis force data in the corresponding coordinate system. |
+| Return example | ros2 topic echo /rm_driver/get_force_data_result displays the raw force data.
ros2 topic echo /rm_driver/get_zero_force_data_result displays the system force data.
ros2 topic echo /rm_driver/get_work_force_data_result displays the force data in the work coordinate system.
ros2 topic echo /rm_driver/get_tool_force_data_result displays the force data in the tool coordinate system. |
+
+#### Clearing_the_six-axis_force_Data
+
+| Function description | Clearing the six-axis force data |
+| :---: | :---- |
+| Parameter description | std_msgs::msg::Empty|
+| Command example | ros2 topic pub /rm_driver/clear_force_data_cmd std_msgs/msg/Empty "{}" |
+| Return value | Successful return: true; failure returns: false, the driver terminal returns an error code. |
+| Return example | ros2 topic echo /rm_driver/clear_force_data_result |
+
+### Functions_related_to_the_control_of_the_five-finger_dexterous_hand
+
+The RealMan RM-65 robotic arm has been equipped with a five-finger dexterous hand at the end. Users can set the hand through the ROS.
+
+#### Setting_the_serial_number_of_the_dexterous_hand_posture
+
+| Function description | Setting the serial number of the dexterous hand posture |
+| :---: | :---- |
+| Parameter description | Handposture.msg
uint16 posture_num: the serial number of the posture pre-saved in the dexterous hand, ranging from 1 to 40.
bool data: whether it is a blocking mode, bool type, true: blocking, false: non-blocking.
uint16 timeout: The timeout setting for blocking mode, unit: seconds. |
+| Command example | ros2 topic pub --once /rm_driver/set_hand_posture_cmd rm_ros_interfaces/msg/Handposture "posture_num: 1
block: true
timeout: 1000" |
+| Return value | Successful return: true; failure returns: false, the driver terminal returns an error code. |
+| Return example | ros2 topic echo /rm_driver/set_hand_posture_result |
+
+#### Set_the_dexterous_hand_action_sequence_number
+
+| Function description | Set the dexterous hand action sequence number |
+| :---: | :---- |
+| Parameter description | Handseq.msg
uint16 seq_num: the serial number of the action sequence pre-saved in the dexterous hand, ranging from 1 to 40.
bool data: whether it is a blocking mode, bool type, true: blocking, false: non-blocking.
uint16 timeout: The timeout setting for blocking mode, unit: seconds. |
+| Command example | ros2 topic pub --once /rm_driver/set_hand_seq_cmd rm_ros_interfaces/msg/Handseq "seq_num: 1
block: true
timeout:1000" |
+| Return value | Successful return: true; failure returns: false, the driver terminal returns an error code. |
+| Return example | ros2 topic echo /rm_driver/set_hand_seq_result |
+
+#### Setting_the_angles_of_various_degrees_of_freedom_for_the_dexterous_hand
+
+| Function description | Setting the angles of various degrees of freedom for the dexterous hand |
+| :---: | :---- |
+| Parameter description | Handangle.msg
int16[6] hand_angle: hand angle array, the range is 0 to 1000, and -1 represents that no operation is performed on this degree of freedom and the current state remains.
bool data: whether it is a blocking mode, bool type, true: blocking, false: non-blocking. |
+| Command example | 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 value | Successful return: true; failure returns: false, the driver terminal returns an error code. |
+| Return example | ros2 topic echo /rm_driver/set_hand_angle_result |
+
+#### Setting_the_dexterous_hand_speed
+
+| Function description | Setting the dexterous hand speed |
+| :---: | :---- |
+| Parameter description | Handspeed.msg
uint16 hand_speed: hand speed, range: 1-1000. |
+| Command example | ros2 topic pub --once /rm_driver/set_hand_speed_cmd rm_ros_interfaces/msg/Handspeed "hand_speed: 200" |
+| Return value | Successful return: true; failure returns: false, the driver terminal returns an error code. |
+| Return example | ros2 topic echo /rm_driver/set_hand_speed_result |
+
+#### Setting_the_force_threshold_of_the_dexterous_hand
+
+| Function description | Setting the force threshold of the dexterous hand |
+| :---: | :---- |
+| Parameter description | Handforce.msg
uint16 hand_force: hand force, range: 1-1000. |
+| Command example | ros2 topic pub --once /rm_driver/set_hand_force_cmd rm_ros_interfaces/msg/Handforce "hand_force: 200" |
+| Return value | Successful return: true; failure returns: false, the driver terminal returns an error code. |
+| Return example | ros2 topic echo /rm_driver/set_hand_force_result |
+
+#### Setting_the_angle_following_of_the_dexterous_hand
+
+| Function description | Setting the angle following of the dexterous hand |
+| :---: | :---- |
+| Parameter description | Handangle.msg
int16[6] hand_angle: hand angle array, the range is 0 to 2000, and -1 represents that no operation is performed on this degree of freedom and the current state remains.
bool data: whether it is a blocking mode, bool type, true: blocking, false: non-blocking. |
+| Command example | ros2 topic pub --once /rm_driver/set_hand_follow_angle_cmd rm_ros_interfaces/msg/Handangle "hand_angle:
- 0
- 0
- 0
- 0
- 0
- 0
block: true" |
+| Return value | Successful return: true; failure returns: false, the driver terminal returns an error code. |
+| Return example | ros2 topic echo /rm_driver/set_hand_follow_angle_result |
+
+#### Setting_the_posture_following_of_the_dexterous_hand
+
+| Function description | Setting the posture following of the dexterous hand |
+| :---: | :---- |
+| Parameter description | Handangle.msg
int16[6] hand_angle: hand posture array, the range is 0 to 1000, and -1 represents that no operation is performed on this degree of freedom and the current state remains.
bool data: whether it is a blocking mode, bool type, true: blocking, false: non-blocking. |
+| Command example | ros2 topic pub --once /rm_driver/set_hand_follow_pos_cmd rm_ros_interfaces/msg/Handangle "hand_angle:
- 0
- 0
- 0
- 0
- 0
- 0
block: true" |
+| Return value | Successful return: true; failure returns: false, the driver terminal returns an error code. |
+| Return example | ros2 topic echo /rm_driver/set_hand_follow_pos_result |
+
+### Lifting_mechanism
+
+The RealMan robotic arm can be integrated with the self-developed lifting mechanism.
+
+#### Speed_open-loop_control_of_the_lifting_mechanism
+
+| Function description | Speed open-loop control of the lifting mechanism |
+| :---: | :---- |
+| Parameter description | Liftspeed.msg
int16 speed: speed percentage, -100-100, Speed < 0: the lifting mechanism moves downward, Speed > 0: the lifting mechanism moves upward, Speed = 0: the lifting mechanism stops.
bool data: whether it is a blocking mode, bool type, true: blocking, false: non-blocking. |
+| Command example | ros2 topic pub /rm_driver/set_lift_speed_cmd rm_ros_interfaces/msg/Liftspeed "speed: 100" |
+| Return value | Successful return: true; failure returns: false, the driver terminal returns an error code. |
+| Return example | ros2 topic echo /rm_driver/set_lift_speed_result |
+
+#### Position_closed-loop_control_of_the_lifting_mechanism
+
+| Function description | Position closed-loop control of the lifting mechanism |
+| :---: | :---- |
+| Parameter description | Liftheight.msg
uint16 height: target height, unit: mm, range: 0-2600.
uint16 speed: speed percentage, 1-100.
bool data: whether it is a blocking mode, bool type, true: blocking, false: non-blocking. |
+| Command example | ros2 topic pub --once /rm_driver/set_lift_height_cmd rm_ros_interfaces/msg/Liftheight "height: 0
speed: 10
block: true" |
+| Return value | Successful return: true; failure returns: false, the driver terminal returns an error code. |
+| Return example | ros2 topic echo /rm_driver/set_lift_height_result |
+
+#### Get_the_lifting_mechanism_state
+
+| Function description | Get the lifting mechanism state |
+| :---: | :---- |
+| Parameter description | Liftstate.msg
int16 height: current height.
int16 current: current current.
uint16 err_flag: drive error code. |
+| Command example | ros2 topic pub /rm_driver/get_lift_state_cmd std_msgs/msg/Empty "{}" |
+| Return value | Successful return: current state of the lifting mechanism; Failure return: the driver terminal returns an error code. |
+| Return example | ros2 topic echo /rm_driver/get_lift_state_result |
+
+### End_Effector_Ecosystem_Command_Set
+
+Reading of basic and real-time information of end-effector devices supported by the end-effector ecosystem protocol.
+
+#### Setting_End_Effector_Ecosystem_Protocol_Mode
+
+| Function description | Set End-Effector Ecosystem Protocol Mode |
+| :---: | :---- |
+| Parameter description | std_msgs::msg::Int32
0 - Disable protocol;
9600 - Enable protocol (baud rate 9600);
115200 - Enable protocol (baud rate 115200);
256000 - Enable protocol (baud rate 256000);
460800 - Enable protocol (baud rate 460800). |
+| Command example | ros2 topic pub /rm_driver/set_rm_plus_mode_cmd std_msgs/msg/Int32 "data: 0" |
+| Return value | Successful return: true; failure returns: false, the driver terminal returns an error code. |
+| Return example | ros2 topic echo /rm_driver/set_rm_plus_mode_result |
+
+#### Querying_End_Effector_Ecosystem_Protocol_Mode
+
+| Function description | Querying End-Effector Ecosystem Protocol Mode |
+| :---: | :---- |
+| Parameter description | std_msgs::msg::Empty |
+| Command example | ros2 topic pub /rm_driver/get_rm_plus_mode_cmd std_msgs/msg/Empty "{}" |
+| Return value | 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). |
+| Return example | ros2 topic echo /rm_driver/get_rm_plus_mode_result |
+
+#### Setting Tactile Sensor Mode
+
+| Function description | Setting Tactile Sensor Mode |
+| :---: | :---- |
+| Parameter description | std_msgs::msg::Int32
0 - Disable tactile sensor;
1 - Enable tactile sensor (returns processed data);
2 - Enable tactile sensor (returns raw data). |
+| Command example | ros2 topic pub /rm_driver/set_rm_plus_touch_cmd std_msgs::msg::Int32 "data: 0" |
+| Return value | Successful return: true; failure returns: false, the driver terminal returns an error code. |
+| Return example | ros2 topic echo /rm_driver/set_rm_plus_touch_result |
+
+#### Querying_Tactile_Sensor_Mode
+
+| Function description | Querying_Tactile_Sensor_Mode |
+| :---: | :---- |
+| Parameter description | std_msgs::msg::Empty |
+| Command example | ros2 topic pub /rm_driver/get_rm_plus_mode_cmd std_msgs/msg/Empty "{}" |
+| Return value | std_msgs::msg::Int32
0 - Disable protocol;
9600 - Enable protocol (baud rate 9600);
115200 - Enable protocol (baud rate 115200);
256000 - Enable protocol (baud rate 256000);
460800 - Enable protocol (baud rate 460800). |
+| Return example | ros2 topic echo /rm_driver/get_rm_plus_mode_result |
+
+### Functions_related_to_the_transmissive_force-position_compensation_Mode
+
+For the RealMan robotic arm with one-axis force and six-axis force versions, the user can not only directly use the teaching device to call the underlying force-position mixing control module but also combine the custom trajectory with the underlying force-position mixing control algorithm in the form of periodic transmission to compensate.
+If force data calibration has not been completed before the force operations, the zero position can be calibrated using the one-axis force and six-axis force data clear interfaces.
+
+#### Starting_the_transmissive_force-position_mixing_control_compensation_mode
+
+| Function description | starting the transmissive force-position mixing control compensation mode |
+| :---: | :---- |
+| Parameter description | std_msgs::msg::Empty |
+| Command example | ros2 topic pub /rm_driver/start_force_position_move_cmd std_msgs/msg/Empty "{}" |
+| Return value | Successful return: true; failure returns: false, the driver terminal returns an error code. |
+| Return example | ros2 topic echo /rm_driver/start_force_position_move_result |
+
+#### Stopping_the_transmissive_force-position_mixing_control_compensation_mode
+
+| Function description | Stopping the transmissive force-position mixing control compensation mode |
+| :---: | :---- |
+| Parameter description | std_msgs::msg::Empty |
+| Command example | ros2 topic pub /rm_driver/stop_force_position_move_cmd std_msgs/msg/Empty "{}" |
+| Return value | Successful return: true; failure returns: false, the driver terminal returns an error code. |
+| Return example | ros2 topic echo /rm_driver/stop_force_position_move_result |
+
+#### Transmissive_force-position_mixing_control_compensation-joint
+
+| Function description | Transmissive force-position mixing control compensation (joint) |
+| :---: | :---- |
+| Parameter description | Forcepositionmovejoint.msg
float32[6] joint: target joint radian
uint8 sensor: type of sensor used, 0 - one-axis force, 1 - six-axis force
uint8 mode, 0 - along the base coordinate system, 1 - along the tool coordinate system.
int16 dir: force control direction, 0-5 represent X/Y/Z/Rx/Ry/Rz respectively, where the default direction is Z direction for one-axis force type
float32 force: force value, unit: 0.1 N.
bool follow: whether high follow, true: high follow, false: low follow.
uint8 dof:degree of freedom of the robotic arm |
+| Command example | It needs to be a large number (10 or more) of continuous position points, with more than 2ms period continuous release.
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 value | Success: no return; Failure return: false, and the driver terminal returns an error code. |
+
+#### Transmissive_force-position_mixing_control_compensation-pose
+
+| Function description | Transmissive force-position mixing control compensation (pose) |
+| :---: | :---- |
+| Parameter description | Forcepositionmovepose.msg
geometry_msgs/Pose pose: target pose, x, y, z coordinates (float type, unit: m) + quaternion.
uint8 sensor: type of sensor used, 0 - one-axis force, 1 - six-axis force.
uint8 mode: mode, 0 - along the base coordinate system, 1 - along the tool coordinate system
int16 dir: force control direction, 0-5 represent X/Y/Z/Rx/Ry/Rz respectively, where the default direction is Z direction for one-axis force type.
float32 force: force value,unit:0.1 N.
bool follow: whether high follow, true: high follow, false: low follow. |
+| Command example | It needs to be a large number (10 or more) of continuous position points, with more than 2ms period continuous release.
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 value | Success: no return; Failure return: false, and the driver terminal returns an error code.|
+
+### Robotic_arm_state_active_reporting
+
+#### Setting_UDP_robotic_arm_state_active_reporting_configuration
+
+| Function description | Set UDP robotic arm state active reporting configuration |
+| :---: | :---- |
+| Parameter description | Setrealtimepush.msg
uint16 cycle: set the broadcast cycle, which is a multiple of 5ms (default 1 i.e. 1 * 5 = 5 ms, 200 Hz).
uint16 port: set the broadcast port number (default 8089).
uint16 force_coordinate: set the coordinate system of force data outside the system (only supported by the arm with force sensors).
string ip: set the custom reporting target IP address (default 192.168.1.10).
bool hand_enable: whether dexterous hand status reporting is enabled, true is enabled, and false is not enabled.
aloha_state_enable: whether to enable aloha main arm status reporting, true to enable, false not to enable.
arm_current_status_enable: whether to enable the status report of the robot arm, true to enable, false not to enable.
expand_state_enable: whether to enable the report of extended joint related data, true is enabled, false is not enabled.
joint_speed_enable: whether joint speed reporting is enabled, true is enabled, and false is not enabled.
lift_state_enable: whether lifting joint data reporting is enabled, true is enabled, and false is not enabled.
plus_base_enable: Basic information of the end-effector device,true is enabled, and false is not enabled
plus_state_enable: Real-time information of the end-effector device,true is enabled, and false is not enabled. |
+| Command example | ros2 topic pub --once /rm_driver/set_realtime_push_cmd rm_ros_interfaces/msg/Setrealtimepush "cycle: 1
port: 8089
force_coordinate: 0
ip: '192.168.1.10'
hand_enable: false
aloha_state_enable: false
arm_current_status_enable: false
expand_state_enable: false
joint_speed_enable: false
lift_state_enable: false" |
+| Return value | Successful return: true; failure returns: false, the driver terminal returns an error code. |
+| Return example | ros2 topic echo /rm_driver/set_realtime_push_result |
+
+#### Getting_UDP_robotic_arm_state_active_reporting_configuration
+
+| Function description | Get UDP robotic arm state active reporting configuration |
+| :---: | :---- |
+| Parameter description | Setrealtimepush.msg
uint16 cycle: set the broadcast cycle, which is a multiple of 5ms (default 1 i.e. 1 * 5 = 5 ms, 200 Hz).
uint16 port: set the broadcast port number (default 8089).
uint16 force_coordinate: set the coordinate system of force data outside the system (only supported by the arm with force sensors).
string ip: set the custom reporting target IP address (default 192.168.1.10).
bool hand_enable: whether dexterous hand status reporting is enabled, true is enabled, and false is not enabled.
aloha_state_enable: whether to enable aloha main arm status reporting, true to enable, false not to enable.
arm_current_status_enable: whether to enable the status report of the robot arm, true to enable, false not to enable.
expand_state_enable: whether to enable the report of extended joint related data, true is enabled, false is not enabled.
joint_speed_enable: whether joint speed reporting is enabled, true is enabled, and false is not enabled.
lift_state_enable: whether lifting joint data reporting is enabled, true is enabled, and false is not enabled.
plus_base_enable: Basic information of the end-effector device,true is enabled, and false is not enabled
plus_state_enable: Real-time information of the end-effector device,true is enabled, and false is not enabled. |
+| Command example | ros2 topic pub --once /rm_driver/get_realtime_push_cmd std_msgs/msg/Empty "{}" |
+| Return value | Successfully set information; Failure return: the driver terminal returns an error code. |
+| Return example | ros2 topic echo /rm_driver/get_realtime_push_result |
+
+#### UDP_robotic_arm_state_active_reporting
+
+* Six-axis force
+
+| Function description | Six-axis force |
+| :---: | :---- |
+| Parameter description | Sixforce.msg
float32 force_fx: the force along the x-axis direction.
float32 force_fy: the force along the y-axis direction.
float32 force_fz: the force along the z-axis direction.
float32 force_mx: the force when rotating along the x-axis direction.
float32 force_my: the force when rotating along the y-axis direction.
float32 force_mz: the force when rotating along the z-axis direction. |
+| Subscription command | ros2 topic echo /rm_driver/udp_six_force |
+
+* One-axis force
+
+| Function description | One-axis force |
+| :---: | :---- |
+| Parameter description | Sixforce.msg
float32 force_fx: the force along the x-axis direction.
float32 force_fy: the force along the y-axis direction.
float32 force_fz: the force along the z-axis direction.(only this value is valid)
float32 force_mx: the force when rotating along the x-axis direction.
float32 force_my: the force when rotating along the y-axis direction.
float32 force_mz: the force when rotating along the z-axis direction. |
+| Subscription command | ros2 topic echo /rm_driver/udp_one_force |
+
+* Robotic arm error
+
+| Function description | Robotic arm error |
+| :---: | :---- |
+| Parameter description | std_msgs::msg::UInt16
uint16 data: the robotic arm error message. |
+| Subscription command | ros2 topic echo /rm_driver/udp_arm_err |
+
+* System error
+
+| Function description | System error |
+| :---: | :---- |
+| Parameter description | std_msgs::msg::UInt16
uint16 data: the system error message. |
+| Subscription command | ros2 topic echo /rm_driver/udp_sys_err |
+
+* Joint error
+
+| Function description | Joint error |
+| :---: | :---- |
+| Parameter description | Jointerrorcode.msg
uint16[] joint_error: the error message for each joint.
Uint8 dof: the arm degree of freedom message. |
+| Subscription command | ros2 topic echo /rm_driver/udp_joint_error_code |
+
+* The robot arm radians data
+
+| Function description | The robot arm radians data |
+| :---: | :---- |
+| Parameter description | sensor_msgs::msg::JointState
builtin_interfaces/Time stamp
int32 sec: time message, unit: second.
uint32 nanosec: time message, unit: nanosecond.
string frame_id: coordinate system name.
string[] name: joint name.
float64[] position: joint radian message.
float64[] velocity: joint speed message. (not used yet)
float64[] effort: joint force message. (not used yet) |
+| Subscription command | ros2 topic echo /joint_states |
+
+* Pose information
+
+| Function description | Pose information |
+| :---: | :---- |
+| Parameter description | geometry_msgs::msg::Pose
Point position: the robotic arm current coordinate information.
float64 x
float64 y
float64 z
Quaternion orientation: the robotic arm current pose information.
float64 x 0
float64 y 0
float64 z 0
float64 w 1 |
+| Subscription command | ros2 topic echo /rm_driver/udp_arm_position |
+
+* Current external force data of the six-axis force sensor system
+
+| Function description | Current external force data of the six-axis force sensor system |
+| :---: | :---- |
+| Parameter description | Sixforce.msg
float32 force_fx: the force forced on the current sensor along the x-axis direction.
float32 force_fy: the force forced on the current sensor along the y-axis direction.
float32 force_fz: the force forced on the current sensor along the z-axis direction.
float32 force_mx: the force forced on the current sensor when rotating along the x-axis direction.
float32 force_my: the force forced on the current sensor when rotating along the y-axis direction.
float32 force_mz: the force forced on the current sensor when rotating along the z-axis direction. |
+| Subscription command | ros2 topic echo /rm_driver/udp_six_zero_force |
+
+* Current external force data of the one-axis force sensor system
+
+| Function description | Current external force data of the one-axis force sensor system |
+| :---: | :---- |
+| Parameter description | Sixforce.msg
float32 force_fx: the force forced on the current sensor along the x-axis direction.
float32 force_fy: the force forced on the current sensor along the y-axis direction.
float32 force_fz: the force forced on the current sensor along the z-axis direction. (only this data is valid)
float32 force_mx: the force forced on the current sensor when rotating along the x-axis direction.
float32 force_my: the force forced on the current sensor when rotating along the y-axis direction.
float32 force_mz: the force forced on the current sensor when rotating along the z-axis direction. |
+| Subscription command | ros2 topic echo /rm_driver/udp_one_zero_force |
+
+* Reference coordinate system for external force data of the system
+
+| Function description | Reference coordinate system for external force data of the system |
+| :----: | :---- |
+| Parameter description | std_msgs::msg::UInt16
uint16 data: : coordinate system for external force data of the system, where 0 is the sensor coordinate system, 1 is the current work coordinate system, and 2 is the current tool coordinate system This data affects the reference coordinate system for external force data of one-axis and six axis force sensor systems. |
+| Subscription command | ros2 topic echo /rm_driver/udp_arm_coordinate |
+
+
+* The current state of dexterous dexterity
+
+| Function description | The current state of dexterous dexterity |
+| :----: | :---- |
+| Parameter description | rm_ros_interfaces::msg::Handstatus.msg
uint16[6] hand_angle: #Finger angle array,range: 0~2000.
uint16[6] hand_pos: #Finger position array,range: 0~1000.
uint16[6] hand_state: #Finger state,0 is releasing, 1 is grasping, 2 positions are in place and stop, 3 forces are in place and stop, 5 current protection stops, 6 electric cylinder stalling stops, 7 electric cylinder failure stops.
uint16[6] hand_force: #Dexterous hand degree of freedom current,unit mN.
uint16 hand_err: #Agile Hand System Error,1 indicates an error, 0 indicates no error. |
+| Subscription command | ros2 topic echo /rm_driver/udp_hand_status |
+
+* current status of the mechanical arm
+
+| Function Description | Get the current status of the mechanical arm |
+| :----: | :---- |
+| parameter description | rm_ros_interfaces:: msg:: Armcurrentstatus.msg
uint16 arm_current_status: mechanical arm status
0-RM_IDLE_E // enabled but idle status
1-RM_MOVE_L_E // Move L moving state
2-RM_MOVE_J_E // move J moving state
3-RM_MOVE_C_E // move C moving state
4-RM_MOVE_S_E // move S moving state
5-RM_MOVE_THROUGH_JOINT_E /angle transmission state
6-RM_MOVE_THROUGH_POSE_E // posture transmission state
7-RM_MOVE_THROUGH_FORCE_POSE_E//force control transmission state
8-RM_MOVE_THROUGH_CURRENT_E// Current loop transparent state
9-RM_STOP_E // emergency stop state
10-RM_SLOW_STOP_E // slow stop state
11-RM_PAUSE_E // Pause state
12-RM_CURRENT_DRAG_E // Current loop drag state
13-RM_SENSOR_DRAG_E // Six-axis force drag state
14-RM_TECH_DEMONSTRATION_E//Teaching state |
+| query example | ros2 topic echo /rm_driver/udp_arm_current_status |
+
+* Current joint current
+
+| Function Description | Current Joint Current |
+| :----: | :---- |
+| parameter description | rm_ros_interfaces:: msg:: Jointcurrent.msg
float 32 [] joint_current: current joint current with accuracy of 0.001mA |
+| query example | ros2 topic echo /rm_driver/udp_joint_current |
+
+* The current joint enabling state
+
+| Function Description | Current Joint Enabling Status |
+| :----: | :---- |
+| parameter description | rm_ros_interfaces:: msg:: Jointenflag.msg
bool [] joint_en_flag: the current joint enabling state, where 1 is the upper enabling state and 0 is the lower enabling state |
+| query example | ros2 topic echo /rm_driver/udp_joint_en_flag |
+
+* Euler angle posture of mechanical arm
+
+| Function Description | Euler Angle Pose of Mechanical Arm |
+| :----: | :---- |
+| parameter description | rm_ros_interfaces:: msg:: Jointposeeuler.msg
float 32 [3] Euler: Euler angle of current waypoint attitude with accuracy of 0.001rad
float32[3] position: current waypoint position with accuracy of 0.000001M|
+| query example | ros2 topic echo /rm_driver/udp_joint_pose_Euler |
+
+* Current joint speed
+
+| Function Description | Current joint speed |
+| :----: | :---- |
+| parameter description | rm_ros_interfaces:: msg:: Jointspeed.msg
float 32 [] joint_speed: current joint speed with an accuracy of 0.02RPM. |
+| query example | ros2 topic echo /rm_driver/udp_joint_speed |
+
+* Current joint temperature
+
+| Function Description | Current joint temperature |
+| :----: | :---- |
+| parameter description | rm_ros_interfaces:: msg:: Jointtemperature.msg
float 32 [] joint_temperature: current joint temperature with accuracy of 0.001℃|
+| query example | ros2 topic echo /rm_driver/udp_joint_temperature |
+
+* Current joint voltage
+
+| Function Description | Current Joint Voltage |
+| :----: | :---- |
+| parameter description | rm_ros_interfaces:: msg:: Jointvoltage.msg
float 32 [] joint_voltage: current joint voltage with accuracy of 0.001V|
+| query example | ros2 topic echo /rm_driver/udp_joint_voltage |
+
+* Reading Basic Information of End-Effector Device
+
+| Function Description | Reading Basic Information of End-Effector Device |
+| :----: | :---- |
+| parameter description | rm_ros_interfaces::msg::Rmplusbase.msg
string manu:Device manufacturer.
int8 type: Device type, including 1 - Two-finger gripper, 2 - Five-finger dexterous hand, 3 - Three-finger gripper
string hv:Hardware version
string sv:Software version
string bv:Bootloader version
int32 id:Device ID
int8 dof:Degrees of freedom
int8 check:Self-check switch
int8 bee:Beeper switch
bool force:Force control support
bool touch:Tactile support
int8 touch_num:Number of tactile sensors
int8 touch_sw:Tactile switch
int8 hand:Hand orientation, including 1 - Left hand, 2 - Right hand
int32[12] pos_up:Position upper limit
int32[12] pos_low:Position lower limit
int32[12] angle_up:Angle upper limit,Unit: 0.01 degrees.
int32[12] angle_low:Angle lower limit,Unit: 0.01 degrees.
int32[12] speed_up:Speed upper limit
int32[12] speed_low:Speed lower limit
int32[12] force_up:Force upper limit
int32[12] force_low:Force lower limit,Unit: 0.001N.|
+| query example | ros2 topic echo /rm_driver/udp_rm_plus_base |
+
+* Reading Real-Time Information of End-Effector Device
+
+| Function Description | Reading Real-Time Information of End-Effector Device |
+| :----: | :---- |
+| parameter description | rm_ros_interfaces::msg::Rmplusstate.msg
int32 sys_state:System status.
int32[12] dof_state:Current status of each degree of freedom (DoF)
int32[12] dof_err:Error information of each DoF
int32[12] pos: Current position of each DoF
int32[12] speed:Current speed of each DoF
int32[12] angle:Current Angle of Each Degree of Freedom angle,Unit: 0.01 degrees.
int32[12] current:Current of each DoF,Unit: mA.
int32[18] normal_force:Normal force of the tactile three-dimensional force of each DoF
int32[18] tangential_force:Tangential force of the tactile three-dimensional force of each DoF
int32[18] tangential_force_dir:Direction of the tangential force of the tactile three-dimensional force of each DoF
uint32[12] tsa:Tactile self-approach of each DoF
uint32[12] tma:Tactile mutual approach of each DoF
int32[18] touch_data:Raw data from the tactile sensor
int32[12] force:Torque of each DoF,Unit: 0.001N.|
+| query example | ros2 topic echo /rm_driver/udp_rm_plus_state |
diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_driver/doc/rm_driver1.png b/HiveCoreR0/src/ros2_rm_robot-humble/rm_driver/doc/rm_driver1.png
new file mode 100755
index 0000000..8090991
Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_driver/doc/rm_driver1.png differ
diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_driver/doc/rm_driver2.png b/HiveCoreR0/src/ros2_rm_robot-humble/rm_driver/doc/rm_driver2.png
new file mode 100755
index 0000000..0d5bfd3
Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_driver/doc/rm_driver2.png differ
diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_driver/doc/rm_driver3.png b/HiveCoreR0/src/ros2_rm_robot-humble/rm_driver/doc/rm_driver3.png
new file mode 100755
index 0000000..9ac9087
Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_driver/doc/rm_driver3.png differ
diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_driver/doc/rm_driver4.png b/HiveCoreR0/src/ros2_rm_robot-humble/rm_driver/doc/rm_driver4.png
new file mode 100755
index 0000000..dcfd810
Binary files /dev/null and b/HiveCoreR0/src/ros2_rm_robot-humble/rm_driver/doc/rm_driver4.png differ
diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_driver/doc/睿尔曼机械臂ROS2rm_driver话题详细说明.md b/HiveCoreR0/src/ros2_rm_robot-humble/rm_driver/doc/睿尔曼机械臂ROS2rm_driver话题详细说明.md
new file mode 100755
index 0000000..e7803ac
--- /dev/null
+++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_driver/doc/睿尔曼机械臂ROS2rm_driver话题详细说明.md
@@ -0,0 +1,937 @@
+
+
+[中文简体](https://github.com/RealManRobot/ros2_rm_robot/blob/humble/rm_driver/doc/%E7%9D%BF%E5%B0%94%E6%9B%BC%E6%9C%BA%E6%A2%B0%E8%87%82ROS2rm_driver%E8%AF%9D%E9%A2%98%E8%AF%A6%E7%BB%86%E8%AF%B4%E6%98%8E.md)|
+[English](https://github.com/RealManRobot/ros2_rm_robot/blob/humble/rm_driver/doc/RealMan%20Robotic%20Arm%20rm_driver%20Topic%20Detailed%20Description%20(ROS2).md)
+
+
+
+
+
+# 睿尔曼机械臂接口函数说明(ROS2)V1.1.6
+
+
+
+
+
+睿尔曼智能科技(北京)有限公司
+
+文件修订记录:
+
+|版本号 | 时间 | 备注 |
+| :---: | :---- | :---: |
+|V1.0 | 2024-2-18 | 拟制 |
+|V1.1 | 2024-7-8 | 修订(添加示教指令3.6) |
+|V1.1.1| 2024-8-13| 修订(添加查询六维力数据)|
+|V1.1.2| 2024-9-25| 修订(修正坐标系话题描述错误)|
+|V1.1.3| 2024-10-31|修订(添加灵巧手UDP功能,跟随功能)|
+|V1.1.4| 2024-12-25|修订(修改UDP上报内容)|
+|V1.1.5| 2025-02-19|修订(适配API2、添加末端生态协议接口、更新UDP接口)|
+|V1.1.6| 2025-05-19|修订(适配四代控制器、添加版本查询接口、添加笛卡尔空间直线偏移运动接口、添加Modbus接口、添加轨迹列表接口)|
+
+
+
+
+## 目录
+* 1[简介](#简介)
+* 2[报错说明](#报错说明)
+* 2.1[控制器错误类型](#控制器错误类型)
+* 2.2[关节错误类型](#关节错误类型)
+* 2.3[API错误类型](#API错误类型)
+* 3[ROS功能包机械臂相关指令使用说明](#ROS功能包机械臂相关指令使用说明)
+* 3.1[关节配置](#关节配置)
+* 3.1.1[清除关节错误代码](#清除关节错误代码)
+* 3.2[版本查询](#版本查询)
+* 3.2.1[查询机械臂基本信息](#查询机械臂基本信息)
+* 3.2.2[查询机械臂软件版本](#查询机械臂软件版本)
+* 3.2.3[查询关节软件版本](#查询关节软件版本)
+* 3.2.4[查询末端接口板软件版本号](#查询末端接口板软件版本号)
+* 3.3[工作坐标系设置](#工作坐标系设置)
+* 3.3.1[切换当前工作坐标系](#切换当前工作坐标系)
+* 3.4[坐标系查询](#坐标系查询)
+* 3.4.1[查询当前工具坐标系](#查询当前工具坐标系)
+* 3.4.2[查询所有工具坐标系名称](#查询所有工具坐标系名称)
+* 3.4.3[查询当前工作坐标系](#查询当前工作坐标系)
+* 3.4.4[查询所有工作坐标系](#查询所有工作坐标系)
+* 3.5[机械臂状态查询](#机械臂状态查询)
+* 3.5.1[获取机械臂当前状态-返回关节角度+欧拉角](#获取机械臂当前状态-返回各关节角度和欧拉角)
+* 3.5.2[获取机械臂当前状态-返回各关节弧度+四元数](#获取机械臂当前状态-返回各关节弧度和四元数)
+* 3.6[机械臂运动规划](#机械臂运动规划)
+* 3.6.1[关节空间运动](#关节空间运动)
+* 3.6.2[笛卡尔空间直线运动](#笛卡尔空间直线运动)
+* 3.6.3[笛卡尔空间直线偏移运动](#笛卡尔空间直线偏移运动)
+* 3.6.4[笛卡尔空间圆弧运动](#笛卡尔空间圆弧运动)
+* 3.6.5[关节角度CANFD透传](#关节角度CANFD透传)
+* 3.6.6[自定义高跟随模式关节角度CANFD透传](#自定义高跟随关节角度CANFD透传)
+* 3.6.7[位姿CANFD透传](#位姿CANFD透传)
+* 3.6.8[自定义高跟随模式位姿CANFD透传](#自定义高跟随模式位姿CANFD透传)
+* 3.6.9[关节空间规划到目标位姿](#关节空间规划到目标位姿)
+* 3.6.10[轨迹急停](#轨迹急停)
+* 3.6.11[紧急停止](#紧急停止)
+* 3.7[示教指令](#示教指令)
+* 3.7.1[关节示教](#关节示教)
+* 3.7.2[位置示教](#位置示教)
+* 3.7.3[姿态示教](#姿态示教)
+* 3.7.4[示教停止](#示教停止)
+* 3.8[轨迹列表](#轨迹列表)
+* 3.8.1[查询轨迹列表](#查询轨迹列表)
+* 3.8.2[开始运行指定轨迹](#开始运行指定轨迹)
+* 3.8.3[删除指定轨迹文件](#删除指定轨迹文件)
+* 3.8.4[保存轨迹文件](#保存轨迹文件)
+* 3.8.5[查询流程图编程状态](#查询流程图编程状态)
+* 3.9[Modbus模式查询与配置](#Modbus模式查询与配置)
+* 3.9.1[配置控制器通讯端口RS485模式](#配置控制器通讯端口RS485模式)
+* 3.9.2[查询控制器RS485模式](#查询控制器RS485模式)
+* 3.9.3[配置工具端RS485模式](#配置工具端RS485模式)
+* 3.9.4[查询工具端RS485模式](#查询工具端RS485模式)
+* 3.10[ModbusTCP主站](#ModbusTCP主站)
+* 3.10.1[新增Modbus TCP主站](#新增ModbusTCP主站)
+* 3.10.2[更新Modbus TCP主站](#更新ModbusTCP主站)
+* 3.10.3[删除Modbus TCP主站](#删除ModbusTCP主站)
+* 3.10.4[查询指定Modbus主站](#查询指定Modbus主站)
+* 3.10.5[查询Modbus主站列表](#查询Modbus主站列表)
+* 3.11[工具端控制器端RTU Modbus协议读写数据](#工具端控制器端ModbusRTU协议读写数据)
+* 3.11.1[ModbusRTU协议读线圈](#ModbusRTU协议读线圈)
+* 3.11.2[ModbusRTU协议写线圈](#ModbusRTU协议写线圈)
+* 3.11.3[ModbusRTU协议读离散量输入](#ModbusRTU协议读离散量输入)
+* 3.11.4[ModbusRTU协议读保持寄存器](#ModbusRTU协议读保持寄存器)
+* 3.11.5[ModbusRTU协议写保持寄存器](#ModbusRTU协议写保持寄存器)
+* 3.11.6[ModbusRTU协议读输入寄存器](#ModbusRTU协议读输入寄存器)
+* 3.12[控制器ModbusTCP协议读写数据](#控制器ModbusTCP协议读写数据)
+* 3.12.1[ModbusTCP协议读线圈](#ModbusTCP协议读线圈)
+* 3.12.2[ModbusTCP协议写线圈](#ModbusTCP协议写线圈)
+* 3.12.3[ModbusTCP协议读离散量输入](#ModbusTCP协议读离散量输入)
+* 3.12.4[ModbusTCP协议读保持寄存器](#ModbusTCP协议读保持寄存器)
+* 3.12.5[ModbusTCP协议写保持寄存器](#ModbusTCP协议写保持寄存器)
+* 3.12.5[ModbusTCP协议读输入寄存器](#ModbusTCP协议读输入寄存器)
+* 3.13[末端工具IO配置](#末端工具IO配置)
+* 3.13.1[设置工具端电源输出](#设置工具端电源输出)
+* 3.14[末端手爪控制](#末端手爪控制)
+* 3.14.1[设置夹爪力控夹取](#设置夹爪力控夹取)
+* 3.14.2[设置夹爪持续力控夹取](#设置夹爪持续力控夹取)
+* 3.14.3[夹爪到达指定位置](#夹爪到达指定位置)
+* 3.15[拖动示教及轨迹复现](#拖动示教及轨迹复现)
+* 3.15.1[设置力位混合控制](#设置力位混合控制)
+* 3.15.2[结束力位混合控制](#结束力位混合控制)
+* 3.16[末端六维力传感器的使用](#末端六维力传感器的使用)
+* 3.16.1[查询六维力数据](#查询六维力数据)
+* 3.16.2[清空六维力数据](#清空六维力数据)
+* 3.17[末端五指灵巧手控制](#末端五指灵巧手控制)
+* 3.17.1[设置灵巧手手势序号](#设置灵巧手手势序号)
+* 3.17.2[设置灵巧手动作序列](#设置灵巧手动作序列)
+* 3.17.3[设置灵巧手各自由度角度](#设置灵巧手各自由度角度)
+* 3.17.4[设置灵巧手速度](#设置灵巧手速度)
+* 3.17.5[设置灵巧手力阈值](#设置灵巧手力阈值)
+* 3.17.6[设置灵巧手角度跟随](#设置灵巧手角度跟随)
+* 3.17.7[设置灵巧手姿态跟随](#设置灵巧手姿态跟随)
+* 3.18[升降机构](#升降机构)
+* 3.18.1[升降机构速度开环控制](#升降机构速度开环控制)
+* 3.18.2[升降机构位置闭环控制](#升降机构位置闭环控制)
+* 3.18.3[获取升降机构状态](#获取升降机构状态)
+* 3.19[末端生态协议](#末端生态协议)
+* 3.19.1[设置末端生态协议模式](#设置末端生态协议模式)
+* 3.19.2[查询末端生态协议模式](#查询末端生态协议模式)
+* 3.19.3[设置触觉传感器模式](#设置触觉传感器模式)
+* 3.19.4[获取触觉传感器模式](#获取触觉传感器模式)
+* 3.20[透传力位混合控制补偿](#透传力位混合控制补偿)
+* 3.20.1[开启透传力位混合控制补偿模式](#开启透传力位混合控制补偿模式)
+* 3.20.2[关闭透传力位混合控制补偿模式](#关闭透传力位混合控制补偿模式)
+* 3.20.3[透传力位混合补偿-关节](#透传力位混合补偿-关节)
+* 3.20.4[透传力位混合补偿-位姿](#透传力位混合补偿-位姿)
+* 3.21[机械臂状态主动上报](#机械臂状态主动上报)
+* 3.21.1[设置UDP机械臂状态主动上报配置](#设置UDP机械臂状态主动上报配置)
+* 3.21.2[查询UDP机械臂状态主动上报配置](#查询UDP机械臂状态主动上报配置)
+* 3.21.3[UDP机械臂状态主动上报](#UDP机械臂状态主动上报)
+
+
+## 简介
+为了方便用户通过ROS2控制机械臂,睿尔曼提供了基于API的ROS2功能包,有关机械臂的控制细节想要了解的话也可以参考API的相关文档和说明,在实际使用机械臂时,用户可通过以太网口与机械臂建立通信,并控制机械臂。
+## 报错说明
+### 控制器错误类型
+| 序号 | 错误代码(16进制) | 错误内容 |
+| :---: | :---- | :---: |
+| 1 | 0x0000 | 系统正常 |
+| 2 | 0x1001 | 关节通信异常 |
+| 3 | 0x1002 | 目标角度超过限位 |
+| 4 | 0x1003 | 该处不可达,为奇异点 |
+| 5 | 0x1004 | 实时内核通信错误 |
+| 6 | 0x1005 | 关节通信总线错误 |
+| 7 | 0x1006 | 规划层内核错误 |
+| 8 | 0x1007 | 关节超速 |
+| 9 | 0x1008 | 末端接口板无法连接 |
+| 10 | 0x1009 | 超速度限制 |
+| 11 | 0x100A | 超加速度限制 |
+| 12 | 0x100B | 关节抱闸未打开 |
+| 13 | 0x100C | 拖动示教时超速 |
+| 14 | 0x100D | 机械臂发生碰撞 |
+| 15 | 0x100E | 无该工作坐标系 |
+| 16 | 0x100F | 无该工具坐标系 |
+| 17 | 0x1010 | 关节发生掉使能错误 |
+### 关节错误类型
+
+| 序号 | 错误代码(16进制) | 错误内容 |
+| :---: | :---- | :---: |
+| 1 | 0x0000 | 关节正常 |
+| 2 | 0x0001 | FOC错误 |
+| 3 | 0x0002 | 过压 |
+| 4 | 0x0004 | 欠压 |
+| 5 | 0x0008 | 过温 |
+| 6 | 0x0010 | 启动失败 |
+| 7 | 0x0020 | 编码器错误 |
+| 8 | 0x0040 | 过流 |
+| 9 | 0x0080 | 软件错误 |
+| 10 | 0x0100 | 温度传感器错误 |
+| 11 | 0x0200 | 位置超限错误 |
+| 12 | 0x0400 | 关节ID非法 |
+| 13 | 0x0800 | 位置跟踪错误 |
+| 14 | 0x1000 | 电流检测错误 |
+| 15 | 0x2000 | 抱闸打开失败 |
+| 16 | 0x4000 | 位置指令阶跃警告 |
+| 17 | 0x8000 | 多圈关节丢圈数 |
+| 18 | 0xF000 | 通信丢帧 |
+### API错误类型
+
+| 错误代码(int) | 说明 | 处理建议 |
+| :---: | :---- | :--- |
+| 0 | 系统运行正常 | - |
+| 1 | 消息请求返回FALSE | - 校验JSON指令:
①启用API的DEBUG日志,捕获原始JSON数据。
②检查JSON语法:确保括号、引号、逗号等格式正确(可借助JSON校验工具)。
③对照API文档,验证参数名称、数据类型及取值范围是否符合规范。
④修正问题后重新发送指令,检查控制器返回的状态码及业务数据是否正常。
- 检查机械臂状态:
①查看机械臂控制器或日志中的实时报错信息(如硬件故障、超限等),根据提示复位、校准或排查硬件问题。
②修正问题后重新发送指令,检查控制器返回的状态码及业务数据是否正常。|
+| -1 | 数据发送失败,通信过程中出现问题 | 检查网络连通性:
使用ping/telnet等工具检测与控制器的通信链路是否正常。|
+| -2 | 数据接收失败,通信过程中出现问题或者控制器超时没有返回。|- 检查网络连通性:
使用ping/telnet等工具检测与控制器的通信链路是否正常。
- 校验版本兼容性:
①核对控制器固件版本是否支持当前API功能,具体版本配套关系请参考版本变更说明。
②若版本过低需升级控制器或使用适配的API版本。
- 调用ModbusTCP接口:仅在读写控制器ModbusTCP设备时适用,创建机械臂控制句柄后,必须调用rm_set_modbustcp_mode()接口,否则无法接收到返回值。|
+| -3 | 返回值解析失败,接收到的数据格式不正确或不完整。|校验版本兼容性:
①核对控制器固件版本是否支持当前API功能,具体版本配套关系请参考[版本变更说明](#https://develop.realman-robotics.com/robot/releaseNotes/releaseNotes/)。
②若版本过低需升级控制器或使用适配的API版本。|
+| -4 | 当前到位设备校验失败,即当前到位设备不为关节/升降机构/夹爪/灵巧手。| - 检测多设备并发控制:检查是否有其他设备给机械臂发送运动指令:包括机械臂、夹爪、灵巧手、升降机的运动;
- 实时监听指令事件:注册回调函数 rm_get_arm_event_call_back:
①捕获设备到位事件(如运动完成、超时等);
②通过回调参数 device 判断触发事件的具体设备类型 |
+| -5 | 单线程阻塞模式超时未接收到返回,请确保超时时间设置合理。| - 检查超时时长设置:单线程阻塞模式下,支持配置等待设备运动完成的超时时间,务必确保设置超时时间大于设备运动时间;
- 检查网络连通性:
使用ping/telnet等工具检测与控制器的通信链路是否正常。|
+## ROS功能包机械臂相关指令使用说明
+该部分介绍如何来通过ROS话题查询和控制机械臂。
+### 关节配置
+#### 清除关节错误代码
+
+| 功能描述 | 清除关节错误代码 |
+| :---: | :---- |
+| 参数说明 | Jointerrclear.msg
uint8 joint_num:对应关节序号,从基座到机械臂手爪端,六自由度序号依次为1~6,七自由度序号依次为1~7。 |
+| 命令示例 | ros2 topic pub /rm_driver/set_joint_err_clear_cmd rm_ros_interfaces/msg/Jointerrclear "joint_num: 1 " |
+| 返回值 | true-设置成功,false-设置失败 |
+| 返回查询示例 | ros2 topic echo /rm_driver/set_joint_err_clear_result |
+
+### 版本查询
+#### 查询机械臂基本信息
+| 功能描述 | 查询机械臂基本信息 |
+| :---: | :---- |
+| 参数说明 | ROS自带msg std_msgs::msg::Empty |
+| 命令示例 | ros2 topic pub --once /rm_driver/get_robot_info_cmd std_msgs/msg/Empty "{}" |
+| 返回值 | RobotInfo.msg
uint8 arm_dof:机械臂自由度(关节数量)
uint8 arm_model: 机械臂型号 示例:0=RM_65, 1=RM_75, 2=RML_63I(已弃用), 3=RML_63II,4=RML_63III,5=ECO_65,6=ECO_62,7=GEN_72,8=ECO63,9=通用机器人
uint8 force_type 末端力传感器版本,示例:0=标准版, 1=一维力版, 2=六维力版, 3=一体化六维力版
uint8 robot_controller_version机械臂控制器版本(3:三代,4:四代)
bool state:是否读取成功。 |
+| 返回查询示例 | ros2 topic echo /rm_driver/get_robot_info_result |
+#### 查询机械臂软件版本
+| 功能描述 | 查询机械臂软件版本 |
+| :---: | :---- |
+| 参数说明 | ROS自带msg std_msgs::msg::Empty |
+| 命令示例 | ros2 topic pub --once /rm_driver/get_arm_software_version_cmd std_msgs/msg/Empty "{}" |
+| 返回值 | Armsoftversion.msg
string product_version:机械臂型号
string controller_version:机械臂控制器版本,若为四代控制器,则该字段为"4.0"
string algorithm_info:算法库信息
Softwarebuildinfo ctrl_info:ctrl 层软件信息
string dynamic_info :动力学版本(三代)
Softwarebuildinfo plan_info:plan 层软件信息(三代)
Softwarebuildinfo com_info :communication 模块软件信息(四代)
Softwarebuildinfo program_info:流程图编程模块软件信息(四代)
bool state :查询状态 成功true 失败false |
+| 返回查询示例 | ros2 topic echo /rm_driver/get_arm_software_version_result |
+#### 查询关节软件版本
+| 功能描述 | 查询关节软件版本 |
+| :---: | :---- |
+| 参数说明 | ROS自带msg std_msgs::msg::Empty |
+| 命令示例 | ros2 topic pub --once /rm_driver/get_joint_software_version_cmd std_msgs/msg/Empty "{}" |
+| 返回值 | Jointversion.msg
string[7] joint_version:获取到的各关节软件版本号数组,需转换为十六进制,例如获取某关节版本为54536,转换为十六进制为D508,则当前关节的版本号为 Vd5.0.8(三代控制器)
bool state :获取状态 true获取成功 false获取失败。 |
+| 返回查询示例 | ros2 topic echo /rm_driver/get_joint_software_version_result |
+#### 查询末端接口板软件版本号
+| 功能描述 | 查询末端接口板软件版本号 |
+| :---: | :---- |
+| 参数说明 | ROS自带msg std_msgs::msg::Empty |
+| 命令示例 | ros2 topic pub --once /rm_driver/get_tool_software_version_cmd std_msgs/msg/Empty "{}" |
+| 返回值 | Toolsoftwareversionv4.msg
string tool_version: End interface board software version number
boolean state: Query status, success returns true, failure returns false |
+| 返回查询示例 | ros2 topic echo /rm_driver/get_tool_software_version_result |
+
+### 工作坐标系设置
+#### 切换当前工作坐标系
+| 功能描述 | 切换当前工作坐标系 |
+| :---: | :---- |
+| 参数说明 | ROS自带msg std_msgs::msg::String |
+| 命令示例 | ros2 topic pub /rm_driver/change_work_frame_cmd std_msgs/msg/String "data: 'Base'" |
+| 返回值 | true-设置成功,false-设置失败 |
+| 返回查询示例 | ros2 topic echo /rm_driver/change_work_frame_result |
+### 坐标系查询
+#### 查询当前工具坐标系
+| 功能描述 | 查询当前工具坐标系 |
+| :---: | :---- |
+| 参数说明 | ROS自带msg std_msgs::msg::Empty |
+| 命令示例 | ros2 topic pub --once /rm_driver/get_current_tool_frame_cmd std_msgs/msg/Empty "{}" |
+| 返回值 | 当前工具坐标系名称 |
+| 返回查询示例 | ros2 topic echo /rm_driver/get_current_tool_frame_result |
+#### 查询所有工具坐标系名称
+| 功能描述 | 查询所有工具坐标系 |
+| :---: | :---- |
+| 参数说明 | ROS自带msg std_msgs::msg::Empty |
+| 命令示例 | ros2 topic pub /rm_driver/get_all_tool_frame_cmd std_msgs/msg/Empty "{}" |
+| 返回值 | 当前工具坐标系所有名称 |
+| 返回查询示例 | ros2 topic echo /rm_driver/get_all_tool_frame_result |
+#### 查询当前工作坐标系
+| 功能描述 | 查询当前工作坐标系 |
+| :---: | :---- |
+| 参数说明 | ROS自带msg std_msgs::msg::Empty |
+| 命令示例 | ros2 topic pub --once /rm_driver/get_curr_workFrame_cmd std_msgs/msg/Empty "{}" |
+| 返回值 | true-设置成功,false-设置失败 |
+| 返回查询示例 | ros2 topic echo /rm_driver/get_curr_workFrame_result |
+#### 查询所有工作坐标系
+| 功能描述 | 查询所有工作坐标系 |
+| :---: | :---- |
+| 参数说明 | ROS自带msg std_msgs::msg::Empty |
+| 命令示例 | ros2 topic pub --once /rm_driver/get_all_work_frame_cmd std_msgs/msg/Empty "{}" |
+| 返回值 | 所有工作坐标系名称 |
+| 返回查询示例 | ros2 topic echo /rm_driver/get_all_work_frame_result |
+### 机械臂状态查询
+#### 获取机械臂当前状态-返回各关节角度和欧拉角
+| 功能描述 | 获取机械臂当前状态 |
+| :---: | :---- |
+| 参数说明 | ROS自带msg std_msgs::msg::Empty |
+| 命令示例 | ros2 topic pub --once /rm_driver/get_current_arm_state_cmd std_msgs/msg/Empty "{}" |
+| 返回值 | 当前机械臂关节状态(角度)+位姿信息(欧拉角)+报错信息 |
+| 返回查询示例 | ros2 topic echo /rm_driver/get_current_arm_original_state_result |
+#### 获取机械臂当前状态-返回各关节弧度和四元数
+| 功能描述 | 获取机械臂当前状态 |
+| :---: | :---- |
+| 参数说明 | ROS自带msg std_msgs::msg::Empty |
+| 命令示例 | ros2 topic pub --once /rm_driver/get_current_arm_state_cmd std_msgs/msg/Empty "{}" |
+| 返回值 | 当前机械臂关节状态(弧度)+位姿信息(四元数)+报错信息 |
+| 返回查询示例 | ros2 topic echo /rm_driver/get_current_arm_state_result |
+### 机械臂运动规划
+#### 关节空间运动
+| 功能描述 | 关节空间运动MOVEJ |
+| :---: | :---- |
+| 参数说明 | Movej.msg
float32[6] joint:关节角度,单位:弧度。
uint8 speed:速度百分比例系数,0~100。
bool block:是否为阻塞模式,bool类型,true:阻塞,false:非阻塞。 |
+| 命令示例 | 六自由度
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"
七自由度
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" |
+| 返回值 | 成功返回:true;失败返回:false,driver终端返回错误码。 |
+| 返回查询示例 | ros2 topic echo /rm_driver/movej_result |
+#### 笛卡尔空间直线运动
+| 功能描述 | 笛卡尔空间直线运动MOVEL |
+| :---: | :---- |
+| 参数说明 | Movel.msg
geometry_msgs/Pose pose:机械臂位姿,geometry_msgs/Pose类型,x、y、z坐标(float类型,单位:m)+四元数。
uint8 speed:速度百分比例系数,0~100。
bool block:是否为阻塞模式,bool类型,true:阻塞,false:非阻塞。 |
+| 命令示例 | 先使用MoveJP
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"
后使用MoveL
ros2 topic pub --once /rm_driver/movel_cmd rm_ros_interfaces/msg/Movel "pose:
position:
x: -0.317239
y: 0.120903
z: 0.295765
orientation:
x: -0.983404
y: -0.178432
z: 0.032271
w: 0.006129
speed: 20
trajectory_connect: 0
block: true" |
+| 返回值 | 成功返回:true;失败返回:false,driver终端返回错误码。 |
+| 返回查询示例 | ros2 topic echo /rm_driver/movel_result |
+#### 笛卡尔空间直线偏移运动
+| 功能描述 | 笛卡尔空间直线偏移运动 |
+| :---: | :---- |
+| 参数说明 | Moveloffset.msg
geometry_msgs/Pose pose:位置姿态偏移,位置单位:米,姿态单位:弧度
int32 speed:速度百分比系数,1~100
int32 r:交融半径百分比系数,0~100。
bool trajectory_connect:轨迹连接标志,0立即规划并执行轨迹,不与后续轨迹连接。1:将当前轨迹与下一条轨迹一起规划,但不立即执行。阻塞模式下,即使发送成功也会立即返回。
bool frame_type:参考坐标系类型,0工作坐标,1工具坐标
bool block:阻塞设置。多线程模式下,0表示非阻塞模式,发送指令后立即返回;1表示阻塞模式,等待机械臂到达目标位置或规划失败后才返回。单线程模式下,0表示非阻塞模式,发送指令后立即返回;其他值时,阻塞模式并设置超时时间,根据运动时间设置,单位为秒。|
+| 命令示例 | 先使用MoveJP
ros2 topic pub --once /rm_driver/movej_p_cmd rm_ros_interfaces/msg/Movejp "{pose: {position: {x: -0.317239, y: 0.120903, z: 0.255765}, orientation: {x: -0.983404, y: -0.178432, z: 0.032271, w: 0.006129}},speed: 20, trajectory_connect: 0, block: true}"
后使用Movel_offset
ros2 topic pub --once /rm_driver/movel_offset_cmd rm_ros_interfaces/msg/Moveloffset "{pose: {position: {x: -0.317239, y: 0.120903, z: 0.295765}, orientation: {x: -0.983404, y: -0.178432, z: 0.032271, w: 0.006129}}, speed: 20 ,r: 0 ,trajectory_connect: false, frame_type: false,block: false}" |
+| 返回值 | 成功返回:true;失败返回:false,driver终端返回错误码。 |
+| 返回查询示例 | ros2 topic echo /rm_driver/movel_offset_result |
+
+#### 笛卡尔空间圆弧运动
+| 功能描述 | 笛卡尔空间圆弧运动MOVEC |
+| :---: | :---- |
+| 参数说明 | Movec.msg
geometry_msgs/Pose pose_mid:中间位姿,geometry_msgs/Pose类型,x、y、z坐标(float类型,单位:m)+四元数。
geometry_msgs/Pose pose_end:终点位姿,geometry_msgs/Pose类型,x、y、z坐标(float类型,单位:m)+四元数。
uint8 speed:速度百分比例系数,0~100。
bool block:是否为阻塞模式,bool类型,true:阻塞,false:非阻塞。 |
+| 命令示例 | 首先使用movej_p到达指定位置
ros2 topic pub --once /rm_driver/movej_p_cmd rm_ros_interfaces/msg/Movejp "pose:
position:
x: 0.274946
y: -0.058786
z: 0.299028
orientation:
x: 0.7071
y: -0.7071
z: 0.0
w: 0.0
speed: 0
block: true"
使用movec到达指定位置
ros2 topic pub --once /rm_driver/movec_cmd rm_ros_interfaces/msg/Movec "pose_mid:
position:
x: 0.324946
y: -0.008786
z: 0.299028
orientation:
x: 0.7071
y: -0.7071
z: 0.0
w: 0.0
pose_end:
position:
x: 0.274946
y: 0.041214
z: 0.299028
orientation:
x: 0.7071
y: -0.7071
z: 0.0
w: 0.0
speed: 20
trajectory_connect: 0
block: false
loop: 0" |
+| 返回值 | 成功返回:true;失败返回:false,driver终端返回错误码。 |
+| 返回查询示例 | ros2 topic echo /rm_driver/movec_result |
+#### 关节角度CANFD透传
+| 功能描述 | 关节角度CANFD透传 |
+| :---: | :---- |
+| 参数说明 | Jointpos.msg
float32[6] joint:关节角度,单位:弧度。
bool follow:跟随状态,true高跟随,false低跟随,不设置默认高跟随。
float32 expand:拓展关节,单位:弧度。 |
+| 命令示例 | 透传需要连续发送多个连续的点实现,单纯靠以下命令并不能实现功能,当前moveit2控制使用了角度透传的控制方式。
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" |
+| 返回值 | 成功:无返回值;失败返回:driver终端返回错误码。 |
+#### 自定义高跟随模式关节角度CANFD透传
+| 功能描述 | 自定义高跟随模式关节角度CANFD透传 |
+| :---: | :---- |
+| 参数说明 | Jointposcustom.msg
float32[6] joint:关节角度,单位:弧度。
bool follow:跟随状态,true高跟随,false低跟随,不设置默认高跟随。
float32 expand:拓展关节,单位:弧度。
uint8 trajectory_mode: 高跟随模式下,支持多种模式,0-完全透传模式、1-曲线拟合模式、2-滤波模式。
uint8 radio: 设置曲线拟合模式下平滑系数(范围0-100)或者滤波模式下的滤波参数(范围0-1000),数值越大表示平滑效果越好 |
+| 命令示例 | 透传需要连续发送多个连续的点实现,单纯靠以下命令并不能实现功能,当前moveit2控制使用了角度透传的控制方式。
ros2 topic pub /rm_driver/movej_canfd_custom_cmd rm_ros_interfaces/msg/Jointposcustom "joint: [0, 0, 0, 0, 0, 0]
follow: false
expand: 0.0
trajectory_mode: 0
radio: 0
dof: 6" |
+| 返回值 | 成功:无返回值;失败返回:driver终端返回错误码。 |
+
+#### 位姿CANFD透传
+| 功能描述 | 位姿CANFD透传 |
+| :---: | :---- |
+| 参数说明 | Cartepos.msg
geometry_msgs/Pose pose:透传位姿,geometry_msgs/Pose类型,x、y、z坐标(float类型,单位:m)+四元数。
bool follow:跟随状态,true高跟随,false低跟随,不设置默认高跟随。 |
+| 命令示例 | 需要是大量(10个以上)位置连续 的点,单纯靠以下命令并不能实现功能,以2ms以上的周期持续发布。
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" |
+| 返回值 | 成功:无返回值;失败返回:driver终端返回错误码。 |
+#### 自定义高跟随模式位姿CANFD透传
+| 功能描述 | 自定义高跟随模式位姿CANFD透传 |
+| :---: | :---- |
+| 参数说明 | Carteposcustom.msg
geometry_msgs/Pose pose:透传位姿,geometry_msgs/Pose类型,x、y、z坐标(float类型,单位:m)+四元数。
bool follow:跟随状态,true高跟随,false低跟随,不设置默认高跟随。
uint8 trajectory_mode: 高跟随模式下,支持多种模式,0-完全透传模式、1-曲线拟合模式、2-滤波模式。
uint8 radio: 设置曲线拟合模式下平滑系数(范围0-100)或者滤波模式下的滤波参数(范围0-1000),数值越大表示平滑效果越好|
+| 命令示例 | 需要是大量(10个以上)位置连续 的点,单纯靠以下命令并不能实现功能,以2ms以上的周期持续发布。
ros2 topic pub /rm_driver/movep_canfd_custom_cmd rm_ros_interfaces/msg/Carteposcustom
"pose:
position:
x: 0.0
y: 0.0
z: 0.0
orientation:
x: 0.0
y: 0.0
z: 0.0
w: 1.0
follow: false
trajectory_mode: 0
radio: 0" |
+| 返回值 | 成功:无返回值;失败返回:driver终端返回错误码。 |
+#### 关节空间规划到目标位姿
+| 功能描述 | 关节空间规划到目标位姿MOVEJP |
+| :---: | :---- |
+| 参数说明 | Movejp.msg
geometry_msgs/Pose pose:目标位姿,x、y、z坐标(float类型,单位:m)+四元数。
uint8 speed:速度百分比例系数,0~100。
bool block:是否为阻塞模式,true:阻塞,false:非阻塞。 |
+| 命令示例 | 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" |
+| 返回值 | 成功返回:true;失败返回:false,driver终端返回错误码。 |
+| 返回查询示例 | ros2 topic echo /rm_driver/movej_p_result |
+#### 轨迹急停
+| 功能描述 | 运动规划轨迹急停 |
+| :---: | :---- |
+| 参数说明 | ROS官方msg std_msgs::msg::Empty |
+| 命令示例 | ros2 topic pub /rm_driver/move_stop_cmd std_msgs/msg/Empty "{}" |
+| 返回值 | 成功返回:true;失败返回:false,driver终端返回错误码。 |
+| 返回查询示例 | ros2 topic echo /rm_driver/move_stop_result |
+#### 紧急停止
+| 功能描述 | 设置机械臂急停状态 |
+| :---: | :---- |
+| 参数说明 | rm_ros_interfaces/Stop 急停状态,true:急停,false:恢复|
+| 命令示例 | ros2 topic pub --once /rm_driver/emergency_stop_cmd rm_ros_interfaces/Stop "state: true" |
+| 返回值 | 成功返回:true;失败返回:false,driver终端返回错误码。 |
+| 返回查询示例 | ros2 topic echo /rm_driver/emergency_stop_result |
+### 示教指令
+#### 关节示教
+| 功能描述 | 关节示教 |
+| :---: | :---- |
+| 参数说明 | Jointteach.msg
uint8 num:示教关节的序号,1~7
uint8 direction:示教方向,0-负方向,1-正方向
uint8 speed:速度百分比例系数,0~100 |
+| 命令示例 | ros2 topic pub /rm_driver/set_joint_teach_cmd rm_ros_interfaces/msg/Jointteach "num: 1
direction: 0
speed: 10" |
+| 返回值 | 成功返回:true;失败返回:false,driver终端返回错误码。 |
+| 返回查询示例 | ros2 topic echo /rm_driver/set_joint_teach_result |
+#### 位置示教
+| 功能描述 | 位置示教 |
+| :---: | :---- |
+| 参数说明 | Posteach.msg
uint8 type:示教类型 输入0X轴方向、1Y轴方向、2Z轴方向
uint8 direction:示教方向,0-负方向,1-正方向
uint8 speed:速度百分比例系数,0~100。|
+| 命令示例 | ros2 topic pub /rm_driver/set_pos_teach_cmd rm_ros_interfaces/msg/Posteach "type: 2
direction: 0
speed: 10" |
+| 返回值 | 成功返回:true;失败返回:false,driver终端返回错误码。 |
+| 返回查询示例 | ros2 topic echo /rm_driver/set_pos_teach_result |
+#### 姿态示教
+| 功能描述 | 姿态示教 |
+| :---: | :---- |
+| 参数说明 | Ortteach.msg
uint8 type:示教类型 输入0RX轴方向、1RY轴方向、2RZ轴方向
uint8 direction:示教方向,0-负方向,1-正方向
uint8 speed:速度百分比例系数,0~100。|
+| 命令示例 | ros2 topic pub /rm_driver/set_ort_teach_cmd rm_ros_interfaces/msg/Ortteach "type: 2
direction: 0
speed: 10" |
+| 返回值 | 成功返回:true;失败返回:false,driver终端返回错误码。 |
+| 返回查询示例 | ros2 topic echo /rm_driver/set_ort_teach_result |
+#### 示教停止
+| 功能描述 | 示教停止 |
+| :---: | :---- |
+| 参数说明 | ROS官方msg std_msgs::msg::Empty |
+| 命令示例 | ros2 topic pub /rm_driver/set_stop_teach_cmd std_msgs/msg/Empty "{}" |
+| 返回值 | 成功返回:true;失败返回:false,driver终端返回错误码。 |
+| 返回查询示例 | ros2 topic echo /rm_driver/set_stop_teach_result |
+### 轨迹列表
+#### 查询轨迹列表
+| 功能描述 | 查询轨迹列表 |
+| :---: | :---- |
+| 参数说明 | Gettrajectorylist.msg
int32 page_num: 页码。
int32 page_size: 每页大小。
string vague_search: 模糊搜索。 |
+| 命令示例 | ros2 topic pub --once /rm_driver/get_trajectory_file_list_cmd rm_ros_interfaces/msg/Gettrajectorylist "{page_num: 1,page_size: 10,vague_search: 's'}" |
+| 返回值 | Trajectorylist.msg
int32 page_num # 页码
int32 page_size # 每页大小
int32 total_size # 列表长度
string vague_search # 模糊搜索
Trajectoryinfo[] tra_list # 返回符合的轨迹列表
bool state # 查询状态 成功true 失败false |
+| 返回查询示例 | ros2 topic echo /rm_driver/get_trajectory_file_list_result |
+#### 开始运行指定轨迹
+| 功能描述 | 开始运行指定轨迹 |
+| :---: | :---- |
+| 参数说明 | ROS官方msg std_msgs::msg::String |
+| 命令示例 | ros2 topic pub --once /rm_driver/set_run_trajectory_cmd std_msgs/msg/String "data: 'sss'" |
+| 返回值 | 成功返回:true;失败返回:false,driver终端返回错误码。 |
+| 返回查询示例 | ros2 topic echo /rm_driver/set_run_trajectory_result |
+#### 删除指定轨迹文件
+| 功能描述 | 删除指定轨迹文件 |
+| :---: | :---- |
+| 参数说明 | ROS官方msg std_msgs::msg::String |
+| 命令示例 | ros2 topic pub --once /rm_driver/delete_trajectory_file_cmd std_msgs/msg/String "data: 'sss'" |
+| 返回值 | 成功返回:true;失败返回:false,driver终端返回错误码。 |
+| 返回查询示例 | ros2 topic echo /rm_driver/delete_trajectory_file_result |
+#### 保存轨迹文件
+| 功能描述 | 保存轨迹文件 |
+| :---: | :---- |
+| 参数说明 | ROS官方msg std_msgs::msg::String |
+| 命令示例 | ros2 topic pub --once /rm_driver/save_trajectory_file_cmd std_msgs/msg/String "data: 'test'" |
+| 返回值 | 成功返回:true;失败返回:false,driver终端返回错误码。 |
+| 返回查询示例 | ros2 topic echo /rm_driver/save_trajectory_file_result |
+#### 查询流程图编程状态
+| 功能描述 | 查询流程图编程状态 |
+| :---: | :---- |
+| 参数说明 | ROS官方msg std_msgs/msg/Empty |
+| 命令示例 | ros2 topic pub --once /rm_driver/get_flowchart_program_run_state_cmd std_msgs/msg/Empty "{}" |
+| 返回值 | Flowchartrunstate.msg
int run_state; #运行状态 0 未开始 1运行中 2暂停中
int id;#当前使能的文件id。
char name[32]; #当前使能的文件名称。
int plan_speed;#当前使能的文件全局规划速度比例 1-100。
int step_mode;#单步模式,0为空,1为正常, 2为单步。
char modal_id[50];#运行到的流程图块的id。
bool state:正常运行返回true,未正常运行则返回false |
+| 返回查询示例 | ros2 topic echo /rm_driver/get_flowchart_program_run_state_result |
+### Modbus模式查询与配置
+#### 配置控制器通讯端口RS485模式
+| 功能描述 | 配置控制器通讯端口RS485模式 |
+| :---: | :---- |
+| 参数说明 | RS485params.msg
int32 mode: 0-RS485串行通讯,1-modbus-RTU主站模式,2-modbus-RTU从站模式。
int32 baudrate: 当前支持9600 19200 38400 57600 115200 230400 460800。 |
+| 命令示例 | ros2 topic pub --once /rm_driver/set_controller_rs485_mode_cmd rm_ros_interfaces/msg/RS485params "{mode: 0, baudrate: 115200}" |
+| 返回值 | 成功返回:true;失败返回:false,driver终端返回错误码。 |
+| 返回查询示例 | ros2 topic echo /rm_driver/set_controller_rs485_mode_result |
+#### 查询控制器RS485模式
+| 功能描述 | 查询控制器RS485模式 |
+| :---: | :---- |
+| 参数说明 | ROS官方msg std_msgs::msg::Empty |
+| 命令示例 | ros2 topic pub --once /rm_driv/get_controller_rs485_mode_cmd std_msgs/msg/Empty "{}" |
+| 返回值 | RS485params.msg
int32 mode # 0代表默认RS485串行通讯,1代表modbus-RTU主站模式,2-代表modbus-RTU从站模式。
int32 baudrate # 波特率(当前支持9600 19200 38400 57600 115200 230400 460800)
bool state # 查询状态 true查询成功 false查询失败 |
+| 返回查询示例 | ros2 topic echo /rm_driver/get_controller_rs485_mode_result |
+#### 配置工具端RS485模式
+| 功能描述 | 配置工具端RS485模式 |
+| :---: | :---- |
+| 参数说明 | RS485params.msg
int32 mode: 0-设置工具端RS485端口为RTU主站,1-灵巧手模式,2-夹爪模式。
int32 baudrate: 当前支持9600,115200,460800。 |
+| 命令示例 | ros2 topic pub --once /rm_driver/set_tool_rs485_mode_cmd rm_ros_interfaces/msg/RS485params "{mode: 0, baudrate: 115200}" |
+| 返回值 | 成功返回:true;失败返回:false,driver终端返回错误码。 |
+| 返回查询示例 | ros2 topic echo /rm_driver/set_tool_rs485_mode_result |
+#### 查询工具端RS485模式
+| 功能描述 | 查询工具端RS485模式 |
+| :---: | :---- |
+| 参数说明 | ROS官方msg std_msgs::msg::Empty |
+| 命令示例 | ros2 topic pub --once /rm_driver/get_tool_rs485_mode_cmd std_msgs/msg/Empty "{}" |
+| 返回值 | RS485params.msg
int32 mode # 0-设置工具端RS485端口为RTU主站,1-灵巧手模式,2-夹爪模式。
int32 baudrate # 波特率(当前支持9600 19200 38400 57600 115200 230400 460800)
bool state # 查询状态 true查询成功 false查询失败。 |
+| 返回查询示例 | ros2 topic echo /rm_driver/get_tool_rs485_mode_result |
+### ModbusTCP主站
+#### 新增ModbusTCP主站
+| 功能描述 | 新增ModbusTCP主站 |
+| :---: | :---- |
+| 参数说明 | Modbustcpmasterinfo.msg
string master_name: Modbus主站名称。
string ip: TCP主站IP地址。
int32 port: TCP主站端口号。 |
+| 命令示例 | ros2 topic pub --once /rm_driver/add_modbus_tcp_master_cmd rm_ros_interfaces/msg/Modbustcpmasterinfo "{master_name: '1',ip: '127.0.0.1',port: 502}" |
+| 返回值 | 成功返回:true;失败返回:false,driver终端返回错误码。 |
+| 返回查询示例 | ros2 topic echo /rm_driver/add_modbus_tcp_master_result |
+#### 更新ModbusTCP主站
+| 功能描述 | 更新ModbusTCP主站 |
+| :---: | :---- |
+| 参数说明 | Modbustcpmasterinfo.msg
string master_name: Modbus原本的主站名称。
string new_master_name: Modbus新的主站名称。
string ip: TCP主站IP地址。
int32 port: TCP主站端口号。 |
+| 命令示例 | ros2 topic pub /rm_driver/update_modbus_tcp_master_cmd rm_ros_interfaces/msg/Modbustcpmasterinfo "{master_name: '1',new_master_name: '125',ip: '127.0.0.1',port: 502}" |
+| 返回值 | 成功返回:true;失败返回:false,driver终端返回错误码。 |
+| 返回查询示例 | ros2 topic echo /rm_driver/update_modbus_tcp_master_result |
+#### 删除ModbusTCP主站
+| 功能描述 | 删除ModbusTCP主站 |
+| :---: | :---- |
+| 参数说明 | Mastername.msg
string master_name: Modbus主站名称。 |
+| 命令示例 | ros2 topic pub --once /rm_driver/delete_modbus_tcp_master_cmd rm_ros_interfaces/msg/Mastername "master_name: '321'" |
+| 返回值 | 成功返回:true;失败返回:false,driver终端返回错误码。 |
+| 返回查询示例 | ros2 topic echo /rm_driver/delete_modbus_tcp_master_result |
+#### 查询指定Modbus主站
+| 功能描述 | 查询指定Modbus主站 |
+| :---: | :---- |
+| 参数说明 | Mastername.msg
string master_name: Modbus主站名称。 |
+| 命令示例 | ros2 topic pub --once /rm_driver/get_modbus_tcp_master_cmd rm_ros_interfaces/msg/Mastername "master_name: '321'" |
+| 返回值 | Modbustcpmasterinfo.msg
string master_name # Modbus主站名称,最大长度15个字符,不超过15个字符
string ip # TCP主站IP地址
int32 port # TCP主站端口号
bool state # 查询状态信息,失败为false,成功为true
失败返回:false,driver终端返回错误码。 |
+| 返回查询示例 | ros2 topic echo /rm_driver/get_modbus_tcp_master_result |
+#### 查询Modbus主站列表
+| 功能描述 | 查询Modbus主站列表 |
+| :---: | :---- |
+| 参数说明 | Getmodbustcpmasterlist.msg
int32 page_num: 页码。
int32 page_size: 每页大小。
string vague_search: 模糊搜索,若输入为空则返回所有主站列表。 |
+| 命令示例 | ros2 topic pub --once /rm_driver/get_modbus_tcp_master_list_cmd rm_ros_interfaces/msg/Getmodbustcpmasterlist "{page_num: 1,page_size: 10,vague_search: '1'}" |
+| 返回值 | Modbustcpmasterlist.msg
uint8 page_num # 页码
uint8 page_size # 每页大小
uint8 total_size # 列表长度
string vague_search # 模糊搜索
Modbustcpmasterinfo[] master_list # 返回符合的TCP主站列表
bool state # 查询状态 成功true 失败false
失败返回:false,driver终端返回错误码。 |
+| 返回查询示例 | ros2 topic echo /rm_driver/get_modbus_tcp_master_list_result |
+
+### 工具端控制器端ModbusRTU协议读写数据
+#### ModbusRTU协议读线圈
+| 功能描述 | ModbusRTU协议读线圈 |
+| :---: | :---- |
+| 参数说明 | Modbusrtureadparams.msg
int32 address: 数据起始地址。
int32 device: 外设设备地址 。
int32 type: 0-控制器端Modbus主机;1-工具端Modbus主机。
int32 num: 要读的数据的数量,数据长度不超过100。 |
+| 命令示例 | ros2 topic pub /rm_driver/read_modbus_rtu_coils_cmd rm_ros_interfaces/msg/Modbusrtureadparams "{address: 0, device: 1, type: 0, num: 1}" |
+| 返回值 | Modbusreaddata.msg
int32[] read_data # 读取到的modbus数据
bool state # 反馈查询状态信息,失败为false,成功true
失败driver终端返回错误码。 |
+| 返回查询示例 | ros2 topic echo /rm_driver/read_modbus_rtu_coils_result |
+#### ModbusRTU协议写线圈
+| 功能描述 | ModbusRTU协议写线圈 |
+| :---: | :---- |
+| 参数说明 | Modbusrtuwriteparams.msg
int32 address: 数据起始地址。
int32 device: 外设设备地址。
int32 type: 0-控制器端modbus主机;1-工具端modbus主机。
int32 num: 要写的数据的数量,最大不超过100。
int32[] data: 要写的数据,数据长度与num对应。 |
+| 命令示例 | ros2 topic pub /rm_driver/write_modbus_rtu_coils_cmd rm_ros_interfaces/msg/Modbusrtuwriteparams "{address: 0, device: 1, type: 0, num: 2, data: [1,1]}" |
+| 返回值 | 成功返回:true;失败返回:false,driver终端返回错误码。 |
+| 返回查询示例 | ros2 topic echo /rm_driver/write_modbus_rtu_coils_result |
+#### ModbusRTU协议读离散量输入
+| 功能描述 | ModbusRTU协议读离散量输入 |
+| :---: | :---- |
+| 参数说明 | Modbusrtureadparams.msg
int32 address: 数据起始地址。
int32 device: 外设设备地址 。
int32 type: 0-控制器端modbus主机;1-工具端modbus主机。。
int32 num: 要读的数据的数量,数据长度不超过100。 |
+| 命令示例 | ros2 topic pub /rm_driver/read_modbus_rtu_input_status_cmd rm_ros_interfaces/msg/Modbusrtureadparams "{address: 0, device: 0, type: 0, num: 1}" |
+| 返回值 | Modbusreaddata.msg
int32[] read_data # 读取到的modbus数据
bool state # 反馈查询状态信息,失败为false,成功true
失败driver终端返回错误码。 |
+| 返回查询示例 | ros2 topic echo /rm_driver/read_modbus_rtu_input_status_result |
+#### ModbusRTU协议读保持寄存器
+| 功能描述 | ModbusRTU协议读保持寄存器 |
+| :---: | :---- |
+| 参数说明 | Modbusrtureadparams.msg
int32 address: 数据起始地址。
int32 device: 外设设备地址 。
int32 type: 0-控制器端Modbus主机;1-工具端Modbus主机。。
int32 num: 要读的数据的数量,数据长度不超过100。 |
+| 命令示例 | ros2 topic pub /rm_driver/read_modbus_rtu_holding_registers_cmd rm_ros_interfaces/msg/Modbusrtureadparams "{address: 0, device: 0, type: 0, num: 1}" |
+| 返回值 | Modbusreaddata.msg
int32[] read_data # 读取到的modbus数据
bool state # 反馈查询状态信息,失败为false,成功true
失败driver终端返回错误码。 |
+| 返回查询示例 | ros2 topic echo /rm_driver/read_modbus_rtu_holding_registers_result |
+#### ModbusRTU协议写保持寄存器
+| 功能描述 | ModbusRTU协议写保持寄存器 |
+| :---: | :---- |
+| 参数说明 | Modbusrtuwriteparams.msg
int32 address: 数据起始地址
int32 device: 外设设备地址
int32 type: 0-控制器端Modbus主机;1-工具端Modbus主机。
int32 num: 要写的数据的数量,最大不超过100
int32[] data: 要写的数据,数据长度与num对应。 |
+| 命令示例 | ros2 topic pub /rm_driver/write_modbus_rtu_registers_cmd rm_ros_interfaces/msg/Modbusrtuwriteparams "{address: 0, device: 0, type: 0, num: 2, data: [1,1]}" |
+| 返回值 | 成功返回:true;失败返回:false,driver终端返回错误码。 |
+| 返回查询示例 | ros2 topic echo /rm_driver/write_modbus_rtu_registers_result |
+#### ModbusRTU协议读输入寄存器
+| 功能描述 | ModbusRTU协议读输入寄存器 |
+| :---: | :---- |
+| 参数说明 | Modbusrtureadparams.msg
int32 address: 数据起始地址。
int32 device: 外设设备地址 。
int32 type: 0-控制器端modbus主机;1-工具端modbus主机。。
int32 num: 要读的数据的数量,数据长度不超过100。 |
+| 命令示例 | ros2 topic pub /rm_driver/read_modbus_rtu_input_registers_cmd rm_ros_interfaces/msg/Modbusrtureadparams "{address: 0, device: 0, type: 0, num: 1}" |
+| 返回值 | Modbusreaddata.msg
int32[] read_data # 读取到的modbus数据
bool state # 反馈查询状态信息,失败为false,成功true
失败driver终端返回错误码。 |
+| 返回查询示例 | ros2 topic echo /rm_driver/read_modbus_rtu_input_registers_result |
+### 控制器ModbusTCP协议读写数据
+#### ModbusTCP协议读线圈
+| 功能描述 | ModbusTCP协议读线圈 |
+| :---: | :---- |
+| 参数说明 | Modbustcpreadparams.msg
int32 address: 数据起始地址。
string master_name: Modbus 主站名称,最大长度15个字符。
string ip: 主机连接的 IP 地址。
int32 port: 主机连接的端口号。
int32 num: 读取数据数量,最大不超过100。 |
+| 命令示例 | ros2 topic pub /rm_driver/read_modbus_tcp_coils_cmd rm_ros_interfaces/msg/Modbustcpreadparams "{address: 0,master_name: '3',ip: '127.0.0.6',port: 502,num: 1}" |
+| 返回值 | Modbusreaddata.msg
int32[] read_data # 读取到的modbus数据
bool state # 反馈查询状态信息,失败为false,成功true
失败driver终端返回错误码。 |
+| 返回查询示例 | ros2 topic echo /rm_driver/read_modbus_tcp_coils_result |
+#### ModbusTCP协议写线圈
+| 功能描述 | ModbusTCP协议写线圈 |
+| :---: | :---- |
+| 参数说明 | Modbustcpwriteparams.msg
int32 address: 数据起始地址。
string master_name: Modbus 主站名称,最大长度15个字符。
string ip: 主机连接的 IP 地址。
int32 port: 主机连接的端口号。
int32 num: 写入数据数量,最大不超过100。
int32[] data: 写入的数据,数据长度与num对应。 |
+| 命令示例 | ros2 topic pub /rm_driver/write_modbus_tcp_coils_cmd rm_ros_interfaces/msg/Modbustcpwriteparams "{address: 0,master_name: '3',ip: '127.0.0.6',port: 502, num: 2, data: [1,1]}" |
+| 返回值 | 成功返回:true;失败返回:false,driver终端返回错误码。 |
+| 返回查询示例 | ros2 topic echo /rm_driver/write_modbus_tcp_coils_result |
+#### ModbusTCP协议读离散量输入
+| 功能描述 | ModbusTCP协议读离散量输入 |
+| :---: | :---- |
+| 参数说明 | Modbustcpreadparams.msg
int32 address: 数据起始地址。
string master_name: Modbus 主站名称,最大长度15个字符。
string ip: 主机连接的 IP 地址。
int32 port: 主机连接的端口号。
int32 num: 读取数据数量,最大不超过100。 |
+| 命令示例 | ros2 topic pub /rm_driver/read_modbus_tcp_input_status_cmd rm_ros_interfaces/msg/Modbustcpreadparams "{address: 0,master_name: '3',ip: '127.0.0.6',port: 502,num: 1}" |
+| 返回值 | Modbusreaddata.msg
int32[] read_data # 读取到的modbus数据
bool state # 反馈查询状态信息,失败为false,成功true
失败driver终端返回错误码。 |
+| 返回查询示例 | ros2 topic echo /rm_driver/read_modbus_tcp_input_status_result |
+#### ModbusTCP协议读保持寄存器
+| 功能描述 | ModbusTCP协议读保持寄存器 |
+| :---: | :---- |
+| 参数说明 | Modbustcpreadparams.msg
int32 address: 数据起始地址。
string master_name: Modbus 主站名称,最大长度15个字符。
string ip: 主机连接的 IP 地址。
int32 port: 主机连接的端口号。
int32 num: 读取数据数量,最大不超过100。 |
+| 命令示例 | ros2 topic pub /rm_driver/read_modbus_tcp_holding_registers_cmd rm_ros_interfaces/msg/Modbustcpreadparams "{address: 0,master_name: '3',ip: '127.0.0.6',port: 502,num: 1}" |
+| 返回值 | Modbusreaddata.msg
int32[] read_data # 读取到的modbus数据
bool state # 反馈查询状态信息,失败为false,成功true
失败driver终端返回错误码。 |
+| 返回查询示例 | ros2 topic echo /rm_driver/read_modbus_tcp_holding_registers_result |
+#### ModbusTCP协议写保持寄存器
+| 功能描述 | ModbusTCP协议写保持寄存器 |
+| :---: | :---- |
+| 参数说明 | Modbustcpwriteparams.msg
int32 address: 数据起始地址。
string master_name: Modbus 主站名称,最大长度15个字符。
string ip: 主机连接的 IP 地址。
int32 port: 主机连接的端口号。
int32 num: 写入数据数量,最大不超过100。
int32[] data: 写入的数据,数据长度与num对应。 |
+| 命令示例 | ros2 topic pub /rm_driver/write_modbus_tcp_registers_cmd rm_ros_interfaces/msg/Modbustcpwriteparams "{address: 0,master_name: '3',ip: '127.0.0.6',port: 502, num: 2, data: [1,1]}" |
+| 返回值 | 成功返回:true;失败返回:false,driver终端返回错误码。 |
+| 返回查询示例 | ros2 topic echo /rm_driver/write_modbus_tcp_registers_result |
+#### ModbusTCP协议读输入寄存器
+| 功能描述 | ModbusTCP协议读输入寄存器 |
+| :---: | :---- |
+| 参数说明 | Modbustcpreadparams.msg
int32 address: 数据起始地址。
string master_name: Modbus 主站名称,最大长度15个字符。
string ip: 主机连接的 IP 地址。
int32 port: 主机连接的端口号。
int32 num: 读取数据数量,最大不超过100。 |
+| 命令示例 | ros2 topic pub /rm_driver/read_modbus_tcp_input_registers_cmd rm_ros_interfaces/msg/Modbustcpreadparams "{address: 0,master_name: '3',ip: '127.0.0.6',port: 502,num: 1}" |
+| 返回值 | Modbusreaddata.msg
int32[] read_data # 读取到的modbus数据
bool state # 反馈查询状态信息,失败为false,成功true
失败driver终端返回错误码。 |
+| 返回查询示例 | ros2 topic echo /rm_driver/read_modbus_tcp_input_registers_result |
+### 末端工具IO配置
+#### 设置工具端电源输出
+| 功能描述 | 设置工具端电源输出 |
+| :---: | :---- |
+| 参数说明 | ROS自带消息文件:std_msgs::msg::UInt16
uint16 data:电源输出类型,范围:0~3 0-0V,1-5V,2-12V,3-24V |
+| 命令示例 | ros2 topic pub --once /rm_driver/set_tool_voltage_cmd std_msgs/msg/UInt16 "data: 0" |
+| 返回值 | 成功返回:true;失败返回:false,driver终端返回错误码。 |
+| 返回查询示例 | ros2 topic echo /rm_driver/set_tool_voltage_result |
+### 末端手爪控制
+睿尔曼机械臂末端配备了因时机器人公司的EG2-4C2手爪,为了便于用户操作手爪,机械臂控制器对用户适配了手爪的ROS控制方式
+#### 设置夹爪力控夹取
+| 功能描述 | 设置夹爪力控夹取 |
+| :---: | :---- |
+| 参数说明 | Gripperpick.msg
uint16 speed:1~1000,代表手爪开合速度,无量纲。
uint16 force:1~1000,代表手爪夹持力,最大1.5kg。
bool block:是否为阻塞模式,true:阻塞,false:非阻塞。 |
+| 命令示例 | ros2 topic pub --once /rm_driver/set_gripper_pick_cmd rm_ros_interfaces/msg/Gripperpick "speed: 200
force: 200
block: true
timeout: 1000" |
+| 返回值 | 成功返回:true;失败返回:false,driver终端返回错误码。 |
+| 返回查询示例 | ros2 topic echo /rm_driver/set_gripper_pick_result |
+#### 设置夹爪持续力控夹取
+| 功能描述 | 设置夹爪持续力控夹取 |
+| :---: | :---- |
+| 参数说明 | Gripperpick.msg
uint16 speed:1~1000,代表手爪开合速度,无量纲。
uint16 force:1~1000,代表手爪夹持力,最大1.5kg。
bool block:是否为阻塞模式,true:阻塞,false:非阻塞。 |
+| 命令示例 | ros2 topic pub --once /rm_driver/set_gripper_pick_on_cmd rm_ros_interfaces/msg/Gripperpick "speed: 200
force: 200
block: true
timeout: 1000" |
+| 返回值 | 成功返回:true;失败返回:false,driver终端返回错误码。 |
+| 返回查询示例 | ros2 topic echo /rm_driver/set_gripper_pick_on_result |
+#### 夹爪到达指定位置
+| 功能描述 | 夹爪到达指定位置 |
+| :---: | :---- |
+| 参数说明 | Gripperset.msg
uint16 position:手爪目标位置,范围:1~1000,代表手爪开口度:0~70mm
bool block:是否为阻塞模式,true:阻塞,false:非阻塞。 |
+| 命令示例 | ros2 topic pub --once /rm_driver/set_gripper_position_cmd rm_ros_interfaces/msg/Gripperset "position: 500
block: true
timeout: 1000" |
+| 返回值 | 成功返回:true;失败返回:false,driver终端返回错误码。 |
+| 返回查询示例 | ros2 topic echo /rm_driver/set_gripper_position_result |
+### 拖动示教及轨迹复现
+#### 设置力位混合控制
+| 功能描述 | 设置力位混合控制 |
+| :---: | :---- |
+| 参数说明 | Setforceposition.msg
uint8 sensor: 0-一维力;1-六维力
uint8 mode: 0-基坐标系力控;1-工具坐标系力控
uint8 direction: 力控方向;0-沿X轴;1-沿Y轴;2-沿Z轴;3-沿RX姿态方向;4-沿RY姿态方向;5-沿RZ姿态方向
int16 n: 力的大小,单位N,精确到0.1N |
+| 命令示例 | ros2 topic pub --once /rm_driver/set_force_postion_cmd rm_ros_interfaces/msg/Setforceposition "sensor: 1
mode: 0
direction: 2
n: 3" |
+| 返回值 | 成功返回:true;失败返回:false,driver终端返回错误码。 |
+| 返回查询示例 | ros2 topic echo /rm_driver/set_force_postion_result |
+#### 结束力位混合控制
+| 功能描述 | 结束力位混合控制 |
+| :---: | :---- |
+| 参数说明 | std_msgs::msg::Empty |
+| 命令示例 | ros2 topic pub /rm_driver/stop_force_postion_cmd std_msgs/msg/Empty "{}" |
+| 返回值 | 成功返回:true;失败返回:false,driver终端返回错误码。 |
+| 返回查询示例 | ros2 topic echo /rm_driver/stop_force_postion_result |
+
+
+### 末端六维力传感器的使用
+睿尔曼RM-65F机械臂末端配备集成式六维力传感器,无需外部走线,用户可直接通过ROS话题对六维力进行操作。
+#### 查询六维力数据
+| 功能描述 | 查询六维力数据 |
+| :---: | :---- |
+| 参数说明 | std_msgs::msg::Empty |
+| 命令示例 | ros2 topic pub rm_driver/get_force_data_cmd std_msgs/msg/Empty "{}" |
+| 返回值 | 成功返回对应坐标系六维力数据。 |
+| 返回查询示例 | ros2 topic echo /rm_driver/get_force_data_result原始数据
ros2 topic echo /rm_driver/get_zero_force_data_result系统受力数据
ros2 topic echo /rm_driver/get_work_force_data_result工作坐标系受力数据
ros2 topic echo /rm_driver/get_tool_force_data_result工具坐标系受力数据 |
+#### 清空六维力数据
+| 功能描述 | 清空六维力数据 |
+| :---: | :---- |
+| 参数说明 | std_msgs::msg::Empty |
+| 命令示例 | ros2 topic pub /rm_driver/clear_force_data_cmd std_msgs/msg/Empty "{}" |
+| 返回值 | 成功返回:true;失败返回:false,driver终端返回错误码。 |
+| 返回查询示例 | ros2 topic echo /rm_driver/clear_force_data_result |
+### 末端五指灵巧手控制
+睿尔曼RM-65机械臂末端配备了五指灵巧手,可通过ROS对灵巧手进行设置。
+#### 设置灵巧手手势序号
+| 功能描述 | 设置灵巧手手势序号 |
+| :---: | :---- |
+| 参数说明 | Handposture.msg
uint16 posture_num:预先保存在灵巧手内的手势序号,范围:1~40。
bool data:是否为阻塞模式,true:阻塞,false:非阻塞。
uint16 timeout : timeout 阻塞模式下超时时间设置,单位:秒 |
+| 命令示例 | ros2 topic pub --once /rm_driver/set_hand_posture_cmd rm_ros_interfaces/msg/Handposture "posture_num: 1
block: true
timeout: 1000" |
+| 返回值 | 成功返回:true;失败返回:false,driver终端返回错误码。 |
+| 返回查询示例 | ros2 topic echo /rm_driver/set_hand_posture_result |
+#### 设置灵巧手动作序列
+| 功能描述 | 设置灵巧手动作序列 |
+| :---: | :---- |
+| 参数说明 | Handseq.msg
uint16 seq_num:预先保存在灵巧手内的序列序号,范围:1~40。
bool data:是否为阻塞模式,true:阻塞,false:非阻塞。
uint16 timeout : timeout 阻塞模式下超时时间设置,单位:秒 |
+| 命令示例 | ros2 topic pub --once /rm_driver/set_hand_seq_cmd rm_ros_interfaces/msg/Handseq "seq_num: 1
block: true
timeout: 1000" |
+| 返回值 | 成功返回:true;失败返回:false,driver终端返回错误码。 |
+| 返回查询示例 | ros2 topic echo /rm_driver/set_hand_seq_result |
+#### 设置灵巧手各自由度角度
+| 功能描述 | 设置灵巧手各自由度角度 |
+| :---: | :---- |
+| 参数说明 | Handangle.msg
int16[6] hand_angle:手指角度数组,范围:0~1000.另外,-1 代表该自由度不执行任何操作,保持当前状态。
bool data:是否为阻塞模式,true:阻塞,false:非阻塞。 |
+| 命令示例 | 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" |
+| 返回值 | 成功返回:true;失败返回:false,driver终端返回错误码。 |
+| 返回查询示例 | ros2 topic echo /rm_driver/set_hand_angle_result |
+#### 设置灵巧手速度
+| 功能描述 | 设置灵巧手速度 |
+| :---: | :---- |
+| 参数说明 | Handspeed.msg
uint16 hand_speed:手指速度,范围:1~1000。 |
+| 命令示例 | ros2 topic pub --once /rm_driver/set_hand_speed_cmd rm_ros_interfaces/msg/Handspeed "hand_speed: 200" |
+| 返回值 | 成功返回:true;失败返回:false,driver终端返回错误码。 |
+| 返回查询示例 | ros2 topic echo /rm_driver/set_hand_speed_result |
+#### 设置灵巧手力阈值
+| 功能描述 | 设置灵巧手力阈值 |
+| :---: | :---- |
+| 参数说明 | Handforce.msg
uint16 hand_force:手指力,范围:1~1000。 |
+| 命令示例 | ros2 topic pub --once /rm_driver/set_hand_force_cmd rm_ros_interfaces/msg/Handforce "hand_force: 200" |
+| 返回值 | 成功返回:true;失败返回:false,driver终端返回错误码。 |
+| 返回查询示例 | ros2 topic echo /rm_driver/set_hand_force_result |
+#### 设置灵巧手角度跟随
+| 功能描述 | 设置灵巧手角度跟随 |
+| :---: | :---- |
+| 参数说明 | Handangle.msg
int16[6] hand_angle:手指角度数组,范围(根据实际设备属性,以下为因时参考):0~2000.另外,-1 代表该自由度不执行任何操作,保持当前状态。
bool data:是否为阻塞模式,true:阻塞,false:非阻塞。 |
+| 命令示例 | ros2 topic pub --once /rm_driver/set_hand_follow_angle_cmd rm_ros_interfaces/msg/Handangle "hand_angle:
- 0
- 0
- 0
- 0
- 0
- 0
block: true" |
+| 返回值 | 成功返回:true;失败返回:false,driver终端返回错误码。 |
+| 返回查询示例 | ros2 topic echo /rm_driver/set_hand_follow_angle_result |
+#### 设置灵巧手姿态跟随
+| 功能描述 | 设置灵巧手姿态跟随 |
+| :---: | :---- |
+| 参数说明 | Handangle.msg
int16[6] hand_angle:手指姿态数组,范围(根据实际设备属性,以下为因时参考):0~1000.另外,-1 代表该自由度不执行任何操作,保持当前状态。
bool data:是否为阻塞模式,true:阻塞,false:非阻塞。 |
+| 命令示例 | ros2 topic pub --once /rm_driver/set_hand_follow_pos_cmd rm_ros_interfaces/msg/Handangle "hand_angle:
- 0
- 0
- 0
- 0
- 0
- 0
block: true" |
+| 返回值 | 成功返回:true;失败返回:false,driver终端返回错误码。 |
+| 返回查询示例 | ros2 topic echo /rm_driver/set_hand_follow_pos_result |
+### 升降机构
+睿尔曼机械臂可集成自主研发升降机构。
+#### 升降机构速度开环控制
+| 功能描述 | 升降机构速度开环控制 |
+| :---: | :---- |
+| 参数说明 | Liftspeed.msg
int16 speed:速度百分比,-100~100,Speed < 0:升降机构向下运动,Speed > 0:升降机构向上运动,Speed = 0:升降机构停止运动。
bool data:是否为阻塞模式,true:阻塞,false:非阻塞。 |
+| 命令示例 | ros2 topic pub /rm_driver/set_lift_speed_cmd rm_ros_interfaces/msg/Liftspeed "speed: 100" |
+| 返回值 | 成功返回:true;失败返回:false,driver终端返回错误码。 |
+| 返回查询示例 | ros2 topic echo /rm_driver/set_lift_speed_result |
+#### 升降机构位置闭环控制
+| 功能描述 | 升降机构位置闭环控制 |
+| :---: | :---- |
+| 参数说明 | Liftheight.msg
uint16 height:目标高度,单位 mm,范围:0-2600。
uint16 speed:速度百分比,1-100。
bool data:是否为阻塞模式,true:阻塞,false:非阻塞。 |
+| 命令示例 | ros2 topic pub --once /rm_driver/set_lift_height_cmd rm_ros_interfaces/msg/Liftheight "height: 0
speed: 10
block: true" |
+| 返回值 | 成功返回:true;失败返回:false,driver终端返回错误码。 |
+| 返回查询示例 | ros2 topic echo rm_driver/set_lift_height_result |
+#### 获取升降机构状态
+| 功能描述 | 获取升降机构状态 |
+| :---: | :---- |
+| 参数说明 | Liftstate.msg
int16 height:当前高度。
int16 current:当前电流。
uint16 err_flag:驱动错误代码。 |
+| 命令示例 | ros2 topic pub /rm_driver/get_lift_state_cmd std_msgs/msg/Empty "{}" |
+| 返回值 | 成功返回:升降机构当前状态;失败返回:driver终端返回错误码。 |
+| 返回查询示例 | ros2 topic echo /rm_driver/get_lift_state_result |
+### 末端生态协议
+末端生态协议支持下的末端设备基础信息与实时信息的读取。
+#### 设置末端生态协议模式
+| 功能描述 | 设置末端生态协议模式 |
+| :---: | :---- |
+| 参数说明 | std_msgs::msg::Int32
0-禁用协议;
9600-开启协议(波特率9600);
115200-开启协议(波特率115200);
256000-开启协议(波特率256000);
460800-开启协议(波特率460800)。|
+| 命令示例 | ros2 topic pub /rm_driver/set_rm_plus_mode_cmd std_msgs/msg/Int32 "data: 0" |
+| 返回值 | 成功返回:true;失败返回:false,driver终端返回错误码。 |
+| 返回查询示例 | ros2 topic echo /rm_driver/set_rm_plus_mode_result |
+#### 查询末端生态协议模式
+| 功能描述 | 查询末端生态协议模式 |
+| :---: | :---- |
+| 参数说明 | std_msgs::msg::Empty |
+| 命令示例 | ros2 topic pub /rm_driver/get_rm_plus_mode_cmd std_msgs/msg/Empty "{}" |
+| 返回值 | 0-禁用协议;
9600-开启协议(波特率9600);
115200-开启协议(波特率115200);
256000-开启协议(波特率256000);
460800-开启协议(波特率460800)。 |
+| 返回查询示例 | ros2 topic echo /rm_driver/get_rm_plus_mode_result |
+#### 设置触觉传感器模式
+| 功能描述 | 设置触觉传感器模式 |
+| :---: | :---- |
+| 参数说明 | std_msgs::msg::Int32
0-关闭触觉传感器;
1-打开触觉传感器(返回处理后数据);
2-打开触觉传感器(返回原始数据)。 |
+| 命令示例 | ros2 topic pub /rm_driver/set_rm_plus_touch_cmd std_msgs::msg::Int32 "data: 0" |
+| 返回值 | 成功无返回;失败返回:false,driver终端返回错误码。 |
+| 返回查询示例 | ros2 topic echo /rm_driver/set_rm_plus_touch_result |
+#### 获取触觉传感器模式
+| 功能描述 | 获取触觉传感器模式 |
+| :---: | :---- |
+| 参数说明 | std_msgs::msg::Empty |
+| 命令示例 | ros2 topic pub /rm_driver/get_rm_plus_touch_cmd std_msgs::msg::Empty "{}" |
+| 返回值 | std_msgs::msg::Int32
0-关闭触觉传感器;
1-打开触觉传感器(返回处理后数据);
2-打开触觉传感器(返回原始数据)。 |
+| 返回查询示例 | ros2 topic echo /rm_driver/get_rm_plus_touch_result |
+### 透传力位混合控制补偿
+针对睿尔曼带一维力和六维力版本的机械臂,用户除了可直接使用示教器调用底层的力位混合控制模块外,还可以将自定义的轨迹以周期性透传的形式结合底层的力位混合控制算法进行补偿。
+在进行力的操作之前,如果未进行力数据标定,可使用清空一维力、六维力数据接口对零位进行标定。
+#### 开启透传力位混合控制补偿模式
+| 功能描述 | 开启透传力位混合控制补偿模式 |
+| :---: | :---- |
+| 参数说明 | std_msgs::msg::Empty |
+| 命令示例 | ros2 topic pub /rm_driver/start_force_position_move_cmd std_msgs/msg/Empty "{}" |
+| 返回值 | 成功返回:true;失败返回:false,driver终端返回错误码。 |
+| 返回查询示例 | ros2 topic echo /rm_driver/start_force_position_move_result |
+#### 关闭透传力位混合控制补偿模式
+| 功能描述 | 关闭透传力位混合控制补偿模式 |
+| :---: | :---- |
+| 参数说明 | std_msgs::msg::Empty |
+| 命令示例 | ros2 topic pub /rm_driver/stop_force_position_move_cmd std_msgs/msg/Empty "{}" |
+| 返回值 | 成功返回:true;失败返回:false,driver终端返回错误码。 |
+| 返回查询示例 | ros2 topic echo /rm_driver/stop_force_position_move_result |
+#### 透传力位混合补偿-关节
+| 功能描述 | 透传力位混合补偿(关节) |
+| :---: | :---- |
+| 参数说明 | Forcepositionmovejoint.msg
float32[6] joint:目标关节弧度
uint8 sensor:所使用传感器类型,0-一维力,1-六维力
uint8 mode:模式,0-沿基坐标系,1-沿工具端坐标系
int16 dir:力控方向,0~5分别代表X/Y/Z/Rx/Ry/Rz,其中一维力类型时默认方向为Z方向
float32 force:力的大小 单位0.1N
bool follow:是否高跟随,true:高跟随,false:低跟随。
uint8 dof:机械臂自由度 |
+| 命令示例 | 需要是大量(10个以上)位置连续的点,以2ms以上的周期持续发布。
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 |
+| 返回值 | 成功无返回;失败返回:false,driver终端返回错误码。 |
+#### 透传力位混合补偿-位姿
+| 功能描述 | 透传力位混合补偿(位姿) |
+| :---: | :---- |
+| 参数说明 | Forcepositionmovepose.msg
geometry_msgs/Pose pose:目标位姿,x、y、z坐标(float类型,单位:m)+四元数。
uint8 sensor:所使用传感器类型,0-一维力,1-六维力
uint8 mode:模式,0-沿基坐标系,1-沿工具端坐标系
int16 dir:力控方向,0~5分别代表X/Y/Z/Rx/Ry/Rz,其中一维力类型时默认方向为Z方向
float32 force:力的大小 单位0.1N
bool follow:是否高跟随,true:高跟随,false:低跟随。 |
+| 命令示例 | 需要是大量(10个以上)位置连续 的点,以2ms以上的周期持续发布。
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" |
+| 返回值 | 成功无返回;失败返回:false,driver终端返回错误码。
+### 机械臂状态主动上报
+#### 设置UDP机械臂状态主动上报配置
+| 功能描述 | 设置UDP 机械臂状态主动上报配置 |
+| :---: | :---- |
+| 参数说明 | Setrealtimepush.msg
uint16 cycle:设置广播周期,为5ms的倍数(默认1即1*5=5ms,200Hz)。
uint16 port:设置广播的端口号(默认8089)。
uint16 force_coordinate:设置系统外受力数据的坐标系(仅带有力传感器的机械臂支持)。
string ip:设置自定义的上报目标IP 地址(默认192.168.1.10)
bool hand_enable:是否使能灵巧手状态上报,true使能,false不使能。
aloha_state_enable: 是否使能aloha主臂状态上报,true使能,false不使能。
arm_current_status_enable: 是否使能机械臂状态上报,true使能,false不使能。
expand_state_enable: 是否使能扩展关节相关数据上报,true使能,false不使能。
joint_speed_enable: 是否使能关节速度上报,true使能,false不使能。
lift_state_enable: 是否使能升降关节数据上报,true使能,false不使能。
plus_base_enable: 末端设备基础信息上报,true使能,false不使能。
plus_state_enable: 末端设备实时信息上报,true使能,false不使能。 |
+| 命令示例 | ros2 topic pub --once /rm_driver/set_realtime_push_cmd rm_ros_interfaces/msg/Setrealtimepush "cycle: 1
port: 8089
force_coordinate: 0
ip: '192.168.1.10'
hand_enable: false
aloha_state_enable: false
arm_current_status_enable: false
expand_state_enable: false
joint_speed_enable: false
lift_state_enable: false
plus_base_enable: false
plus_state_enable: false" |
+| 返回值 | 成功返回:true;失败返回:false,driver终端返回错误码。 |
+| 返回查询示例 | ros2 topic echo /rm_driver/set_realtime_push_result |
+#### 查询UDP机械臂状态主动上报配置
+| 功能描述 | 查询UDP 机械臂状态主动上报配置 |
+| :---: | :---- |
+| 参数说明 | Setrealtimepush.msg
uint16 cycle:设置广播周期,为5ms的倍数(默认1即1*5=5ms,200Hz)。
uint16 port:设置广播的端口号(默认8089)。
uint16 force_coordinate:设置系统外受力数据的坐标系(仅带有力传感器的机械臂支持)。
string ip:设置自定义的上报目标IP 地址(默认192.168.1.10)
bool hand_enable:是否使能灵巧手状态上报,true使能,false不使能。
aloha_state_enable: 是否使能aloha主臂状态上报,true使能,false不使能。
arm_current_status_enable: 是否使能机械臂状态上报,true使能,false不使能。
expand_state_enable: 是否使能扩展关节相关数据上报,true使能,false不使能。
joint_speed_enable: 是否使能关节速度上报,true使能,false不使能。
lift_state_enable: 是否使能升降关节数据上报,true使能,false不使能。
plus_base_enable: 末端设备基础信息上报,true使能,false不使能。
plus_state_enable: 末端设备实时信息上报,true使能,false不使能。 |
+| 命令示例 | ros2 topic pub --once /rm_driver/get_realtime_push_cmd std_msgs/msg/Empty "{}" |
+| 返回值 | 成功设置信息;失败返回:driver终端返回错误码。 |
+| 返回查询示例 | ros2 topic echo /rm_driver/get_realtime_push_result |
+#### UDP机械臂状态主动上报
+
+* 六维力
+
+| 功能描述 | 六维力 |
+| :---: | :---- |
+| 参数说明 | Sixforce.msg
float32 force_fx:沿x轴方向受力大小。
float32 force_fy:沿y轴方向受力大小。
float32 force_fz:沿z轴方向受力大小。
float32 force_mx:沿x轴方向转动受力大小。
float32 force_my:沿y轴方向转动受力大小。
float32 force_mz:沿z轴方向转动受力大小。 |
+| 查询示例 | ros2 topic echo /rm_driver/udp_six_force |
+
+* 一维力
+
+| 功能描述 | 一维力 |
+| :---: | :---- |
+| 参数说明 | Sixforce.msg
float32 force_fx:沿x轴方向受力大小。
float32 force_fy:沿y轴方向受力大小。
float32 force_fz:沿z轴方向受力大小。(仅该数值有效)
float32 force_mx:沿x轴方向转动受力大小。
float32 force_my:沿y轴方向转动受力大小。
float32 force_mz:沿z轴方向转动受力大小。 |
+| 查询示例 | ros2 topic echo /rm_driver/udp_one_force |
+
+* 机械臂错误
+
+| 功能描述 | 机械臂错误 |
+| :---: | :---- |
+| 参数说明 | std_msgs::msg::UInt16
uint16 data:机械臂报错信息。 |
+| 查询示例 | ros2 topic echo /rm_driver/udp_arm_err |
+
+* 系统错误
+
+| 功能描述 | 系统错误 |
+| :---: | :---- |
+| 参数说明 | std_msgs::msg::UInt16
uint16 data:系统报错信息。 |
+| 查询示例 | ros2 topic echo /rm_driver/udp_sys_err |
+
+* 关节错误
+
+| 功能描述 | 关节错误 |
+| :---: | :---- |
+| 参数说明 | Jointerrorcode.msg
uint16[] joint_error:每个关节报错信息。
Uint8 dof:机械臂自由度信息。 |
+| 查询示例 | ros2 topic echo /rm_driver/udp_joint_error_code |
+
+* 机械臂弧度数据
+
+| 功能描述 | 机械臂弧度数据 |
+| :---: | :---- |
+| 参数说明 | sensor_msgs::msg::JointState
builtin_interfaces/Time stamp
int32 sec:时间信息,秒。
uint32 nanosec:时间信息,纳秒。
string frame_id:坐标系名称。
string[] name:关节名称。
float64[] position:关节弧度信息。
float64[] velocity:关节速度信息。(暂未使用)
float64[] effort:关节受力信息。(暂未使用) |
+| 查询示例 | ros2 topic echo /joint_states |
+
+* 位姿信息
+
+| 功能描述 | 位姿信息 |
+| :---: | :---- |
+| 参数说明 | geometry_msgs::msg::Pose
Point position:机械臂当前坐标信息。
float64 x
float64 y
float64 z
Quaternion orientation:机械臂当前姿态信息。
float64 x 0
float64 y 0
float64 z 0
float64 w 1 |
+| 查询示例 | ros2 topic echo /rm_driver/udp_arm_position |
+
+* 当前六维力传感器系统外受力数据
+
+| 功能描述 | 当前六维力传感器系统外受力数据 |
+| :---: | :---- |
+| 参数说明 | Sixforce.msg
float32 force_fx:当前传感器沿x轴方向受外力大小。
float32 force_fy:当前传感器沿y轴方向受外力大小。
float32 force_fz:当前传感器沿z轴方向受外力大小。
float32 force_mx:当前传感器沿x轴方向转动受外力大小。
float32 force_my:当前传感器沿y轴方向转动受外力大小。
float32 force_mz:当前传感器沿z轴方向转动受外力大小。 |
+| 查询示例 | ros2 topic echo /rm_driver/udp_six_zero_force |
+
+* 当前一维力传感器系统外受力数据
+
+| 功能描述 | 当前一维力传感器系统外受力数据 |
+| :---: | :---- |
+| 参数说明 | Sixforce.msg
float32 force_fx:当前传感器沿x轴方向受外力大小。
float32 force_fy:当前传感器沿y轴方向受外力大小。
float32 force_fz:当前传感器沿z轴方向受外力大小。(仅该数据有效)
float32 force_mx:当前传感器沿x轴方向转动受外力大小。
float32 force_my:当前传感器沿y轴方向转动受外力大小。
float32 force_mz:当前传感器沿z轴方向转动受外力大小。 |
+| 查询示例 | ros2 topic echo /rm_driver/udp_one_zero_force |
+
+* 系统外受力数据参考坐标系
+
+| 功能描述 | 系统外受力数据参考坐标系 |
+| :----: | :---- |
+| 参数说明 | std_msgs::msg::UInt16
uint16 data:系统外受力数据的坐标系,0 为传感器坐标系 1 为当前工作坐标系 2 为当前工具坐标系。该数据会影响一维力和六维力传感器系统外受力数据的参考坐标系 |
+| 查询示例 | ros2 topic echo /rm_driver/udp_arm_coordinate |
+
+* 灵巧手力当前状态
+
+| 功能描述 | 获取灵巧手力当前状态 |
+| :----: | :---- |
+| 参数说明 | rm_ros_interfaces::msg::Handstatus.msg
uint16[6] hand_angle:#手指角度数组,范围:0~2000.
uint16[6] hand_pos:#手指位置数组,范围:0~1000.
uint16[6] hand_state:#手指状态,0正在松开,1正在抓取,2位置到位停止,3力到位停止,5电流保护停止,6电缸堵转停止,7电缸故障停止.
uint16[6] hand_force:#灵巧手自由度电流,单位mN.
uint16 hand_err:#灵巧手系统错误,1表示有错误,0表示无错误. |
+| 查询示例 | ros2 topic echo /rm_driver/udp_hand_status |
+* 机械臂当前状态
+
+| 功能描述 | 获取机械臂当前状态 |
+| :----: | :---- |
+| 参数说明 | rm_ros_interfaces::msg::Armcurrentstatus.msg
uint16 arm_current_status:机械臂状态
0 - RM_IDLE_E // 使能但空闲状态
1 - RM_MOVE_L_E // move L运动中状态
2 - RM_MOVE_J_E // move J运动中状态
3 - RM_MOVE_C_E // move C运动中状态
4 - RM_MOVE_S_E // move S运动中状态
5 - RM_MOVE_THROUGH_JOINT_E // 角度透传状态
6 - RM_MOVE_THROUGH_POSE_E // 位姿透传状态
7 - RM_MOVE_THROUGH_FORCE_POSE_E // 力控透传状态
8 - RM_MOVE_THROUGH_CURRENT_E // 电流环透传状态
9 - RM_STOP_E // 急停状态
10 - RM_SLOW_STOP_E // 缓停状态
11 - RM_PAUSE_E // 暂停状态
12 - RM_CURRENT_DRAG_E // 电流环拖动状态
13 - RM_SENSOR_DRAG_E // 六维力拖动状态
14 - RM_TECH_DEMONSTRATION_E // 示教状态 |
+| 查询示例 | ros2 topic echo /rm_driver/udp_arm_current_status |
+
+* 当前关节电流
+
+| 功能描述 | 当前关节电流 |
+| :----: | :---- |
+| 参数说明 | rm_ros_interfaces::msg::Jointcurrent.msg
float32[] joint_current: 当前关节电流,精度 0.001mA |
+| 查询示例 | ros2 topic echo /rm_driver/udp_joint_current |
+
+* 当前关节使能状态
+
+| 功能描述 | 当前关节使能状态 |
+| :----: | :---- |
+| 参数说明 | rm_ros_interfaces::msg::Jointenflag.msg
bool[] joint_en_flag: 当前关节使能状态 ,1 为上使能,0 为掉使能|
+| 查询示例 | ros2 topic echo /rm_driver/udp_joint_en_flag |
+
+* 机械臂欧拉角位姿
+
+| 功能描述 | 机械臂欧拉角位姿 |
+| :----: | :---- |
+| 参数说明 | rm_ros_interfaces::msg::Jointposeeuler.msg
float32[3] euler: 当前路点姿态欧拉角,精度 0.001rad
float32[3] position:当前路点位置,精度 0.000001M|
+| 查询示例 | ros2 topic echo /rm_driver/udp_joint_pose_euler |
+
+* 当前关节速度
+
+| 功能描述 | 当前关节速度 |
+| :----: | :---- |
+| 参数说明 | rm_ros_interfaces::msg::Jointspeed.msg
float32[] joint_speed: 当前关节速度,精度0.02RPM。|
+| 查询示例 | ros2 topic echo /rm_driver/udp_joint_speed |
+
+* 当前关节温度
+
+| 功能描述 | 当前关节温度 |
+| :----: | :---- |
+| 参数说明 | rm_ros_interfaces::msg::Jointtemperature.msg
float32[] joint_temperature: 当前关节温度,精度 0.001℃|
+| 查询示例 | ros2 topic echo /rm_driver/udp_joint_temperature |
+* 当前关节电压
+
+| 功能描述 | 当前关节电压 |
+| :----: | :---- |
+| 参数说明 | rm_ros_interfaces::msg::Jointvoltage.msg
float32[] joint_voltage: 当前关节电压,精度 0.001V|
+| 查询示例 | ros2 topic echo /rm_driver/udp_joint_voltage |
+* 末端设备基础信息
+
+| 功能描述 | 末端设备基础信息(末端生态协议支持) |
+| :----: | :---- |
+| 参数说明 | rm_ros_interfaces::msg::Rmplusbase.msg
string manu:# 设备厂家.
int8 type:设备类型 1:两指夹爪 2:五指灵巧手 3:三指夹爪
string hv:硬件版本
string sv:软件版本
string bv:boot版本
int32 id:设备ID
int8 dof:自由度
int8 check:自检开关
int8 bee:蜂鸣器开关
bool force:力控支持
bool touch:触觉支持
int8 touch_num:触觉个数
int8 touch_sw:触觉开关
int8 hand:手方向 1 :左手 2: 右手
int32[12] pos_up:位置上限,单位:无量纲
int32[12] pos_low:位置下限,单位:无量纲
int32[12] angle_up:角度上限,单位:0.01度
int32[12] angle_low:角度下限,单位:0.01度
int32[12] speed_up:速度上限,单位:无量纲
int32[12] speed_low:速度下限,单位:无量纲
int32[12] force_up:力上限,单位:0.001N
int32[12] force_low:力下限,单位:0.001N|
+| 查询示例 | ros2 topic echo /rm_driver/udp_rm_plus_base |
+* 末端设备实时信息
+
+| 功能描述 | 末端设备实时信息(末端生态协议支持) |
+| :----: | :---- |
+| 参数说明 | rm_ros_interfaces::msg::Rmplusstate.msg
int32 sys_state:系统状态.
int32[12] dof_state:各自由度当前状态
int32[12] dof_err:各自由度错误信息
int32[12] pos:各自由度当前位置
int32[12] speed:各自由度当前速度
int32[12] angle:各自由度当前角度,单位:0.01度
int32[12] current:各自由度当前电流,单位:mA
int32[18] normal_force:自由度触觉三维力的法向力
int32[18] tangential_force:自由度触觉三维力的切向力
int32[18] tangential_force_dir:自由度触觉三维力的切向力方向
uint32[12] tsa:自由度触觉自接近
uint32[12] tma:自由度触觉互接近
int32[18] touch_data:触觉传感器原始数据
int32[12] force:自由度力矩,单位0.001N|
+| 查询示例 | ros2 topic echo /rm_driver/udp_rm_plus_state |
diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_driver/include/rm_driver/rm_define.h b/HiveCoreR0/src/ros2_rm_robot-humble/rm_driver/include/rm_driver/rm_define.h
new file mode 100755
index 0000000..40ec038
--- /dev/null
+++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_driver/include/rm_driver/rm_define.h
@@ -0,0 +1,1032 @@
+#ifndef RM_DEFINE_H
+#define RM_DEFINE_H
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+#include
+#include
+#include
+
+#define ARM_DOF 7
+#define M_PI 3.14159265358979323846
+
+#define RM_MOVE_NBLOCK 0 ///<机械臂运动设置,非阻塞模式
+#define RM_MOVE_MULTI_BLOCK 1 ///<机械臂运动设置,多线程阻塞模式
+static inline int RM_MOVE_SINGLE_BLOCK(int timeout){return timeout;} ///<机械臂运动设置,单线程阻塞模式超时时间
+
+/**
+ * @brief 线程模式
+ * @ingroup Init_Class
+ */
+typedef enum {
+ RM_SINGLE_MODE_E, ///< 单线程模式,单线程非阻塞等待数据返回
+ RM_DUAL_MODE_E, ///< 双线程模式,增加接收线程监测队列中的数据
+ RM_TRIPLE_MODE_E, ///< 三线程模式,在双线程模式基础上增加线程监测UDP接口数据
+}rm_thread_mode_e;
+
+/**
+ * @brief 机械臂型号
+ * @ingroup Algo
+ */
+typedef enum{
+ RM_MODEL_RM_65_E, ///< RM_65
+ RM_MODEL_RM_75_E, ///< RM_75
+ RM_MODEL_RM_63_I_E, ///< RML_63I(已弃用)
+ RM_MODEL_RM_63_II_E, ///< RML_63II
+ RM_MODEL_RM_63_III_E, ///< RML_63III
+ RM_MODEL_ECO_65_E, ///< ECO_65
+ RM_MODEL_ECO_62_E, ///< ECO_62
+ RM_MODEL_GEN_72_E, ///< GEN_72
+ RM_MODEL_ECO_63_E, ///< ECO63
+ RM_MODEL_UNIVERSAL_E
+}rm_robot_arm_model_e;
+
+/**
+ * @brief 机械臂末端力传感器版本
+ * @ingroup Algo
+ */
+typedef enum{
+ RM_MODEL_RM_B_E, ///< 标准版
+ RM_MODEL_RM_ZF_E, ///< 一维力版
+ RM_MODEL_RM_SF_E, ///< 六维力版
+ RM_MODEL_RM_ISF_E, ///< 一体化六维力版
+}rm_force_type_e;
+
+/**
+ * @brief 事件类型
+ * @ingroup Init_Class
+ */
+typedef enum
+{
+ RM_NONE_EVENT_E, ///< 无事件
+ RM_CURRENT_TRAJECTORY_STATE_E, ///< 当前轨迹到位
+ RM_PROGRAM_RUN_FINISH_E, ///< 在线编程运行结束
+} rm_event_type_e;
+
+/**
+ * @brief 事件信息
+ * @ingroup Init_Class
+ */
+typedef struct
+{
+ int handle_id; ///< 返回消息的机械臂id
+ rm_event_type_e event_type; ///< 事件类型,包含无事件、当前轨迹到位、在线编程运行结束
+ bool trajectory_state; ///< 当前轨迹到位状态
+ int device; ///< 到位设备,0:关节 1:夹爪 2:灵巧手 3:升降机构 4:扩展关节 其他:保留
+ int trajectory_connect; ///< 是否连接下一条轨迹,0:全部到位,1:连接下一条轨迹
+ int program_id; ///< 运行结束的在线编程程序id
+}rm_event_push_data_t;
+
+/**
+ * @brief 机械臂当前规划类型
+ *
+ */
+typedef enum
+{
+ RM_NO_PLANNING_E, ///< 无规划
+ RM_JOINT_SPACE_PLANNING_E, ///< 关节空间规划
+ RM_CARTESIAN_LINEAR_PLANNING_E, ///< 笛卡尔空间直线规划
+ RM_CARTESIAN_ARC_PLANNING_E, ///< 笛卡尔空间圆弧规划
+ RM_SPLINE_CURVE_MOTION_PLANNING_E, ///< 样条曲线运动规划
+ RM_TRAJECTORY_REPLAY_PLANNING_E, ///< 示教轨迹复现规划
+}rm_arm_current_trajectory_e;
+
+typedef struct
+{
+ int joint_speed; ///< 关节速度。
+ int lift_state; ///< 升降关节信息。1:上报;0:关闭上报;-1:不设置,保持之前的状态
+ int expand_state; ///< 扩展关节信息(升降关节和扩展关节为二选一,优先显示升降关节)1:上报;0:关闭上报;-1:不设置,保持之前的状态
+ int hand_state; ///< 灵巧手状态。1:上报;0:关闭上报;-1:不设置,保持之前的状态(1.7.0版本无这个)
+ int arm_current_status; ///< 机械臂当前状态。1:上报;0:关闭上报;-1:不设置,保持之前的状态
+ int aloha_state; ///< aloha主臂状态是否上报。1:上报;0:关闭上报;-1:不设置,保持之前的状态
+ int plus_base; ///< 末端设备基础信息。1:上报;0:关闭上报;-1:不设置,保持之前的状态
+ int plus_state; ///< 末端设备实时信息。1:上报;0:关闭上报;-1:不设置,保持之前的状态
+}rm_udp_custom_config_t;
+
+/**
+ * @brief 机械臂主动上报接口配置
+ * @ingroup UdpConfig
+ */
+typedef struct {
+ int cycle; ///< 广播周期,5ms的倍数
+ bool enable; ///< 使能,是否主动上报
+ int port; ///< 广播的端口号
+ int force_coordinate; ///< 系统外受力数据的坐标系,-1不支持力传感器 0为传感器坐标系 1为当前工作坐标系 2为当前工具坐标系
+ char ip[28]; ///< 自定义的上报目标IP地址
+ rm_udp_custom_config_t custom_config; ///< 自定义项内容
+} rm_realtime_push_config_t;
+
+/**
+ * @brief 四元数
+ *
+ */
+typedef struct
+{
+ float w;
+ float x;
+ float y;
+ float z;
+} rm_quat_t;
+
+/**
+ * @brief 位置坐标
+ *
+ */
+typedef struct
+{
+ float x; //* unit: m
+ float y;
+ float z;
+} rm_position_t;
+
+/**
+ * @brief 欧拉角
+ *
+ */
+typedef struct
+{
+ float rx; //* unit: rad
+ float ry;
+ float rz;
+} rm_euler_t;
+
+/**
+ * @brief 机械臂位置姿态结构体
+ * @ingroup Algo
+ */
+typedef struct
+{
+ rm_position_t position; ///< 位置,单位:m
+ rm_quat_t quaternion; ///< 四元数
+ rm_euler_t euler; ///< 欧拉角,单位:rad
+}rm_pose_t;
+
+/**
+ * @brief 坐标系名称
+ * 不超过10个字符
+ * @ingroup ToolCoordinateConfig
+ * @ingroup WorkCoordinateConfig
+ */
+typedef struct
+{
+ char name[12];
+}rm_frame_name_t;
+
+
+/**
+ * @brief 坐标系
+ * @ingroup Algo
+ * @ingroup ToolCoordinateConfig
+ * @ingroup WorkCoordinateConfig
+ */
+typedef struct
+{
+ char frame_name[12]; ///< 坐标系名称
+ rm_pose_t pose; ///< 坐标系位姿
+ float payload; ///< 坐标系末端负载重量,单位:kg
+ float x; ///< 坐标系末端负载质心位置,单位:m
+ float y; ///< 坐标系末端负载质心位置,单位:m
+ float z; ///< 坐标系末端负载质心位置,单位:m
+}rm_frame_t;
+
+typedef struct{
+ char build_time[20]; ///< 编译时间
+ char version[20]; ///< 版本号
+}rm_ctrl_version_t;
+
+typedef struct{
+ char model_version[5]; ///< 动力学模型版本号
+}rm_dynamic_version_t;
+
+typedef struct{
+ char build_time[20]; ///<编译时间
+ char version[20]; ///< 版本号
+}rm_planinfo_t;
+
+typedef struct {
+ char version[20]; ///< 算法库版本号
+}rm_algorithm_version_t;
+
+typedef struct {
+ char build_time[20]; ///<编译时间
+ char version[20]; ///< 版本号
+}rm_software_build_info_t;
+/**
+ * @brief 机械臂软件信息
+ *
+ */
+typedef struct
+{
+ char product_version[20]; ///< 机械臂型号
+ char robot_controller_version[10]; ///< 机械臂控制器版本,若为四代控制器,则该字段为"4.0"
+ rm_algorithm_version_t algorithm_info; ///< 算法库信息
+ rm_software_build_info_t ctrl_info; ///< ctrl 层软件信息
+ rm_dynamic_version_t dynamic_info; ///< 动力学版本(三代)
+ rm_software_build_info_t plan_info; ///< plan 层软件信息(三代)
+ rm_software_build_info_t com_info; ///< communication 模块软件信息(四代)
+ rm_software_build_info_t program_info; ///< 流程图编程模块软件信息(四代)
+}rm_arm_software_version_t;
+
+/**
+ * @brief 错误代码结构体
+ *
+*/
+typedef struct
+{
+ uint8_t err_len; ///< 错误代码个数
+ int err[24]; ///< 错误代码数组
+}rm_err_t;
+
+/**
+ * @brief 机械臂当前状态
+ *
+*/
+typedef struct
+{
+ rm_pose_t pose; ///< 机械臂当前位姿
+ float joint[ARM_DOF]; ///< 机械臂当前关节角度
+ rm_err_t err;
+}rm_current_arm_state_t;
+
+/**
+ * @brief 机械臂关节状态参数
+ *
+*/
+typedef struct
+{
+ float joint_current[ARM_DOF]; ///< 关节电流,单位mA,精度:0.001mA
+ bool joint_en_flag[ARM_DOF]; ///< 当前关节使能状态 ,1为上使能,0为掉使能
+ uint16_t joint_err_code[ARM_DOF]; ///< 当前关节错误码
+ float joint_position[ARM_DOF]; ///< 关节角度,单位°,精度:0.001°
+ float joint_temperature[ARM_DOF]; ///< 当前关节温度,精度0.001℃
+ float joint_voltage[ARM_DOF]; ///< 当前关节电压,精度0.001V
+ float joint_speed[ARM_DOF]; ///< 当前关节速度,精度0.01RPM。
+}rm_joint_status_t;
+
+/**
+ * @brief 位置示教方向
+ *
+ */
+typedef enum
+{
+ RM_X_DIR_E, ///< 位置示教,x轴方向
+ RM_Y_DIR_E, ///< 位置示教,y轴方向
+ RM_Z_DIR_E, ///< 位置示教,z轴方向
+}rm_pos_teach_type_e;
+
+/**
+ * @brief 姿态示教方向
+ *
+ */
+typedef enum
+{
+ RM_RX_ROTATE_E, ///< 姿态示教,绕x轴旋转
+ RM_RY_ROTATE_E, ///< 姿态示教,绕y轴旋转
+ RM_RZ_ROTATE_E, ///< 姿态示教,绕z轴旋转
+}rm_ort_teach_type_e;
+
+/**
+ * @brief 数字IO配置结构体
+ * io_mode:模式,0-通用输入模式、1-通用输出模式、2-输入开始功能复用模式、3-输入暂停功能复用模式、
+ * 4-输入继续功能复用模式、5-输入急停功能复用模式、6-输入进入电流环拖动复用模式
+ * 7-输入进入力只动位置拖动模式(六维力版本可配置)、8-输入进入力只动姿态拖动模式(六维力版本可配置)
+ * 9-输入进入力位姿结合拖动复用模式(六维力版本可配置)、10-输入外部轴最大软限位复用模式(外部轴模式可配置)
+ * 11-输入外部轴最小软限位复用模式(外部轴模式可配置)、12-输入初始位姿功能复用模式
+ * 13-输出碰撞功能复用模式、14-实时调速功能复用模式
+ * io_state:数字io状态(0低 1高)(该成员在set时无效)
+ * io_real_time_config_t:实时调速功能,io配置
+ * speed:速度取值范围0-100 (当io_mode不为14时,默认值为-1)
+ * mode :模式取值范围1或2 (当io_mode不为14时,默认值为-1)
+ * 1表示单次触发模式,单次触发模式下当IO拉低速度设置为speed参数值,IO恢复高电平速度设置为初始值
+ * 2表示连续触发模式,连续触发模式下IO拉低速度设置为speed参数值,IO恢复高电平速度维持当前值
+ */
+typedef struct
+{
+ int io_mode; // io_mode:模式0~14
+ struct
+ {
+ int speed; // speed:速度取值范围0-100
+ int mode; // mode :模式取值范围1或2
+ }io_real_time_config_t;
+}rm_io_config_t;
+
+/**
+ * @brief 数字IO状态获取结构体
+ * io_state:数字io状态(0低 1高)(该成员在set时无效)
+ * io_config:io配置结构体
+ */
+typedef struct
+{
+ int io_state; // io_state:数字io状态(0低 1高)
+ rm_io_config_t io_config; // io_config:数字io配置结构体
+}rm_io_get_t;
+
+/**
+ * @brief 复合模式拖动示教参数
+ *
+ */
+typedef struct{
+ int free_axes[6]; ///< 自由驱动方向[x,y,z,rx,ry,rz],0-在参考坐标系对应方向轴上不可拖动,1-在参考坐标系对应方向轴上可拖动
+ int frame; ///< 参考坐标系,0-工作坐标系 1-工具坐标系。
+ int singular_wall; ///< 仅在六维力模式拖动示教中生效,用于指定是否开启拖动奇异墙,0表示关闭拖动奇异墙,1表示开启拖动奇异墙,若无配置参数,默认启动拖动奇异墙
+}rm_multi_drag_teach_t;
+
+/**
+ * @brief 力位混合控制传感器枚举
+ *
+ */
+typedef enum{
+ RM_FP_OF_SENSOR_E = 0, ///<一维力
+ RM_FP_SF_SENSOR_E, ///<六维力
+}rm_force_position_sensor_e;
+
+/**
+ * @brief 力位混合控制模式枚举
+ *
+ */
+typedef enum{
+ RM_FP_BASE_COORDINATE_E = 0, ///<基坐标系力控
+ RM_FP_TOOL_COORDINATE_E, ///<工具坐标系力控
+}rm_force_position_mode_e;
+
+/**
+ * @brief 力位混合控制模式(单方向)力控方向枚举
+ *
+ */
+typedef enum{
+ RM_FP_X_E = 0, ///<沿X轴
+ RM_FP_Y_E, ///<沿Y轴
+ RM_FP_Z_E, ///<沿Z轴
+ RM_FP_RX_E, ///<沿RX姿态方向
+ RM_FP_RY_E, ///<沿RY姿态方向
+ RM_FP_RZ_E, ///<沿RZ姿态方向
+}rm_force_position_dir_e;
+
+/**
+ * @brief 力位混合控制参数
+ *
+ */
+typedef struct
+{
+ int sensor; ///< 传感器,0-一维力;1-六维力
+ int mode; ///< 0-基坐标系力控;1-工具坐标系力控;
+ int control_mode[6]; ///< 6个力控方向(Fx Fy Fz Mx My Mz)的模式 0-固定模式 1-浮动模式 2-弹簧模式 3-运动模 4-力跟踪模式 8-力跟踪+姿态自适应模式
+ float desired_force[6]; ///< 力控轴维持的期望力/力矩,力控轴的力控模式为力跟踪模式时,期望力/力矩设置才会生效 ,精度0.1N。
+ float limit_vel[6]; ///< 力控轴的最大线速度和最大角速度限制,只对开启力控方向生效。
+}rm_force_position_t;
+
+/**
+ * @brief 透传力位混合补偿参数
+ * 建议初始化方式,避免一些未知错误
+ * rm_force_position_move_t my_fp_move = (rm_force_position_move_t){ 0 };
+ */
+typedef struct
+{
+ int flag; ///< 0-下发目标角度,1-下发目标位姿
+ rm_pose_t pose; ///< 当前坐标系下的目标位姿,支持四元数/欧拉角表示姿态。位置精度:0.001mm,欧拉角表示姿态,姿态精度:0.001rad,四元数方式表示姿态,姿态精度:0.000001
+ float joint[ARM_DOF]; ///< 目标关节角度,单位:°,精度:0.001°
+ int sensor; ///< 传感器,0-一维力;1-六维力
+ int mode; ///< 0-基坐标系力控;1-工具坐标系力控;
+ bool follow; ///< 表示驱动器的运动跟随效果,true 为高跟随,false 为低跟随。
+ int control_mode[6]; ///< 6个力控方向的模式 0-固定模式 1-浮动模式 2-弹簧模式 3-运动模式 4-力跟踪模式 5-浮动+运动模式 6-弹簧+运动模式 7-力跟踪+运动模式 8-姿态自适应模式
+ float desired_force[6]; ///< 力控轴维持的期望力/力矩,力控轴的力控模式为力跟踪模式时,期望力/力矩设置才会生效 ,精度0.1N。
+ float limit_vel[6]; ///< 力控轴的最大线速度和最大角速度限制,只对开启力控方向生效。
+ int trajectory_mode; ///< 高跟随模式下,0-完全透传模式、1-曲线拟合模式、2-滤波模式
+ int radio; ///< 曲线拟合模式0-100和滤波模式下的平滑系数(数值越大效果越好),滤波模式下取值范围0~1000,曲线拟合模式下取值范围0~100
+}rm_force_position_move_t;
+
+/**
+ * @brief 角度透传模式结构体
+ * 建议初始化方式,避免一些未知错误
+ * rm_movej_canfd_mode_t my_j_canfd = (rm_movej_canfd_mode_t){ 0 };
+ */
+typedef struct
+{
+ float* joint; // 关节角度(若为六轴机械臂,那么最后一个元素无效),单位°
+ float expand; // 扩展关节角度(若没有扩展关节,那么此成员值无效)
+ bool follow; // 跟随模式,0-低跟随,1-高跟随,若使用高跟随,透传周期要求不超过 10ms
+ int trajectory_mode; // 高跟随模式下,0-完全透传模式、1-曲线拟合模式、2-滤波模式
+ int radio; // 曲线拟合模式和滤波模式下的平滑系数(数值越大效果越好),滤波模式下取值范围0~1000,曲线拟合模式下取值范围0~100
+}rm_movej_canfd_mode_t;
+
+/**
+ * @brief 姿态透传模式结构体
+ * 建议初始化方式,避免一些未知错误
+ * rm_movep_canfd_mode_t my_p_canfd = (rm_movep_canfd_mode_t){ 0 };
+ */
+typedef struct
+{
+ rm_pose_t pose; // 位姿 (优先采用四元数表达)
+ bool follow; // 跟随模式,0-低跟随,1-高跟随,若使用高跟随,透传周期要求不超过 10ms
+ int trajectory_mode; // 高跟随模式下,0-完全透传模式、1-曲线拟合模式、2-滤波模式
+ int radio; // 曲线拟合模式和滤波模式下的平滑系数(数值越大效果越好),滤波模式下取值范围0~1000,曲线拟合模式下取值范围0~100
+}rm_movep_canfd_mode_t;
+
+/**
+ * @brief 无线网络信息结构体
+ *
+ */
+typedef struct{
+ int channel; ///< 如果是 AP 模式,则存在此字段,标识 wifi 热点的物理信道号
+ char ip[16]; ///< IP 地址
+ char mac[18]; ///< MAC 地址
+ char mask[16]; ///< 子网掩码
+ char mode[5]; ///< ap 代表热点模式,sta 代表联网模式,off 代表未开启无线模式
+ char password[16]; ///< 密码
+ char ssid[32]; ///< 网络名称 (SSID)
+}rm_wifi_net_t;
+
+/**
+ * @brief 机械臂所有状态参数
+ *
+*/
+typedef struct
+{
+ float joint_current[ARM_DOF]; ///< 关节电流,单位mA
+ int joint_en_flag[ARM_DOF]; ///< 关节使能状态
+ float joint_temperature[ARM_DOF]; ///< 关节温度,单位℃
+ float joint_voltage[ARM_DOF]; ///< 关节电压,单位V
+ int joint_err_code[ARM_DOF]; ///< 关节错误码
+ rm_err_t err; ///< 错误代码
+}rm_arm_all_state_t;
+
+/**
+ * @brief 夹爪状态
+ *
+ */
+typedef struct
+{
+ int enable_state; ///< 夹爪使能标志,0 表示未使能,1 表示使能
+ int status; ///< 夹爪在线状态,0 表示离线, 1表示在线
+ int error; ///< 夹爪错误信息,低8位表示夹爪内部的错误信息bit5-7 保留bit4 内部通bit3 驱动器bit2 过流 bit1 过温bit0 堵转
+ int mode; ///< 当前工作状态:1 夹爪张开到最大且空闲,2 夹爪闭合到最小且空闲,3 夹爪停止且空闲,4 夹爪正在闭合,5 夹爪正在张开,6 夹爪闭合过程中遇到力控停止
+ int current_force; ///< 夹爪当前的压力,单位g
+ int temperature; ///< 当前温度,单位℃
+ int actpos; ///< 夹爪开口度
+}rm_gripper_state_t;
+
+/**
+ * @brief 六维力传感器数据结构体
+ *
+*/
+typedef struct {
+ float force_data[6]; ///< 当前力传感器原始数据,力的单位为N;力矩单位为Nm。
+ float zero_force_data[6]; ///< 当前力传感器系统外受力数据,力的单位为N;力矩单位为Nm。
+ float work_zero_force_data[6]; ///< 当前工作坐标系下系统外受力原始数据,力的单位为N;力矩单位为Nm。
+ float tool_zero_force_data[6]; ///< 当前工具坐标系下系统外受力原始数据,力的单位为N;力矩单位为Nm。
+} rm_force_data_t;
+
+/**
+ * @brief 一维力传感器数据结构体
+ *
+*/
+typedef struct {
+ float Fz; ///< 原始数据
+ float zero_Fz; ///< 传感器坐标系下系统外受力数据,力的单位为N;力矩单位为Nm。
+ float work_zero_Fz; ///< 当前工作坐标系下系统外受力原始数据,力的单位为N;力矩单位为Nm。
+ float tool_zero_Fz; ///< 当前工具坐标系下系统外受力原始数据,力的单位为N;力矩单位为Nm。
+} rm_fz_data_t;
+
+/**
+ * @brief 外设数据读写参数结构体
+ *
+*/
+typedef struct {
+ int port; ///< 通讯端口,0-控制器RS485端口,1-末端接口板RS485接口,3-控制器ModbusTCP设备
+ int address; ///< 数据起始地址
+ int device; ///< 外设设备地址
+ int num; ///< 要读的数据的数量
+} rm_peripheral_read_write_params_t;
+
+/**
+ * @brief 升降机构、扩展关节状态结构体
+ *
+*/
+typedef struct {
+ int pos; ///< 扩展关节角度,单位度,精度 0.001°(若为升降机构高度,则单位:mm,精度:1mm,范围:0 ~2300)
+ int current; ///< 驱动电流,单位:mA,精度:1mA
+ int err_flag; ///< 驱动错误代码,错误代码类型参考关节错误代码
+ int mode; ///< 当前状态,0-空闲,1-正方向速度运动,2-正方向位置运动,3-负方向速度运动,4-负方向位置运动
+} rm_expand_state_t;
+
+/**
+ * @brief 文件下发
+ * @ingroup OnlineProgramming
+ */
+typedef struct {
+ char project_path[300]; ///< 下发文件路径文件名
+ int project_path_len; ///< 名称长度
+ int plan_speed; ///< 规划速度比例系数
+ int only_save; ///< 0-保存并运行文件,1-仅保存文件,不运行
+ int save_id; ///< 保存到控制器中的编号
+ int step_flag; ///< 设置单步运行方式模式,1-设置单步模式 0-设置正常运动模式
+ int auto_start; ///< 设置默认在线编程文件,1-设置默认 0-设置非默认
+ int project_type; ///< 下发文件类型。0-在线编程文件,1-拖动示教轨迹文件
+ // int err_line; ///< 若运行失败,该参数返回有问题的工程行数,err_line 为 0,则代表校验数据长度不对
+} rm_send_project_t;
+
+/**
+ * @brief 在线编程存储信息
+ * @ingroup OnlineProgramming
+ */
+typedef struct {
+ int id; ///< 在线编程文件id
+ int size; ///< 文件大小
+ int speed; ///< 默认运行速度
+ char trajectory_name[32]; ///< 文件名称
+}rm_trajectory_data_t;
+/**
+ * @brief 查询在线编程列表
+ * @ingroup OnlineProgramming
+ */
+typedef struct
+{
+ int page_num; // 页码
+ int page_size; // 每页大小
+ int list_size; //返回总数量
+ char vague_search[32]; // 模糊搜索
+ rm_trajectory_data_t trajectory_list[100]; // 符合的在线编程列表
+}rm_program_trajectorys_t;
+
+/**
+ * @brief 在线编程运行状态
+ * @ingroup OnlineProgramming
+ */
+typedef struct
+{
+ int run_state; ///< 运行状态 0 未开始 1运行中 2暂停中
+ int id; ///< 运行轨迹编号
+ int edit_id; ///< 上次编辑的在线编程编号 id
+ int plan_num; ///< 运行行数
+ int total_loop; ///< 循环指令数量
+ int step_mode; ///< 单步模式,1 为单步模式,0 为非单步模式
+ int plan_speed; ///< 全局规划速度比例 1-100
+ int loop_num[100]; ///< 循环行数
+ int loop_cont[100]; ///< 对应循环次数
+}rm_program_run_state_t;
+
+/**
+ * @brief 流程图程序运行状态
+ */
+typedef struct
+{
+ int run_state; ///< 运行状态 0 未开始 1运行中 2暂停中
+ int id; ///< 当前使能的文件id。
+ char name[32]; ///< 当前使能的文件名称。
+ int plan_speed; ///< 当前使能的文件全局规划速度比例 1-100。
+ int step_mode; ///< 单步模式,0为空,1为正常, 2为单步。
+ char modal_id[50]; ///< 运行到的流程图块的id。未运行则不返回
+}rm_flowchart_run_state_t;
+
+/**
+ * @brief 全局路点存储信息
+ * @ingroup OnlineProgramming
+ */
+typedef struct
+{
+ char point_name[20]; ///< 路点名称
+ float joint[ARM_DOF]; ///< 关节角度
+ rm_pose_t pose; ///< 位姿信息
+ char work_frame[12]; ///< 工作坐标系名称
+ char tool_frame[12]; ///< 工具坐标系名称
+ char time[50]; ///< 路点新增或修改时间
+}rm_waypoint_t;
+/**
+ * @brief 全局路点列表
+ * @ingroup OnlineProgramming
+ */
+typedef struct{
+ int page_num; ///< 页码
+ int page_size; ///< 每页大小
+ int total_size; ///< 列表长度
+ char vague_search[32]; ///< 模糊搜索
+ int list_len; ///<返回符合的全局路点列表长度
+ rm_waypoint_t points_list[100]; ///< 返回符合的全局路点列表
+}rm_waypoint_list_t;
+
+/**
+ * @brief 几何模型长方体参数
+ * @ingroup Electronic_Fence
+ */
+typedef struct{
+ float x_min_limit; ///< 长方体基于世界坐标系 X 方向最小位置,单位 m
+ float x_max_limit; ///< 长方体基于世界坐标系 X 方向最大位置,单位 m
+ float y_min_limit; ///< 长方体基于世界坐标系 Y 方向最小位置,单位 m
+ float y_max_limit; ///< 长方体基于世界坐标系 Y 方向最大位置,单位 m
+ float z_min_limit; ///< 长方体基于世界坐标系 Z 方向最小位置,单位 m
+ float z_max_limit; ///< 长方体基于世界坐标系 Z 方向最大位置,单位 m
+}rm_fence_config_cube_t;
+/**
+ * @brief 几何模型点面矢量平面参数
+ * @ingroup Electronic_Fence
+ */
+typedef struct{
+ float x1, y1, z1; ///< 点面矢量平面三点法中的第一个点坐标,单位 m
+ float x2, y2, z2; ///< 点面矢量平面三点法中的第二个点坐标,单位 m
+ float x3, y3, z3; ///< 点面矢量平面三点法中的第三个点坐标,单位 m
+}rm_fence_config_plane_t;
+/**
+ * @brief 几何模型球体参数
+ * @ingroup Electronic_Fence
+ */
+typedef struct{
+ float x; ///< 表示球心在世界坐标系 X 轴的坐标,单位 m
+ float y; ///< 表示球心在世界坐标系 Y 轴的坐标,单位 m
+ float z; ///< 表示球心在世界坐标系 Z 轴的坐标,单位 m
+ float radius; ///< 表示半径,单位 m
+}rm_fence_config_sphere_t;
+/**
+ * @brief 几何模型参数
+ * @ingroup Electronic_Fence
+ */
+typedef struct{
+ int form; ///< 形状,1 表示长方体,2 表示点面矢量平面,3 表示球体
+ char name[12]; ///< 电子围栏名称,不超过 10 个字节,支持字母、数字、下划线
+ rm_fence_config_cube_t cube; ///< 长方体参数
+ rm_fence_config_plane_t plan; ///< 点面矢量平面参数
+ rm_fence_config_sphere_t sphere; ///< 球体参数
+}rm_fence_config_t;
+
+/**
+ * @brief 几何模型名称结构体
+ * @ingroup Electronic_Fence
+ */
+typedef struct
+{
+ char name[12]; ///< 几何模型名称,不超过10个字符
+}rm_fence_names_t;
+
+/**
+ * @brief 几何模型参数列表
+ * @ingroup Electronic_Fence
+ */
+typedef struct
+{
+ rm_fence_config_t config[10];
+}rm_fence_config_list_t;
+/**
+ * @brief 包络球参数
+ *
+ */
+typedef struct{
+ char name[12]; ///< 工具包络球体的名称,1-10 个字节,支持字母数字下划线
+ float radius; ///< 工具包络球体的半径,单位 m
+ float x; ///< 工具包络球体球心基于末端法兰坐标系的 X 轴坐标,单位 m
+ float y; ///< 工具包络球体球心基于末端法兰坐标系的 Y 轴坐标,单位 m
+ float z; ///< 工具包络球体球心基于末端法兰坐标系的 Z 轴坐标,单位 m
+}rm_envelopes_ball_t;
+/**
+ * @brief 包络球参数集合
+ *
+ */
+typedef struct{
+ rm_envelopes_ball_t balls[5];///< 包络参数列表,每个工具最多支持 5 个包络球,可以没有包络
+ int size; ///< 包络球数量
+ char tool_name[12];///< 控制器中已存在的工具坐标系名称,如果不存在该字段,则为临时设置当前包络参数
+}rm_envelope_balls_list_t;
+
+/**
+ * @brief 电子围栏/虚拟墙使能状态参数
+ *
+ */
+typedef struct
+{
+ bool enable_state; ///< 电子围栏/虚拟墙使能状态,true 代表使能,false 代表禁使能
+ int in_out_side; ///< 0-机器人在电子围栏/虚拟墙内部,1-机器人在电子围栏外部
+ int effective_region; ///< 0-电子围栏针对整臂区域生效,1-虚拟墙针对末端生效
+}rm_electronic_fence_enable_t;
+
+
+/**
+ * @brief (UDP主动上报机械臂信息)力传感器数据结构体
+ *
+*/
+typedef struct {
+ float force[6]; ///< 当前力传感器原始数据,0.001N或0.001Nm
+ float zero_force[6]; ///< 当前力传感器系统外受力数据,0.001N或0.001Nm
+ int coordinate; ///< 系统外受力数据的坐标系,0为传感器坐标系 1为当前工作坐标系 2为当前工具坐标系
+} rm_force_sensor_t;
+
+/***
+ * 扩展关节数据
+ *
+ */
+typedef struct {
+ float pos; ///< 当前角度 精度 0.001°,单位:°
+ int current; ///< 当前驱动电流,单位:mA,精度:1mA
+ int err_flag; ///< 驱动错误代码,错误代码类型参考关节错误代码
+ int en_flag; ///< 当前关节使能状态 ,1 为上使能,0 为掉使能
+ int joint_id; ///< 关节id号
+ int mode; ///< 当前升降状态,0-空闲,1-正方向速度运动,2-正方向位置运动,3-负方向速度运动,4-负方向位置运动
+} rm_udp_expand_state_t;
+
+/***
+ * 升降机构状态
+ *
+ */
+typedef struct {
+ int height; ///< 当前升降机构高度,单位:mm,精度:1mm
+ float pos; ///< 当前角度 精度 0.001°,单位:°
+ int current; ///< 当前驱动电流,单位:mA,精度:1mA
+ int err_flag; ///< 驱动错误代码,错误代码类型参考关节错误代码
+ int en_flag; ///< 当前关节使能状态 ,1 为上使能,0 为掉使能
+} rm_udp_lift_state_t;
+/***
+ * 灵巧手状态
+ *
+ */
+typedef struct {
+ int hand_pos[6]; ///< 表示灵巧手位置
+ int hand_angle[6]; ///< 表示灵巧手角度
+ int hand_force[6]; ///< 表示灵巧手自由度力,单位mN
+ int hand_state[6]; ///< 表示灵巧手自由度状态,由灵巧手厂商定义状态含义
+ int hand_err; ///< 表示灵巧手系统错误,由灵巧手厂商定义错误含义,例如因时状态码如下:1表示有错误,0表示无错误
+} rm_udp_hand_state_t;
+
+/***
+ *
+ * 轨迹连接配置
+ */
+typedef enum{
+ RM_TRAJECTORY_DISCONNECT_E = 0, ///<立即规划并执行轨迹,不连接后续轨迹
+ RM_TRAJECTORY_CONNECT_E ///<将当前轨迹与下一条轨迹一起规划
+}rm_trajectory_connect_config_e;
+
+/**
+ * @brief 机械臂当前状态
+ *
+ */
+typedef enum {
+ RM_IDLE_E, // 使能但空闲状态
+ RM_MOVE_L_E, // move L运动中状态
+ RM_MOVE_J_E, // move J运动中状态
+ RM_MOVE_C_E, // move C运动中状态
+ RM_MOVE_S_E, // move S运动中状态
+ RM_MOVE_THROUGH_JOINT_E, // 角度透传状态
+ RM_MOVE_THROUGH_POSE_E, // 位姿透传状态
+ RM_MOVE_THROUGH_FORCE_POSE_E, // 力控透传状态
+ RM_MOVE_THROUGH_CURRENT_E, // 电流环透传状态
+ RM_STOP_E, // 急停状态
+ RM_SLOW_STOP_E, // 缓停状态
+ RM_PAUSE_E, // 暂停状态
+ RM_CURRENT_DRAG_E, // 电流环拖动状态
+ RM_SENSOR_DRAG_E, // 六维力拖动状态
+ RM_TECH_DEMONSTRATION_E // 示教状态
+} rm_udp_arm_current_status_e;
+
+/***
+ * aloha主臂状态
+ *
+ */
+typedef struct {
+ int io1_state; ///< IO1状态(手柄光电检测),0为按键未触发,1为按键触发。
+ int io2_state; ///< IO2状态(手柄光电检测),0为按键未触发,1为按键触发。
+} rm_udp_aloha_state_t;
+
+/**
+ * 末端设备基础信息(末端生态协议支持)
+*/
+typedef struct{
+ char manu[10]; // 设备厂家
+ int type; // 设备类型 1:两指夹爪 2:五指灵巧手 3:三指夹爪
+ char hv[10]; // 硬件版本
+ char sv[10]; // 软件版本
+ char bv[10]; // boot版本
+ int id; // 设备ID
+ int dof; // 自由度
+ int check; // 自检开关
+ int bee; // 蜂鸣器开关
+ bool force; // 力控支持
+ bool touch; // 触觉支持
+ int touch_num; // 触觉个数
+ int touch_sw; // 触觉开关
+ int hand; // 手方向 1 :左手 2: 右手
+ int pos_up[12]; // 位置上限,单位:无量纲
+ int pos_low[12]; // 位置下限,单位:无量纲
+ int angle_up[12]; // 角度上限,单位:0.01度
+ int angle_low[12]; // 角度下限,单位:0.01度
+ int speed_up[12]; // 速度上限,单位:无量纲
+ int speed_low[12]; // 速度下限,单位:无量纲
+ int force_up[12]; // 力上限,单位:0.001N
+ int force_low[12]; // 力下限,单位:0.001N
+} rm_plus_base_info_t;
+// 单位:无量纲
+/**
+ * 末端设备实时信息(末端生态协议支持)
+*/
+typedef struct{
+ int sys_state; // 系统状态:0正常1设备故障
+ int dof_state[12]; // 各自由度当前状态:0正在松开1正在闭合2位置到位停止3力控到位停止4触觉到位停止5电流保护停止6发生故障
+ int dof_err[12]; // 各自由度错误信息
+ int pos[12]; // 各自由度当前位置,单位:无量纲
+ int speed[12]; //各自由度当前速度,闭合正,松开负,单位:无量纲
+ int angle[12]; // 各自由度当前角度,单位:0.01度
+ int current[12]; // 各自由度当前电流,单位:mA
+ int normal_force[18]; // 自由度触觉三维力的法向力,1-6自由度触觉三维力的法向力*3
+ int tangential_force[18]; // 自由度触觉三维力的切向力
+ int tangential_force_dir[18]; // 自由度触觉三维力的切向力方向
+ uint32_t tsa[12]; // 自由度触觉自接近
+ uint32_t tma[12]; // 自由度触觉互接近
+ int touch_data[18]; // 触觉传感器原始数据(示例中有,但未显示数据的JSON情况)
+ int force[12]; //自由度力矩,闭合正,松开负,单位0.001N
+} rm_plus_state_info_t;
+
+
+/**
+ * @brief udp主动上报机械臂信息
+ *
+*/
+typedef struct
+{
+ int errCode; ///< 数据解析错误码,-3为数据解析错误,代表推送的数据不完整或格式不正确
+ char arm_ip[16]; ///< 推送数据的机械臂的IP地址
+ rm_joint_status_t joint_status; ///< 关节状态
+ rm_force_sensor_t force_sensor; ///< 力数据(六维力或一维力版本支持)
+ rm_err_t err; ///< 错误码
+ rm_pose_t waypoint; ///< 当前路点信息
+ rm_udp_lift_state_t liftState; ///< 升降关节数据
+ rm_udp_expand_state_t expandState; ///< 扩展关节数据
+ rm_udp_hand_state_t handState; ///< 灵巧手数据
+ rm_udp_arm_current_status_e arm_current_status; ///< 机械臂状态
+ rm_udp_aloha_state_t aloha_state; ///< aloha主臂状态
+ int rm_plus_state; ///< 末端设备状态,0-设备在线,1-表示协议未开启,2-表示协议开启但是设备不在线
+ rm_plus_base_info_t plus_base_info; ///< 末端设备基础信息
+ rm_plus_state_info_t plus_state_info; ///< 末端设备实时信息
+}rm_realtime_arm_joint_state_t;
+
+/**
+ * @brief 逆解参数
+ * @ingroup Algo
+ */
+typedef struct {
+ float q_in[ARM_DOF]; ///< 上一时刻关节角度,单位°
+ rm_pose_t q_pose; ///< 目标位姿
+ uint8_t flag; ///< 姿态参数类别:0-四元数;1-欧拉角
+} rm_inverse_kinematics_params_t;
+
+typedef struct {
+ int result; // 0:成功,1:逆解失败,-1:上一时刻关节角度输入为空或超关节限位,-2:目标位姿四元数不合法, -3:当前机器人非六自由度,当前仅支持六自由度机器人
+ int num; // number of solutions
+ float q_ref[8]; // 参考关节角度,通常是当前关节角度, 单位 °
+ float q_solve[8][8]; // 关节角全解, 单位 °
+} rm_inverse_kinematics_all_solve_t;
+
+/**
+ * @brief 包络球描述数据结构
+*/
+typedef struct
+{
+ float radius; // 球体半径(单位:m)
+ float centrePoint[3]; // 球体中心位置(单位:m,以法兰坐标系为参考坐标系)
+} rm_tool_sphere_t; // 工具包络球参数
+
+
+/**
+ * @brief 旋转矩阵
+ * @ingroup Algo
+ */
+typedef struct
+{
+ short irow;
+ short iline;
+ float data[4][4];
+} rm_matrix_t;
+/**
+ * @brief 机械臂事件回调函数
+ * @ingroup Init_Class
+ */
+typedef void (*rm_event_callback_ptr)(rm_event_push_data_t data);
+/**
+ * @brief UDP机械臂状态主动上报回调函数
+ * @ingroup Init_Class
+ */
+typedef void (*rm_realtime_arm_state_callback_ptr)(rm_realtime_arm_joint_state_t data);
+
+/**
+ * @brief 机械臂基本信息
+ * @ingroup Init_Class
+ */
+typedef struct
+{
+ uint8_t arm_dof; ///< 机械臂自由度
+ rm_robot_arm_model_e arm_model; ///< 机械臂型号
+ rm_force_type_e force_type; ///< 末端力传感器版本
+ uint8_t robot_controller_version; ///< 机械臂控制器版本,4:四代控制器,3:三代控制器。
+}rm_robot_info_t;
+
+/**
+ * @brief 机械臂控制句柄
+ * @ingroup Init_Class
+ */
+typedef struct {
+ int id; ///< 句柄id,连接成功id大于0,连接失败返回-1
+}rm_robot_handle;
+
+
+typedef struct
+{
+ float d[8]; //* unit: m
+ float a[8]; //* unit: m
+ float alpha[8]; //* unit: °
+ float offset[8]; //* unit: °
+} rm_dh_t;
+
+/**
+ * @brief 版本号结构体
+ * 不超过10个字符
+ * @ingroup ToolCoordinateConfig
+ * @ingroup WorkCoordinateConfig
+ */
+typedef struct {
+ char version[10];
+} rm_version_t;
+
+/**
+ * @brief 轨迹信息结构体
+ */
+typedef struct {
+ int point_num; ///< 轨迹点数量
+ char name[20]; ///< 轨迹名称
+ char create_time[20]; ///< 创建时间
+}rm_trajectory_info_t;
+/**
+ * @brief 轨迹列表结构体
+ * @ingroup OnlineProgramming
+ */
+typedef struct{
+ int page_num; ///< 页码
+ int page_size; ///< 每页大小
+ int total_size; ///< 列表长度
+ char vague_search[32]; ///< 模糊搜索
+ int list_len; ///<返回符合的轨迹列表长度
+ rm_trajectory_info_t tra_list[100]; ///< 返回符合的轨迹列表
+}rm_trajectory_list_t;
+/**
+ * @brief Modbus TCP主站信息结构体
+ */
+typedef struct {
+ char master_name[20]; // Modbus 主站名称,最大长度15个字符,不超过15个字符
+ char ip[16]; // TCP主站 IP 地址
+ int port; // TCP主站端口号
+}rm_modbus_tcp_master_info_t;
+/**
+ * @brief Modbus TCP主站列表结构体
+ */
+typedef struct{
+ int page_num; ///< 页码
+ int page_size; ///< 每页大小
+ int total_size; ///< 列表长度
+ char vague_search[32]; ///< 模糊搜索
+ int list_len; ///<返回符合的TCP主站列表长度
+ rm_modbus_tcp_master_info_t master_list[100]; ///< 返回符合的TCP主站列表
+}rm_modbus_tcp_master_list_t;
+
+/**
+ * @brief Modbus RTU读数据参数结构体
+ */
+typedef struct {
+ int address; ///< 数据起始地址
+ int device; ///< 外设设备地址
+ int type; ///< 0-控制器端modbus主机;1-工具端modbus主机。
+ int num; ///< 要读的数据的数量,数据长度不超过109
+}rm_modbus_rtu_read_params_t;
+/**
+ * @brief Modbus RTU写数据结构体
+ */
+typedef struct {
+ int address; ///< 数据起始地址
+ int device; ///< 外设设备地址
+ int type; ///< 0-控制器端modbus主机;1-工具端modbus主机。
+ int num; ///< 要写的数据的数量,最大不超过100
+ int data[120]; ///< 要写的数据,数据长度不超过100
+}rm_modbus_rtu_write_params_t;
+
+/**
+ * @brief Modbus TCP读数据参数结构体
+ */
+typedef struct {
+ int address; // 数据起始地址
+ char master_name[20]; // Modbus 主站名称,最大长度15个字符,不超过15个字符(master_name与IP二选一,若有IP和port优先使用IP和port)
+ char ip[16]; // 主机连接的 IP 地址(master_name与IP二选一,若有IP和port优先使用IP和port)
+ int port; // 主机连接的端口号
+ int num; // 读取数据数量,最大不超过100
+}rm_modbus_tcp_read_params_t;
+/**
+ * @brief Modbus TCP写数据结构体
+ */
+typedef struct {
+ int address; // 数据起始地址
+ char master_name[20]; // Modbus 主站名称,最大长度15个字符,不超过15个字符(master_name与IP二选一,若有IP和port优先使用IP和port)
+ char ip[16]; // 主机连接的 IP 地址(master_name与IP二选一,若有IP和port优先使用IP和port)
+ int port; // 主机连接的端口号
+ int num; // 写入数据数量,最大不超过100
+ int data[120]; // 写入的数据,数据长度不超过100
+}rm_modbus_tcp_write_params_t;
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif
\ No newline at end of file
diff --git a/HiveCoreR0/src/ros2_rm_robot-humble/rm_driver/include/rm_driver/rm_driver.h b/HiveCoreR0/src/ros2_rm_robot-humble/rm_driver/include/rm_driver/rm_driver.h
new file mode 100755
index 0000000..90976cf
--- /dev/null
+++ b/HiveCoreR0/src/ros2_rm_robot-humble/rm_driver/include/rm_driver/rm_driver.h
@@ -0,0 +1,773 @@
+// Copyright (c) 2023 RealMan Intelligent Ltd
+//
+// Licensed under the Apache License, Version 2.0 (the "License");
+// you may not use this file except in compliance with the License.
+// You may obtain a copy of the License at
+//
+// http://www.apache.org/licenses/LICENSE-2.0
+//
+// Unless required by applicable law or agreed to in writing, software
+// distributed under the License is distributed on an "AS IS" BASIS,
+// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+// See the License for the specific language governing permissions and
+// limitations under the License.
+
+#include
+#include "rclcpp/rclcpp.hpp"
+#include "rclcpp/clock.hpp"
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+
+
+#include // 设置非阻塞需要用到的头文件
+#include
+#include //使用fd_set结构体时使用。
+#include
+
+#include "rm_service.h"
+#include "rm_define.h"
+#include "rm_ros_interfaces/msg/movej.hpp"
+#include "rm_ros_interfaces/msg/movel.hpp"
+#include "rm_ros_interfaces/msg/movec.hpp"
+#include "rm_ros_interfaces/msg/movejp.hpp"
+#include "rm_ros_interfaces/msg/jointteach.hpp"
+#include "rm_ros_interfaces/msg/ortteach.hpp"
+#include "rm_ros_interfaces/msg/posteach.hpp"
+#include "rm_ros_interfaces/msg/setrealtimepush.hpp"
+#include "rm_ros_interfaces/msg/softwarebuildinfo.hpp"
+#include "rm_ros_interfaces/msg/armsoftversion.hpp"
+#include "rm_ros_interfaces/msg/sixforce.hpp"
+#include "rm_ros_interfaces/msg/jointerrorcode.hpp"
+#include "rm_ros_interfaces/msg/forcepositionmovejoint.hpp"
+#include "rm_ros_interfaces/msg/forcepositionmovepose.hpp"
+#include "rm_ros_interfaces/msg/setforceposition.hpp"
+#include "rm_ros_interfaces/msg/jointpos.hpp"
+#include "rm_ros_interfaces/msg/cartepos.hpp"
+#include "rm_ros_interfaces/msg/jointerrclear.hpp"
+#include "rm_ros_interfaces/msg/gripperset.hpp"
+#include "rm_ros_interfaces/msg/gripperpick.hpp"
+#include "rm_ros_interfaces/msg/handangle.hpp"
+#include "rm_ros_interfaces/msg/handforce.hpp"
+#include "rm_ros_interfaces/msg/handposture.hpp"
+#include "rm_ros_interfaces/msg/handseq.hpp"
+#include "rm_ros_interfaces/msg/handspeed.hpp"
+#include "rm_ros_interfaces/msg/armstate.hpp"
+#include "rm_ros_interfaces/msg/armoriginalstate.hpp"
+#include "rm_ros_interfaces/msg/getallframe.hpp"
+#include "rm_ros_interfaces/msg/liftspeed.hpp"
+#include "rm_ros_interfaces/msg/liftstate.hpp"
+#include "rm_ros_interfaces/msg/liftheight.hpp"
+#include "rm_ros_interfaces/msg/handstatus.hpp"
+#include "rm_ros_interfaces/msg/armcurrentstatus.hpp"
+#include "rm_ros_interfaces/msg/jointcurrent.hpp"
+#include "rm_ros_interfaces/msg/jointenflag.hpp"
+#include "rm_ros_interfaces/msg/jointposeeuler.hpp"
+#include "rm_ros_interfaces/msg/jointspeed.hpp"
+#include "rm_ros_interfaces/msg/jointtemperature.hpp"
+#include "rm_ros_interfaces/msg/jointvoltage.hpp"
+#include "rm_ros_interfaces/msg/jointposcustom.hpp"
+#include "rm_ros_interfaces/msg/carteposcustom.hpp"
+#include "rm_ros_interfaces/msg/rmplusbase.hpp"
+#include "rm_ros_interfaces/msg/rmplusstate.hpp"
+#include "rm_ros_interfaces/msg/rmerr.hpp"
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+// 适配四代控制器新增
+#include "rm_ros_interfaces/msg/robot_info.hpp"
+// #include "rm_ros_interfaces/msg/rmversion.hpp"
+#include "rm_ros_interfaces/msg/flowchartrunstate.hpp"
+#include "rm_ros_interfaces/msg/trajectoryinfo.hpp"
+#include "rm_ros_interfaces/msg/trajectorylist.hpp"
+#include "rm_ros_interfaces/msg/modbustcpmasterinfo.hpp"
+#include "rm_ros_interfaces/msg/modbustcpmasterupdata.hpp"
+#include "rm_ros_interfaces/msg/modbustcpmasterlist.hpp"
+#include "rm_ros_interfaces/msg/modbustcpreadparams.hpp"
+#include "rm_ros_interfaces/msg/modbustcpwriteparams.hpp"
+#include "rm_ros_interfaces/msg/modbusrtureadparams.hpp"
+#include "rm_ros_interfaces/msg/modbusrtuwriteparams.hpp"
+#include "rm_ros_interfaces/msg/programrunstate.hpp"
+// #include "rm_ros_interfaces/msg/armsoftversionv3.hpp"
+// #include "rm_ros_interfaces/msg/armsoftversionv4.hpp"
+#include "rm_ros_interfaces/msg/moveloffset.hpp"
+#include "rm_ros_interfaces/msg/jointversion.hpp"
+#include "rm_ros_interfaces/msg/stop.hpp"
+#include "rm_ros_interfaces/msg/mastername.hpp"
+#include "rm_ros_interfaces/msg/getmodbustcpmasterlist.hpp"
+#include "rm_ros_interfaces/msg/rs485params.hpp"
+#include "rm_ros_interfaces/msg/modbusreaddata.hpp"
+#include "rm_ros_interfaces/msg/gettrajectorylist.hpp"
+#include "rm_ros_interfaces/msg/sendproject.hpp"
+#include "rm_ros_interfaces/msg/toolsoftwareversionv4.hpp"
+
+
+#define RAD_DEGREE 57.295791433
+#define DEGREE_RAD 0.01745
+using namespace std::chrono_literals;
+//udp数据处理函数
+// void Udp_RobotStatuscallback(RobotStatus Udp_RM_Callback);
+void Udp_Robot_Status_Callback(rm_realtime_arm_joint_state_t data);
+//ctrl+c执行程序
+static void my_handler(int sig);
+//机械臂型号信息
+int realman_arm;
+//tcp ip
+char* tcp_ip;
+//tcp port
+int tcp_port;
+//udp hz
+int udp_cycle_g = 5;
+//arm dof
+int arm_dof_g = 6;
+// controller verison
+int controller_version = 3;
+//ctrl+c触发信号
+bool ctrl_flag = false;
+// 灵巧手数据发布
+bool udp_hand_g = false;
+// 末端设备基础信息发布
+bool rm_plus_base_g = false;
+// 末端设备实时信息
+bool rm_plus_state_g = false;
+// 连接状态标志
+int connect_state_flag = 0;
+//api类
+RM_Service Rm_Api;
+//机械臂TCp网络通信套接字
+// SOCKHANDLE m_sockhand = -1;
+//机械臂控制句柄
+rm_robot_handle *robot_handle;
+
+//末端设备基础信息
+typedef struct{
+ char manu[10]; // 设备厂家
+ int type; // 设备类型 1:两指夹爪 2:五指灵巧手 3:三指夹爪
+ char hv[10]; // 硬件版本
+ char sv[10]; // 软件版本
+ char bv[10]; // boot版本
+ int id; // 设备ID
+ int dof; // 自由度
+ int check; // 自检开关
+ int bee; // 蜂鸣器开关
+ bool force; // 力控支持
+ bool touch; // 触觉支持
+ int touch_num; // 触觉个数
+ int touch_sw; // 触觉开关
+ int hand; // 手方向 1 :左手 2: 右手
+ int pos_up[12]; // 位置上限,单位:无量纲
+ int pos_low[12]; // 位置下限,单位:无量纲
+ int angle_up[12]; // 角度上限,单位:0.01度
+ int angle_low[12]; // 角度下限,单位:0.01度
+ int speed_up[12]; // 速度上限,单位:无量纲
+ int speed_low[12]; // 速度下限,单位:无量纲
+ int force_up[12]; // 力上限,单位:0.001N
+ int force_low[12]; // 力下限,单位:0.001N
+} RM_PLUS_BASE_INFO;
+
+//末端设备实时信息(末端生态协议支持)
+typedef struct
+{
+ int sys_state; //系统状态
+ int dof_state[12]; //各自由度当前状态
+ int dof_err[12]; //各自由度错误信息
+ int pos[12]; //各自由度当前位置
+ int speed[12]; //各自由度当前速度
+ int angle[12]; //各自由度当前角度
+ int current[12]; //各自由度当前电流
+ int normal_force[18]; //自由度触觉三维力的法向力
+ int tangential_force[18]; //自由度触觉三维力的切向力
+ int tangential_force_dir[18]; //自由度触觉三维力的切向力方向
+ uint32_t tsa[12]; //自由度触觉自接近
+ uint32_t tma[12]; //自由度触觉互接近
+ int touch_data[18]; //触觉传感器原始数据
+ int force[12]; //自由度力矩
+} RM_PLUS_STATE_INFO;
+
+typedef struct
+{
+ uint8_t err_len;
+ std::vector err;
+} RM_ERR;
+
+//机械臂状态参数
+typedef struct
+{
+ float joint[7]; //关节角度
+ uint16_t err_flag[7]; //关节错误代码
+ uint16_t sys_err; //系统错误代码
+ uint16_t arm_err; //机械臂错误代码
+ float one_force; //一维力传感器原始数据0.001N或0.001Nm
+ float six_force[6]; //六维力数据
+ float joint_current[7]; //机械臂电流数据
+ bool en_flag[7]; //当前关节使能状态 ,1为上使能,0为掉使能
+ float joint_position[3]; //当前末端关节位置,精度0.001°
+ float joint_temperature[7]; //当前关节温度,精度0.001℃
+ float joint_voltage[7]; //当前关节电压,精度0.001V
+ float joint_euler[3]; //欧拉角
+ float joint_quat[4]; //四元数
+ float zero_force[6]; //当前力传感器系统外受力数据0.001N或0.001Nm
+ float work_zero_force[6]; //当前工作坐标系下系统受到的外力数据
+ float tool_zero_force[6]; //当前该工具坐标系下系统受到的外力数据
+ float one_zero_force; //一维力基准坐标系下系统受力数据
+ uint16_t control_version; //版本信息
+ uint16_t coordinate; //当前六维力传感器的基准坐标
+ uint16_t hand_angle[6]; //手指角度数组,范围:0~2000.
+ uint16_t hand_pos[6]; //手指位置数组,范围:0~1000.
+ uint16_t hand_state[6]; //手指状态,0正在松开,1正在抓取,2位置到位停止,3力到位停止,5电流保护停止,6电缸堵转停止,7电缸故障停止
+ uint16_t hand_force[6]; //灵巧手自由度电流,单位mN
+ uint16_t hand_err; //灵巧手系统错误,1表示有错误,0表示无错误
+ uint16_t arm_current_status; //当前机械臂状态上报,
+ float joint_speed[7]; //当前关节速度,精度0.02RPM。
+ RM_PLUS_STATE_INFO udp_rm_plus_state_info; //末端设备实时信息
+ RM_PLUS_BASE_INFO udp_rm_plus_base_info; //末端设备实时信息
+ RM_ERR udp_rm_err;
+} JOINT_STATE_VALUE;
+JOINT_STATE_VALUE Udp_RM_Joint;
+
+std_msgs::msg::UInt16 sys_err_; //系统错误信息
+std_msgs::msg::UInt16 arm_err_; //机械臂错误信息
+std_msgs::msg::UInt16 arm_coordinate_; //六维力基准坐标系
+sensor_msgs::msg::JointState udp_real_joint_; //关节角度
+geometry_msgs::msg::Pose udp_arm_pose_; //位姿
+rm_ros_interfaces::msg::Sixforce udp_sixforce_; //六维力传感器原始数据
+rm_ros_interfaces::msg::Sixforce udp_zeroforce_; //六维力传感器转化后数据
+rm_ros_interfaces::msg::Sixforce udp_oneforce_; //一维力传感器原始数据
+rm_ros_interfaces::msg::Sixforce udp_onezeroforce_; //一维力传感器转化后数据
+rm_ros_interfaces::msg::Jointerrorcode udp_joint_error_code_; //关节报错数据
+rm_ros_interfaces::msg::Handstatus udp_hand_status_;
+rm_ros_interfaces::msg::Armoriginalstate Arm_original_state; //机械臂原始数据(角度+欧拉角)
+rm_ros_interfaces::msg::Armstate Arm_state; //机械臂数据(弧度+四元数)
+rm_ros_interfaces::msg::Armcurrentstatus udp_arm_current_status_; //
+rm_ros_interfaces::msg::Jointcurrent udp_joint_current_; //
+rm_ros_interfaces::msg::Jointenflag udp_joint_en_flag_;
+rm_ros_interfaces::msg::Jointposeeuler udp_joint_pose_euler_;
+rm_ros_interfaces::msg::Jointspeed udp_joint_speed_;
+rm_ros_interfaces::msg::Jointtemperature udp_joint_temperature_;
+rm_ros_interfaces::msg::Jointvoltage udp_joint_voltage_;
+rm_ros_interfaces::msg::Rmplusbase udp_rm_plus_base_; //末端设备基础信息
+rm_ros_interfaces::msg::Rmplusstate udp_rm_plus_state_; //末端设备实时信息
+rm_ros_interfaces::msg::Rmerr udp_rm_err_; //末端设备实时信息
+
+class RmArm: public rclcpp::Node
+{
+public:
+ RmArm();
+ ~RmArm();
+
+/**********************************************初始化需要用到的回调函数***********************************************/
+ void Get_Arm_Version();
+ void Get_Controller_Version(); //获取版本信息
+ void Set_UDP_Configuration(int udp_cycle, int udp_port, int udp_force_coordinate, std::string udp_ip,bool hand, bool rm_plus_base, bool rm_plus_state); //设置udp主动上报配置
+ /*******************************运动控制回调函数******************************/
+ // void Arm_MoveJ_75_Callback(rm_ros_interfaces::msg::Movej75::SharedPtr msg); //75角度控制
+ void Arm_MoveJ_Callback(rm_ros_interfaces::msg::Movej::SharedPtr msg); //角度控制
+ void Arm_MoveL_Callback(rm_ros_interfaces::msg::Movel::SharedPtr msg);
+ void Arm_MoveL_Offset_Callback(rm_ros_interfaces::msg::Moveloffset::SharedPtr msg);
+ void Arm_MoveC_Callback(rm_ros_interfaces::msg::Movec::SharedPtr msg); //圆弧运动控制
+ void Arm_Movej_CANFD_Callback(rm_ros_interfaces::msg::Jointpos::SharedPtr msg); //角度透传控制
+ void Arm_Movej_CANFD_Custom_Callback(rm_ros_interfaces::msg::Jointposcustom::SharedPtr msg); //角度透传控制高跟随下可自定义模式
+ void Arm_Movep_CANFD_Callback(rm_ros_interfaces::msg::Cartepos::SharedPtr msg); //位姿透传控制
+ void Arm_Movep_CANFD_Custom_Callback(rm_ros_interfaces::msg::Carteposcustom::SharedPtr msg); //位姿透传控制高跟随下可自定义模式
+ void Arm_MoveJ_P_Callback(rm_ros_interfaces::msg::Movejp::SharedPtr msg); //位姿运动控制
+ void Arm_Move_Stop_Callback(const std_msgs::msg::Empty::SharedPtr msg); //轨迹急停控制
+ void Arm_Emergency_Stop_Callback(const rm_ros_interfaces::msg::Stop::SharedPtr msg); //设置机械臂急停状态
+ /**************************************************************************/
+ void Set_Joint_Teach_Callback(rm_ros_interfaces::msg::Jointteach::SharedPtr msg); //关节示教
+ void Set_Pos_Teach_Callback(rm_ros_interfaces::msg::Posteach::SharedPtr msg); //位置示教
+ void Set_Ort_Teach_Callback(rm_ros_interfaces::msg::Ortteach::SharedPtr msg); //姿态示教
+ void Set_Stop_Teach_Callback(const std_msgs::msg::Empty::SharedPtr msg); //停止示教
+
+ /*******************************主动上报回调函数******************************/
+ void Arm_Get_Realtime_Push_Callback(const std_msgs::msg::Empty::SharedPtr msg); //获取主动上报配置
+ void Arm_Set_Realtime_Push_Callback(const rm_ros_interfaces::msg::Setrealtimepush::SharedPtr msg); //设置主动上报配置参数
+ /*******************************力位混合回调函数******************************/
+ void Arm_Start_Force_Position_Move_Callback(const std_msgs::msg::Empty::SharedPtr msg); //力位混合开始
+ void Arm_Stop_Force_Position_Move_Callback(const std_msgs::msg::Empty::SharedPtr msg); //力位混合结束
+ void Arm_Force_Position_Move_Joint_Callback(const rm_ros_interfaces::msg::Forcepositionmovejoint::SharedPtr msg); //力位混合透传(角度)
+ void Arm_Force_Position_Move_Pose_Callback(const rm_ros_interfaces::msg::Forcepositionmovepose::SharedPtr msg); //力位混合透传(位姿)
+ void Arm_Set_Force_Postion_Callback(const rm_ros_interfaces::msg::Setforceposition::SharedPtr msg); //使能力位混合透传
+ void Arm_Stop_Force_Postion_Callback(const std_msgs::msg::Empty::SharedPtr msg); //结束力位混合透传
+ /*******************************坐标系回调函数******************************/
+ void Arm_Change_Work_Frame_Callback(const std_msgs::msg::String::SharedPtr msg); //更改工作坐标系
+ void Arm_Get_Curr_WorkFrame_Callback(const std_msgs::msg::Empty::SharedPtr msg); //查询工作坐标系
+ void Arm_Get_Current_Tool_Frame_Callback(const std_msgs::msg::Empty::SharedPtr msg); //查询工具坐标系
+ void Arm_Get_All_Tool_Frame_Callback(const std_msgs::msg::Empty::SharedPtr msg); //查询所有工具坐标系
+ void Arm_Get_All_Work_Frame_Callback(const std_msgs::msg::Empty::SharedPtr msg); //查询所有工作坐标系
+ /*******************************设置工具端电压*********************************/
+ void Arm_Set_Tool_Voltage_Callback(const std_msgs::msg::UInt16::SharedPtr msg);
+ /*******************************清除错误码回调函数****************************/
+ void Arm_Set_Joint_Err_Clear_Callback(const rm_ros_interfaces::msg::Jointerrclear::SharedPtr msg);
+ /*********************************夹爪回调函数******************************/
+ void Arm_Set_Gripper_Pick_On_Callback(const rm_ros_interfaces::msg::Gripperpick::SharedPtr msg); //持续力控夹取
+ void Arm_Set_Gripper_Pick_Callback(const rm_ros_interfaces::msg::Gripperpick::SharedPtr msg); //力控夹取
+ void Arm_Set_Gripper_Position_Callback(const rm_ros_interfaces::msg::Gripperset::SharedPtr msg); //移动到固定位置
+ /*********************************灵巧手回调函数******************************/
+ void Arm_Set_Hand_Posture_Callback(const rm_ros_interfaces::msg::Handposture::SharedPtr msg); //设置灵巧手手势
+ void Arm_Set_Hand_Seq_Callback(const rm_ros_interfaces::msg::Handseq::SharedPtr msg); //设置灵巧手动作序列
+ void Arm_Set_Hand_Angle_Callback(const rm_ros_interfaces::msg::Handangle::SharedPtr msg); //设置灵巧手角度
+ void Arm_Set_Hand_Speed_Callback(const rm_ros_interfaces::msg::Handspeed::SharedPtr msg); //设置灵巧手速度
+ void Arm_Set_Hand_Force_Callback(const rm_ros_interfaces::msg::Handforce::SharedPtr msg); //设置灵巧手力控
+ void Arm_Set_Hand_Follow_Angle_Callback(const rm_ros_interfaces::msg::Handangle::SharedPtr msg); //设置灵巧手角度跟随
+ void Arm_Set_Hand_Follow_Pos_Callback(const rm_ros_interfaces::msg::Handangle::SharedPtr msg); //设置灵巧手位置跟随
+ /*********************************升降机构回调函数******************************/
+ void Arm_Set_Lift_Speed_Callback(const rm_ros_interfaces::msg::Liftspeed::SharedPtr msg); //升降机构速度开环控制
+ void Arm_Set_Lift_Height_Callback(const rm_ros_interfaces::msg::Liftheight::SharedPtr msg); //升降机构位置闭环控制
+ void Arm_Get_Lift_State_Callback(const std_msgs::msg::Empty::SharedPtr msg); //获取升降机构状态
+ /*******************************机械臂状态回调函数****************************/
+ void Arm_Get_Current_Arm_State_Callback(const std_msgs::msg::Empty::SharedPtr msg);
+ /*********************************六维力数据清零******************************/
+ void Arm_Clear_Force_Data_Callback(const std_msgs::msg::Empty::SharedPtr msg);
+ /*********************************六维力数据获取******************************/
+ void Arm_Get_Force_Data_Callback(const std_msgs::msg::Empty::SharedPtr msg);
+ /*********************************适配四代控制器******************************/
+ /*******************************固件版本回调函数******************************/
+ void Arm_Get_Robot_Info_Callback(const std_msgs::msg::Empty::SharedPtr msg); //获取机械臂固件版本
+ void Arm_Get_Arm_Software_Info_Callback(const std_msgs::msg::Empty::SharedPtr msg); //获取机械臂固件版本
+ void Arm_Get_Joint_Software_Version_Callback(const std_msgs::msg::Empty::SharedPtr msg); //获取机械臂固件版本
+ void Arm_Get_Tool_Software_Version_Callback(const std_msgs::msg::Empty::SharedPtr msg); //获取机械臂固件版本
+
+ void Get_Trajectory_File_List_Callback(const rm_ros_interfaces::msg::Gettrajectorylist::SharedPtr msg); //查询轨迹列表
+ void Set_Run_Trajectory_Callback(const std_msgs::msg::String::SharedPtr msg); //开始运行指定轨迹
+ void Delete_Trajectory_File_Callback(const std_msgs::msg::String::SharedPtr msg); //删除指定轨迹
+ void Save_Trajectory_File_Callback(const std_msgs::msg::String::SharedPtr msg); //保存轨迹到控制机器
+
+ void Arm_Get_Flowchart_Program_Run_State_Callback(const std_msgs::msg::Empty::SharedPtr msg); //获取机械臂固件版本
+ void Add_Modbus_Tcp_Master_Callback(const rm_ros_interfaces::msg::Modbustcpmasterinfo::SharedPtr msg); //新增Modbus TCP主站
+ void Update_Modbus_Tcp_Master_Callback(const rm_ros_interfaces::msg::Modbustcpmasterupdata::SharedPtr msg); //更新Modbus TCP主站
+ void Delete_Modbus_Tcp_Master_Callback(const rm_ros_interfaces::msg::Mastername::SharedPtr msg); //删除Modbus TCP主站
+ void Get_Modbus_Tcp_Master_Callback(const rm_ros_interfaces::msg::Mastername::SharedPtr msg); //查询指定modbus主站
+ void Get_Modbus_Tcp_Master_List_Callback(const rm_ros_interfaces::msg::Getmodbustcpmasterlist::SharedPtr msg); //查询modbus主站列表
+ void Set_Controller_RS485_Mode_Callback(const rm_ros_interfaces::msg::RS485params::SharedPtr msg); // 设置控制器RS485模式(四代控制器支持)
+ void Get_Controller_RS485_Mode_v4_Callback(const std_msgs::msg::Empty::SharedPtr msg); // 查询控制器RS485模式(四代控制器支持)
+ void Set_Tool_RS485_Mode_Callback(const rm_ros_interfaces::msg::RS485params::SharedPtr msg); // 设置工具端RS485模式(四代控制器支持)
+ void Get_Tool_RS485_Mode_v4_Callback(const std_msgs::msg::Empty::SharedPtr msg); // 查询工具端RS485模式(四代控制器支持)
+ void Read_Modbus_RTU_Coils_Callback(const rm_ros_interfaces::msg::Modbusrtureadparams::SharedPtr msg);// Modbus RTU协议读线圈
+ void Write_Modbus_RTU_Coils_Callback(const rm_ros_interfaces::msg::Modbusrtuwriteparams::SharedPtr msg);// Modbus RTU协议写线圈
+ void Read_Modbus_RTU_Input_Status_Callback(const rm_ros_interfaces::msg::Modbusrtureadparams::SharedPtr msg);// Modbus RTU协议读离散量输入
+ void Read_Modbus_RTU_Holding_Registers_Callback(const rm_ros_interfaces::msg::Modbusrtureadparams::SharedPtr msg);// Modbus RTU协议读保持寄存器
+ void Write_Modbus_RTU_Registers_Callback(const rm_ros_interfaces::msg::Modbusrtuwriteparams::SharedPtr msg);// Modbus RTU协议写保持寄存器
+ void Read_Modbus_RTU_Input_Registers_Callback(const rm_ros_interfaces::msg::Modbusrtureadparams::SharedPtr msg);// Modbus RTU协议读输入寄存器
+ void Read_Modbus_TCP_Coils_Callback(const rm_ros_interfaces::msg::Modbustcpreadparams::SharedPtr msg);// Modbus TCP协议读线圈
+ void Write_Modbus_TCP_Coils_Callback(const rm_ros_interfaces::msg::Modbustcpwriteparams::SharedPtr msg);// Modbus TCP协议写线圈
+ void Read_Modbus_TCP_Input_Status_Callback(const rm_ros_interfaces::msg::Modbustcpreadparams::SharedPtr msg);// Modbus TCP协议读离散量输入
+ void Read_Modbus_TCP_Holding_Registers_Callback(const rm_ros_interfaces::msg::Modbustcpreadparams::SharedPtr msg);// Modbus TCP协议读保持寄存器
+ void Write_Modbus_TCP_Registers_Callback(const rm_ros_interfaces::msg::Modbustcpwriteparams::SharedPtr msg);// Modbus TCP协议写保持寄存器
+ void Read_Modbus_TCP_Input_Registers_Callback(const rm_ros_interfaces::msg::Modbustcpreadparams::SharedPtr msg);// Modbus TCP协议读输入寄存器
+
+ void Send_Project_Callback(const rm_ros_interfaces::msg::Sendproject::SharedPtr msg); //文件下发
+ void Get_Program_Run_State_Callback(const std_msgs::msg::Empty::SharedPtr msg); //查询在线编程运行状态
+
+
+
+/***************************************************************end******************************************************/
+private:
+ // int Arm_Start(void); //TCP连接函数
+ // void Arm_Close(); //TCP断连函数
+
+/************************************************************变量信息******************************************************/
+ std_msgs::msg::Empty::SharedPtr copy; //闲置
+ // std_msgs::msg::UInt16 sys_err_; //系统错误信息
+ // std_msgs::msg::UInt16 arm_err_; //机械臂错误信息
+ // std_msgs::msg::UInt16 arm_coordinate_; //六维力基准坐标系
+ // sensor_msgs::msg::JointState udp_real_joint_; //关节角度
+ // geometry_msgs::msg::Pose udp_arm_pose_; //位姿
+ // rm_ros_interfaces::msg::Sixforce udp_sixforce_; //六维力传感器原始数据
+ // rm_ros_interfaces::msg::Sixforce udp_zeroforce_; //六维力传感器转化后数据
+ // rm_ros_interfaces::msg::Sixforce udp_oneforce_; //一维力传感器原始数据
+ // rm_ros_interfaces::msg::Sixforce udp_onezeroforce_; //一维力传感器转化后数据
+ // rm_ros_interfaces::msg::Jointerrorcode udp_joint_error_code_; //关节报错数据
+ // rm_ros_interfaces::msg::Armoriginalstate Arm_original_state; //机械臂原始数据(角度+欧拉角)
+ // rm_ros_interfaces::msg::Armstate Arm_state; //机械臂数据(弧度+四元数)
+
+ /****************************************udp主动上报配置查询发布器*************************************/
+ rclcpp::Publisher::SharedPtr Get_Realtime_Push_Result;
+ /****************************************udp主动上报配置查询订阅器*************************************/
+ rclcpp::Subscription::SharedPtr Get_Realtime_Push_Cmd;
+ /******************************************udp主动上报配置发布器***************************************/
+ rclcpp::Publisher::SharedPtr Set_Realtime_Push_Result;
+ /******************************************udp主动上报配置发布器***************************************/
+ rclcpp::Subscription::SharedPtr Set_Realtime_Push_Cmd;
+ /**********************************************************end******************************************************/
+
+ /********************************************************运动配置******************************************************/
+ /****************************************MoveJ运动控制结果发布器*************************************/
+ rclcpp::Publisher::SharedPtr MoveJ_Cmd_Result;
+ /******************************************75MoveJ运动控制订阅器***************************************/
+ // rclcpp::Subscription::SharedPtr MoveJ_75_Cmd;
+ /******************************************MoveJ运动控制订阅器***************************************/
+ rclcpp::Subscription::SharedPtr MoveJ_Cmd;
+ /****************************************MoveL运动控制结果发布器*************************************/
+ rclcpp::Publisher::SharedPtr MoveL_Cmd_Result;
+ rclcpp::Publisher::SharedPtr MoveL_offset_Cmd_Result;
+ /*******************************************MoveL运动控制订阅器*************************************/
+ rclcpp::Subscription::SharedPtr MoveL_Cmd;
+ rclcpp::Subscription::SharedPtr MoveL_offset_Cmd;
+ /****************************************MoveC运动控制结果发布器*************************************/
+ rclcpp::Publisher