Skip to content

调用机械臂JSON协议

为了方便用户通过ROS1控制机械臂,睿尔曼提供了基于JSON的ROS1功能包,可以通过ROS话题查询和控制机械臂。在实际使用机械臂时,用户可通过以太网口与机械臂建立通信控制机械臂。

控制器错误代码

序号错误代码(16进制)错误内容
10x0000系统正常
20x1001关节通信异常
30x1002目标角度超过限位
40x1003该处不可达,为奇异点
50x1004实时内核通信错误
60x1005关节通信总线错误
70x1006规划层内核错误
80x1007关节超速
90x1008末端接口板无法连接
100x1009超速度限制
110x100A超加速度限制
120x100B关节抱闸未打开
130x100C拖动示教时超速
140x100D机械臂发生碰撞
150x100E无该工作坐标系
160x100F无该工具坐标系
170x1010关节发生掉使能错误
180x1011圆弧规划错误
190x1012自碰撞错误
200x1013碰撞到电子围栏错误(预留)
210x5001预留
220x5002预留
230x5003控制器过温
240x5004预留
250x5005控制器过流
260x5006控制器欠流
270x5007控制器过压
280x5008控制器欠压
290x5009实时内核通讯错误

关节错误代码

序号错误代码(16进制)错误内容
10x0000关节正常
20x0001FOC错误
30x0002过压
40x0004欠压
50x0008过温
60x0010启动失败
70x0020编码器错误
80x0040过流
90x0080软件错误
100x0100温度传感器错误
110x0200位置超限错误
120x0400关节ID非法
130x0800位置跟踪错误
140x1000电流检测错误
150x2000抱闸打开失败
160x4000位置指令阶跃警告
170x8000多圈关节丢圈数
180xF000通信丢帧

设置关节使能状态

参数说明:Joint_Enable.msg 对指定关节进行使能操作

参数类型说明
joint_numuint8对应关节序号,从基座到机械臂夹爪端。六自由度序号依次为1~6,七自由度序号依次为1~7.
statebooltrue-上使能,false-掉使能

使用命令示例:

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

返回命令示例:

json
rostopic echo /rm_driver/Joint_En_State_Result

参数说明:

参数类型说明
std_msgsbooltrue:设置成功;false:设置失败。

切换当前工具坐标系

参数说明:

参数类型说明
std_msgsStringROS自带msg

使用命令示例:

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

返回命令示例:

json
rostopic echo /rm_driver/ChangeTool_State

参数说明:

参数类型说明
std_msgsbooltrue:设置成功;false:设置失败。

切换当前工作坐标系

参数说明:

参数类型说明
std_msgsStringROS自带msg

使用命令示例:

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

返回命令示例:

json
rostopic echo /rm_driver/ChangeWorkFrame_State

参数说明:

参数类型说明
std_msgsbooltrue:设置成功;false:设置失败。

查询当前工作坐标系

参数说明:

参数类型说明
std_msgsEmptyROS自带msg

使用命令示例:

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

返回值查看: 根据rm_driver节点打印信息查看。

获取机械臂关节当前电流

参数说明:

参数类型说明
std_msgsStringROS自带msg

使用命令示例:

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

返回命令示例:

json
rostopic echo /rm_driver/Joint_Current

参数说明:Joint_Current.msg

参数类型说明
joint_currentfloat32[]关节电流(单位:uA)

机械臂运动规划

关节空间运动MoveJ.msg

参数说明:

参数类型说明
jointfloat32[]关节角度,单位:弧度。
speedfloat32速度比例系数,0~1。
trajectory_connectuint8可选参数,代表是否和下一条运动一起规划,0代表立即规划,1代表和下一条轨迹一起规划,当为1时,轨迹不会立即执行。

使用命令示例:

六自由度

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

七自由度

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

返回命令示例:

json
rostopic echo /rm_driver/Plan_State

参数说明:

参数类型说明
std_msgsbooltrue:设置成功;false:设置失败。

笛卡尔空间直线运动MoveL.msg

参数说明:

参数类型说明
Posegeometry_msgs/Pose机械臂位姿,x、y、z坐标(float类型,单位:m)+四元数。
speedfloat32速度比例系数,0~1。
trajectory_connectuint8可选参数,代表是否和下一条运动一起规划,0代表立即规划,1代表和下一条轨迹一起规划,当为1时,轨迹不会立即执行。

使用命令示例:

json
rostopic pub /rm_driver/MoveL_Cmd rm_msgs/MoveL "Pose:
  position:
    x: 0.0
    y: 0.0
    z: 0.0
  orientation:
    x: 0.0
    y: 0.0
    z: 0.0
    w: 0.0
speed: 0.2
trajectory_connect: 0"

返回命令示例:

json
rostopic echo /rm_driver/Plan_State

参数说明:

参数类型说明
std_msgsbooltrue:设置成功;false:设置失败。

笛卡尔空间圆弧运动MoveC.msg

参数说明:

参数类型说明
Mid_Posegeometry_msgs/Pose中间位姿,x、y、z坐标(float类型,单位:m)+四元数。
End_Posegeometry_msgs/Pose终点位姿,x、y、z坐标(float类型,单位:m)+四元数。
speedfloat32速度比例系数,0~1。
trajectory_connectuint8可选参数,代表是否和下一条运动一起规划。0代表立即规划,1代表和下一条轨迹一起规划,当为1时,轨迹不会立即执行。

使用命令示例:

json
rostopic pub /rm_driver/MoveC_Cmd rm_msgs/MoveC "Mid_Pose:
  position:
    x: 0.2949
    y: 0.1377
    z: 0.1048
  orientation:
    x: 0.05
    y: -0.989
    z: -0.1359
    w: 0.0274
End_Pose:
  position:
    x: 0.2417
    y: 0.0
    z: 0.1213
  orientation:
    x: 0.0136
    y: 0.9993
    z: 0.0241
    w: 0.0261
speed: 0.5
trajectory_connect: 0"

返回命令示例:

json
rostopic echo /rm_driver/Plan_State

参数说明:

参数类型说明
std_msgsbooltrue:设置成功;false:设置失败。

关节角度CANFD透传JointPos.msg

参数说明:

参数类型说明
jointfloat32[]关节角度,单位:弧度。
expandfloat32拓展关节,单位:弧度。

使用命令示例: 透传需要连续发送多个连续的点实现,单纯靠以下命令并不能实现功能,当前moveit控制使用了角度透传的控制方式。

json
rostopic pub /rm_driver/JointPos rm_msgs/JointPos "joint: [0, 0, 0, 0, 0, 0] expand: 0.0"

返回参数说明: 成功:无返回值;失败返回:driver终端返回错误码。

位姿CANFD透传CartePos.msg

参数说明:

参数类型说明
Posegeometry_msgs/Pose透传位姿,x、y、z坐标(float类型,单位:m)+四元数。

使用命令示例: 需要是大量(10个以上)位置连续的点,单纯靠以下命令并不能实现功能,以2ms以上的周期持续发布。

json
rostopic pub /rm_driver/MoveP_Fd_Cmd rm_msgs/CartePos 
"Pose:
  position:
    x: 0.0
    y: 0.0
    z: 0.0
  orientation:
    x: 0.0
    y: 0.0
    z: 0.0
    w: 0.0"

返回参数说明: 成功:无返回值;失败返回:driver终端返回错误码。

关节空间规划到目标位姿MoveJ_P.msg

参数说明:

参数类型说明
Mid_Posegeometry_msgs/Pose目标位姿,x、y、z坐标(float类型,单位:m)+四元数。
speedfloat32速度比例系数,0~1。
trajectory_connectuint8可选参数,代表是否和下一条运动一起规划,0代表立即规划,1代表和下一条轨迹一起规划,当为1时,轨迹不会立即执行。

使用命令示例:

json
rostopic pub /rm_driver/MoveJ_P_Cmd rm_msgs/MoveJ_P "Pose:
  position:
    x: 0.0
    y: 0.0
    z: 0.0
  orientation:
    x: 0.0
    y: 0.0
    z: 0.0
    w: 0.0
speed: 0.0
trajectory_connect: 0"

返回命令示例:

json
rostopic echo /rm_driver/Plan_State

机械臂运动配置-步进指令

关节步进Joint_Step.msg

参数说明:

参数类型说明
joint_numuint8要运动的关节。
step_anglefloat32步进角度(单位:角度)。
speedfloat32运动速度。

使用命令示例: 六自由度

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

七自由度

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

返回命令示例:

json
rostopic echo /rm_driver/Plan_State

参数说明:

参数类型说明
std_msgsbooltrue:设置成功;false:设置失败。

机械臂运动配置-运动指令

轨迹急停Stop.msg

参数说明:

参数类型说明
statetooltrue:生效 false:不生效

使用命令示例:

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

返回命令示例:

json
rostopic echo /rm_driver/Set_Arm_Stop_Result

参数说明:

参数类型说明
std_msgsbooltrue:设置成功;false:设置失败。

机械臂运动配置-示教指令类

关节示教Joint_Teach.msg

参数说明:

参数类型说明
teach_jointint16示教控制关节
directionstring关节转动方向 “pos”:正方向,“neg”:反方向
vint16关节转动速度0-100

使用命令示例: 六自由度

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

返回命令示例:

json
rostopic echo /rm_driver/SetJointTeach_Result

参数说明:

参数类型说明
std_msgsbooltrue:设置成功;false:设置失败。

位置示教Pos_Teach.msg

参数说明:

参数类型说明
teach_typestring坐标轴,”x”,”y”,”z”
directionstring示教方向 “pos”:正方向,“neg”:反方向
vint16关节转动速度0-100

使用命令示例:

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

返回命令示例:

json
rostopic echo /rm_driver/SetPosTeach_Result

参数说明:

参数类型说明
std_msgsbooltrue:设置成功;false:设置失败。

姿态示教Ort_Teach.msg

参数说明:

参数类型说明
joint_numstring旋转所绕坐标轴,”rx”,“ry”,“rz”
step_anglestring示教方向 “pos”:正方向,“neg”:反方向
vint16关节转动速度0-100

使用命令示例:

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

返回命令示例:

json
rostopic echo /rm_driver/SetOrtTeach_Result

参数说明:

参数类型说明
std_msgsbooltrue:设置成功;false:设置失败。

示教停止Stop_Teach.msg

参数说明:

参数类型说明
commandstring停止指令“set_stop_teach”,运行以下指令即可

使用命令示例:

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

返回命令示例:

json
rostopic echo /rm_driver/SetStopTeach_Result

参数说明:

参数类型说明
std_msgsbooltrue:设置成功;false:设置失败。

系统配置

控制机械臂上电断电

参数说明:

参数类型说明
std_msgsByte msg1控制机械臂上电 0控制机械臂断电

使用命令示例:

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

返回命令示例:

json
rostopic echo /rm_driver/Set_Arm_Power_Result

参数说明:

参数类型说明
std_msgsbooltrue:设置成功;false:设置失败。

读取软件版本号

参数说明:

参数类型说明
std_msgsByte msg1控制机械臂上电 0控制机械臂断电

使用命令示例:

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

返回命令示例:

json
rostopic echo /rm_driver/Get_Arm_Software_Version_Result

参数说明:

参数类型说明
Arm_Software_Version.msgstringProduct_version #机械臂类型 Plan_version #软件版本号

清除系统错误

参数说明:

参数类型说明
std_msgsEmpty msg/

使用命令示例:

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

返回命令示例:

json
rostopic echo /rm_driver/System_En_State_Result

参数说明:

参数类型说明
std_msgsbooltrue:设置成功;false:设置失败。

查询机械臂状态信息

获取机械臂关节当前电流Joint_Current.msg

参数说明:

参数类型说明
std_msgsEmptyROS自带msg

使用命令示例:

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

返回命令示例:

json
rostopic echo /rm_driver/Joint_Current

参数说明:

参数类型说明
joint_currentfloat32[]关节电流(单位:uA)

查询机械臂关节角度

参数说明:

参数类型说明
std_msgsEmpty msg/

使用命令示例:

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

返回命令示例:

json
rostopic echo /joint_states

参数说明:

参数类型说明
sensor_msgsJointState/

查询机械臂状态(弧度+四元数)GetArmState_Command.msg

参数说明:

参数类型说明
commandstring/

使用命令示例:

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

返回命令示例:

json
rostopic echo /rm_driver/ArmCurrentState

参数说明:ArmState.msg

参数类型说明
jointfloat32[]机械臂弧度信息
Posebool机械臂当前位姿(四元数)
arm_errbool机械臂错误信息
sys_errbool系统错误信息
dofbool机械臂自由度

查询机械臂状态(角度+欧拉角)GetArmState_Command.msg

参数说明:

参数类型说明
commandstring/

使用命令示例:

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

返回命令示例:

json
rostopic echo /rm_driver/Arm_Current_State

参数说明:Arm_Current_State.msg

参数类型说明
jointfloat32[]机械臂角度信息
Posebool机械臂当前位姿(欧拉角)
arm_errbool机械臂错误信息
sys_errbool系统错误信息
dofbool机械臂自由度

控制器IO配置及获取

设置机械臂数字IO输出状态Arm_Digital_Output.msg

参数说明:

参数类型说明
numuint8IO端口号,范围:1~4
statebool“state”:IO状态,1-输出高,0-输出低

使用命令示例:

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

返回命令示例:

json
rostopic echo /rm_driver/Set_DO_State_Result

参数说明:

参数类型说明
std_msgsBooltrue:设置成功;false:设置失败。

获取所有IO输入状态IO_Update.msg

参数说明:

参数类型说明
typeint81查询控制器IO状态; 2查询工具端IO状态

使用命令示例:

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

返回命令示例:

json
rostopic echo /rm_driver/Arm_IO_State

参数说明:Arm_IO_State.msg

参数类型说明
Arm_Digital_Inputnt8[4]1代表高;-1代表为输出状态

工具端IO配置及获取

设置工具端数字IO输出状态Tool_Digital_Output.msg

参数说明:

参数类型说明
numuint8IO端口号,范围:1~4
statebool“state”:IO状态,1-输出高,0-输出低

使用命令示例:

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

返回命令示例:

json
rostopic echo /rm_driver/Set_Tool_DO_State_Result

参数说明:

参数类型说明
std_msgsBooltrue:设置成功;false:设置失败。

获取工具端数字IO状态IO_Update.msg

参数说明:

参数类型说明
typeuint81查询控制器IO状态; 2查询工具端IO状态

使用命令示例:

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

返回命令示例:

json
rostopic echo /rm_driver/Tool_IO_State

参数说明:Tool_IO_State.msg

参数类型说明
Tool_IO_Modebool[2]数字I/O输入/输出状态 0-输入模式,1-输出模式
Tool_IO_Statebool[2]数字I/O电平状态 0-低,1-高

末端夹爪控制(选配)

睿尔曼机械臂末端配备了因时的EG2-4C2夹爪,为了便于用户操作夹爪,机械臂控制器对用户适配了夹爪的ROS控制方式。

设置夹爪持续力控夹取Gripper_Pick.msg

夹爪以设定的速度力控夹取,当受力超过设定力后,停止运动

参数说明:

参数类型说明
speeduint161~1000,代表夹爪开合速度,无量纲
forceuint161~1000,代表夹爪夹持力,最大1.5kg

使用命令示例:

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

返回命令示例:

json
rostopic echo /rm_driver/Set_Gripper_Result

参数说明:

参数类型说明
std_msgsBooltrue:设置成功;false:设置失败。

设置夹爪力控夹取Gripper_Pick.msg

夹爪以设定的速度力控夹取,当受力超过设定力后,停止运动。

参数说明:

参数类型说明
speeduint161~1000,代表夹爪开合速度,无量纲
forceuint161~1000,代表夹爪夹持力,最大1.5kg

使用命令示例:

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

返回命令示例:

json
rostopic echo /rm_driver/Set_Gripper_Result

参数说明:

参数类型说明
std_msgsBooltrue:设置成功;false:设置失败。

夹爪到达指定位置Gripper_Set.msg

设置夹爪到固定位置,夹爪到位置后或者所受力超过阈值后停止。

参数说明:

参数类型说明
positionuint16夹爪目标位置,范围:1~1000,代表夹爪开口度:0~70mm

使用命令示例:

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

返回命令示例:

json
rostopic echo /rm_driver/Set_Gripper_Result

参数说明:

参数类型说明
std_msgsBooltrue:设置成功;false:设置失败。

末端六维力传感器的使用(选配)

睿尔曼RM-65F机械臂末端配备集成式六维力传感器,无需外部走线,用户可直接通过ROS话题对六维力进行操作。

查询六维力数据

参数说明:

参数类型说明
std_msgsEmpty/

使用命令示例:

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

返回命令示例:

json
rostopic echo /rm_driver/GetSixForce     #六维力原始数据
rostopic echo /rm_driver/SixZeroForce    #传感器坐标系下的六维力数据
rostopic echo /rm_driver/WorkZeroForce   #工作坐标系下的传感器数据
rostopic echo /rm_driver/ToolZeroForce   #工具坐标系下的传感器数据

参数说明:Six_Force.msg

参数类型说明
force_Fxfloat32/
force_Fyfloat32/
force_Fzfloat32/
force_Mxfloat32/
force_Myfloat32/
force_Mzfloat32/

清空六维力数据

参数说明:

参数类型说明
std_msgsEmpty/

使用命令示例:

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

返回命令示例:

json
rostopic echo /rm_driver/ClearForceData_Result

参数说明:

参数类型说明
std_msgsBooltrue:设置成功;false:设置失败。

自动设置六维力重心参数

参数说明:

参数类型说明
std_msgsEmpty/

使用命令示例:

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

返回命令示例:

json
rostopic echo /rm_driver/ForceSensorSet_Result

参数说明:

参数类型说明
std_msgsBooltrue:设置成功;false:设置失败。

手动标定六维力数据

参数说明:

Manual_Set_Force_Pose.msg

参数类型说明
pose1string位置1关节角度;
pose2string位置1关节角度;
pose3string位置1关节角度;
pose4string位置1关节角度;
pose5string位置1关节角度;
jointint64[]0.001角度,如90度为90000;

使用命令示例:

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

返回命令示例:

json
rostopic echo /rm_driver/ForceSensorSet_Result

参数说明:

参数类型说明
std_msgsBooltrue:设置成功;false:设置失败。

停止标定力传感器重心

参数说明:

参数类型说明
std_msgsEmpty/

使用命令示例:

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

返回命令示例:

json
rostopic echo /rm_driver/StopSetForceSensor_Result

参数说明:

参数类型说明
std_msgsBooltrue:设置成功;false:设置失败。

拖动示教

拖动示教结束

参数说明:

参数类型说明
std_msgsEmpty/

使用命令示例:

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

返回命令示例:

json
rostopic echo /rm_driver/StopDragTeach_Result

参数说明:

参数类型说明
std_msgsBooltrue:设置成功;false:设置失败。

开启复合拖动示教

参数说明:Start_Multi_Drag_Teach.msg

参数类型说明
modeuint80-电流环模式,1-使用末端六维力只动位置2-使用末端六维力,只动姿态3-使用末端六维力,位置和姿态同时动

使用命令示例:

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

返回命令示例:

json
rostopic echo /rm_driver/StartMultiDragTeach_Result

参数说明:

参数类型说明
std_msgsBooltrue:设置成功;false:设置失败。

力位混合控制Set_Force_Position.msg

参数说明:

参数类型说明
modesensor传感器;0-一维力;1-六维力
modeuint80-工作坐标系力控;1-工具坐标系
directionuint8力控方向0-沿X轴1-沿Y轴2-沿Z轴3-沿RX姿态方向4-沿RY姿态方向5-沿RZ姿态方向

使用命令示例:

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

返回命令示例:

json
rostopic echo /rm_driver/SetForcePosition_Result

参数说明:

参数类型说明
std_msgsBooltrue:设置成功;false:设置失败。

结束力位混合控制

参数说明:

参数类型说明
std_msgsEmpty/

使用命令示例:

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

返回命令示例:

json
rostopic echo /rm_driver/StopForcePostion_Result

参数说明:

参数类型说明
std_msgsBooltrue:设置成功;false:设置失败。

末端五指灵巧手控制(选配)

睿尔曼机械臂末端配备了五指灵巧手,可通过ROS对灵巧手进行设置。

设置灵巧手手势序号Hand_Posture.msg

参数说明:

参数类型说明
posture_numuint16#预先保存在灵巧手内的手势序号,范围:1~40

使用命令示例:

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

返回命令示例:

json
rostopic echo /rm_driver/Set_Hand_Posture_Result

参数说明:

参数类型说明
std_msgsBooltrue:设置成功;false:设置失败。

设置灵巧手动作序列Hand_Seq.msg

参数说明:

参数类型说明
seq_numuint16预先保存在灵巧手内的序列序号,范围:1~40

使用命令示例:

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

返回命令示例:

json
rostopic echo /rm_driver/Set_Hand_Seq_Result

参数说明:

参数类型说明
std_msgsBooltrue:设置成功;false:设置失败。

设置灵巧手各自由度角度Hand_Angle.msg

设置灵巧手角度,灵巧手有 6 个自由度,从 1~6 分别为小拇指,无名指,中指,食指,大拇指弯曲,大拇指旋转。 参数说明:

参数类型说明
hand_angleuint16手指角度数组,范围:0~1000.另外,-1 代表该自由度不执行任何操作,保持当前状态

使用命令示例:

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

返回命令示例:

json
rostopic echo /rm_driver/Set_Hand_Angle_Result

参数说明:

参数类型说明
std_msgsBooltrue:设置成功;false:设置失败。

设置灵巧手速度Hand_Speed.msg

参数说明:

参数类型说明
hand_speeduint16手指速度,范围:1~1000

使用命令示例:

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

返回命令示例:

json
rostopic echo /rm_driver/Set_Hand_Speed_Result

参数说明:

参数类型说明
std_msgsBooltrue:设置成功;false:设置失败。

设置灵巧手力阈值Hand_Force.msg

参数说明:

参数类型说明
hand_Forceuint16手指力,范围:1~1000

使用命令示例:

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

返回命令示例:

json
rostopic echo /rm_driver/Set_Hand_Force_Result

参数说明:

参数类型说明
std_msgsBooltrue:设置成功;false:设置失败。

透传力位混合控制补偿模式

针对睿尔曼带一维力和六维力版本的机械臂,用户除了可直接使用示教器调用底层的力位混合控制模块外,还可以将自定义的轨迹以周期性透传的形式结合底层的力位混合控制算法进行补偿。

开启透传力位混合控制补偿模式

参数说明:

参数类型说明
std_msgsEmpty/

使用命令示例:

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

返回命令示例:

json
rostopic echo /rm_driver/StartForcePositionMove_Result

参数说明:

参数类型说明
std_msgsBooltrue:设置成功;false:设置失败。

透传力位混合控制补偿(位姿)Force_Position_Move_Pose.msg

参数说明:

参数类型说明
Posegeometry_msgs/Pose#四元数信息
sensorgeometry_msgs/Pose#所使用传感器类型,0-一维力,1-六维力
modegeometry_msgs/Pose#模式,0-沿工作坐标系,1-沿工具端坐标系
dirgeometry_msgs/Pose#力控方向,0~5分别代表X/Y/Z/Rx/Ry/Rz,其中一维力类型时默认方向为Z方向
forcegeometry_msgs/Pose#力的大小,精度0.1N或者0.1Nm

使用命令示例:

json
rostopic pub /rm_driver/ForcePositionMovePose_Cmd rm_msgs/Force_Position_Move_Pose "Pose:   position: {x: 0.0, y: 0.0, z: 0.0}   orientation: {x: 0.0, y: 0.0, z: 0.0, w: 0.0} sensor: 1 mode: 0 dir: 0 force: 0"

参数说明:

成功:无返回,失败:报错信息查看rm_driver节点。

透传力位混合控制补偿(弧度)Force_Position_Move_Joint.msg

参数说明:

参数类型说明
jointfloat32[]弧度信息。
sensorgeometry_msgs/Pose所使用传感器类型,0-一维力,1-六维力。
modegeometry_msgs/Pose模式,0-沿工作坐标系,1-沿工具端坐标系。
dirgeometry_msgs/Pose力控方向,0~5分别代表X/Y/Z/Rx/Ry/Rz,其中一维力类型时默认方向为Z方向。
forcegeometry_msgs/Pose力的大小,精度0.1N或者0.1Nm。
dofuint8机械臂自由度信息。

使用命令示例:

json
rostopic pub /rm_driver/ForcePositionMoveJiont_Cmd rm_msgs/Force_Position_Move_Joint "joint: [0, 0, 0, 0, 0, 0] sensor: 0 mode: 0 dir: 0 force: 0 dof: 0"

参数说明:

成功:无返回,失败:报错信息查看rm_driver节点

开启透传力位混合控制补偿模式

参数说明:

参数类型说明
std_msgsEmpty/

使用命令示例:

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

返回命令示例:

json
rostopic echo /rm_driver/StopForcePositionMove_Result

参数说明:

参数类型说明
std_msgsBooltrue:设置成功;false:设置失败。

升降机构

睿尔曼机械臂可集成自主研发升降机构。

升降机构速度开环控制Lift_Speed.msg

参数说明:

参数类型说明
speedint16速度百分比,-100~100Speed < 0:升降机构向下运动Speed > 0:升降机构向上运动Speed = 0:升降机构停止运动。

使用命令示例:

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

返回命令示例:

json
rostopic echo /rm_driver/Set_Lift_Speed_Result

参数说明:

参数类型说明
std_msgsBooltrue:设置成功;false:设置失败。

升降机构位置闭环控制Lift_Height.msg

升降机构运行到指定高度。 参数说明:

参数类型说明
heightuint16目标高度,单位 mm,范围:0~2600。
speeduint16速度百分比,1~100。

使用命令示例:

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

返回命令示例:

json
rostopic echo /rm_driver/Plan_State

参数说明:

参数类型说明
std_msgsBooltrue:设置成功;false:设置失败。

获取升降机构状态

参数说明:

参数类型说明
std_msgsEmpty/

使用命令示例:

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

返回命令示例:

json
rostopic echo /rm_driver/LiftState

参数说明:LiftState.msg

参数类型说明
heightint16当前高度。
currentint16当前电流。
err_flaguint16驱动错误代码。
modebyte当前升降状态0-空闲1-正方向速度运动2-正方向位置运动3-负方向速度运动4-负方向位置运动。

机械臂状态主动上报

设置 UDP 机械臂状态主动上报配置Set_Realtime_Push.msg

参数说明:

参数类型说明
cycleuint16设置广播周期,为5ms的倍数(默认1即1*5=5ms,200Hz)。
portuint16设置广播的端口号(默认8089)。
force_coordinateuint16设置系统外受力数据的坐标系(仅带有力传感器的机械臂支持)。
ipstring设置自定义的上报目标IP 地址(默认192.168.1.10)。

使用命令示例:

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

返回命令示例:

json
rostopic echo /rm_driver/Set_Realtime_Push_Result

参数说明:

参数类型说明
std_msgsBooltrue:设置成功;false:设置失败。

查询 UDP 机械臂状态主动上报配置

参数说明:

参数类型说明
std_msgsEmpty/

使用命令示例:

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

返回命令示例:

json
rostopic echo /rm_driver/Get_Realtime_Push_Result

参数说明:

参数类型说明
std_msgsBooltrue:设置成功;false:设置失败。

UDP机械臂状态主动上报

六维力Six_Force.msg

参数说明:

参数类型说明
force_fxfloat32沿x轴方向受力大小。
force_fyfloat32沿y轴方向受力大小。
force_fzfloat32沿z轴方向受力大小。
force_mxfloat32沿x轴方向转动受力大小。
force_myfloat32沿y轴方向转动受力大小。
force_mzfloat32沿z轴方向转动受力大小。

使用命令示例:

json
rostopic echo /rm_driver/UdpSixForce

机械臂错误std_msgs::msg::UInt16

参数说明:

参数类型说明
datauint16机械臂报错信息。

使用命令示例:

json
rostopic echo /rm_driver/ArmError

系统错误std_msgs::msg::UInt16

参数说明:

参数类型说明
datauint16系统报错信息。

使用命令示例:

json
rostopic echo/rm_driver/SysError

关节错误Joint_Error_Code.msg

参数说明:

参数类型说明
joint_erroruint16[]每个关节报错信息.

使用命令示例:

json
rostopic echo /rm_driver/JointErrorCode

机械臂弧度数据sensor_msgs::msg::JointState

参数说明:

参数类型说明
header.sequint32时间信息,秒。
header.stampclass时间信息,秒。
header.frame_idstring坐标系名称。
namestring[]关节名称。
positionfloat64[]关节弧度信息。
velocityfloat64[]关节速度信息。(暂未使用)
secfloat64[]关节受力信息。(暂未使用)

使用命令示例:

json
rostopic echo /joint_states
功能描述机械臂弧度数据
参数说明sensor_msgs::msg::JointStatebuiltin_interfaces/Time stampint32 sec:时间信息,秒。uint32 nanosec:时间信息,纳秒。  string frame_id:坐标系名称。 string[] name:关节名称。 float64[] position:关节弧度信息。 float64[] velocity:关节速度信息。(暂未使用) float64[] effort:关节受力信息。(暂未使用)
订阅命令rostopic echo /joint_states

位姿信息geometry_msgs::msg::Pose Point

参数说明:

参数类型说明
position.xfloat64机械臂当前坐标信息。
position.yfloat64机械臂当前坐标信息。
position.zfloat64机械臂当前坐标信息。
Quaternion orientation.xfloat64机械臂当前姿态信息。
Quaternion orientation.yfloat64机械臂当前姿态信息。
Quaternion orientation.zfloat64机械臂当前姿态信息。
Quaternion orientation.wfloat64机械臂当前姿态信息。

使用命令示例:

json
rostopic echo /rm_driver/Pose_State

当前六维力传感器系统外受力数据Six_Force.msg

参数说明:

参数类型说明
force_fxfloat32当前传感器沿x轴方向受外力大小。
force_fyfloat32当前传感器沿y轴方向受外力大小。
force_fzfloat32当前传感器沿z轴方向受外力大小。
force_mxfloat32沿x轴方向转动受力大小。
force_myfloat32沿y轴方向转动受力大小。
force_mzfloat32沿z轴方向转动受力大小。

使用命令示例:

json
rostopic echo /rm_driver/UdpSixZeroForce

系统外受力数据参考坐标系std_msgs::UInt16

参数说明:

参数类型说明
force_fxfloat32沿x轴方向受力大小。
datauint16系统外受力数据的坐标系0 为传感器坐标系1 为当前工作坐标系2 为当前工具坐标系该数据会影响一维力和六维力传感器系统外受力数据的参考坐标系。

使用命令示例:

json
rostopic echo /rm_driver/Udp_Coordinate