8.5 头部关节
8.5.1 状态获取接口
1. 获取头部关节信息
-
说明:获取头部关节的状态信息,其中包含关节的当前位置、速度、电流、温度和告警,适用于天工行者·无疆。
-
控制方式:topic
-
话题名称:
/head/status -
数据定义位置:
bodyctrl_msgs::msg::MotorStatusMsg.msg -
数据格式:
std_msgs/Header header
MotorStatus[] status
MotorStatus # 定义如下:
uint16 name # MotorName
float32 pos # rad
float32 speed # rad
float32 current # A
float32 temperature # Mos温度
uint32 errorerror 错误字段值定义如下:
序号 说明 error = 33072, 设备掉线 error = 33073, 关节位置超限 error = 1, 关节电机过温 error = 2, 过流 error = 3, 电压过低 error = 4, 关节 mos 过温 error = 5, 堵转 error = 6, 电压过高 error = 7, 缺相 error = 8, 编码器错误 ros2 topic echo /head/status
8.5.2 控制接口
注意
需要确保机器人本体服务(body_control)是启动的,头部电机转动的接口才可以正常工作(最简单的方式就是确保 proc_manager 服务是启动的并且已经按过遥控器上的A按钮完成了自检)。
1. 位置模式
-
说明:头部关节的位置控制接口,需要提供期望位置、期望速度、最大电流,适用于天工行者·无疆。
-
控制方式:topic
-
话题名称:
/head/cmd_pos -
数据定义位置:
bodyctrl_msgs::msg::CmdSetMotorPosition.msg -
数据格式:
std_msgs/Header header
SetMotorPosition[] cmds
#SetMotorPosition.msg
uint16 name # MotorName
float32 pos # rad
float32 spd # rad/s
float32 cur # A -
示例命令:
ros2 topic pub /head/cmd_pos bodyctrl_msgs/msg/CmdSetMotorPosition "{cmds: [{name: 1, pos: 0.1, spd: 0.2, cur: 5.0 }]}"
ros2 topic pub /head/cmd_pos bodyctrl_msgs/msg/CmdSetMotorPosition "{cmds: [{name: 1, pos: 0.0, spd: 0.2, cur: 5.0 }]}"
ros2 topic pub /head/cmd_pos bodyctrl_msgs/msg/CmdSetMotorPosition "{cmds: [{name: 2, pos: -0.1, spd: 0.2, cur: 5.0 }]}"
ros2 topic pub /head/cmd_pos bodyctrl_msgs/msg/CmdSetMotorPosition "{cmds: [{name: 2, pos: 0.1, spd: 0.2, cur: 5.0 }]}"
ros2 topic pub /head/cmd_pos bodyctrl_msgs/msg/CmdSetMotorPosition "{cmds: [{name: 3, pos: -0.1, spd: 0.2, cur: 5.0 }]}"
2. 力位混合模式
-
说明:头部关节的力位混合控制接口,需要提供期望位置、期望速度、前馈力矩、kp、kd 系数,适用于天工行者·无疆。
-
控制方式:topic
-
话题名称:
/head/cmd_ctrl -
数据定义位置:
bodyctrl_msgs::msg::CmdMotorCtrl.msg -
数据格式:
std_msgs/Header header
MotorCtrl[] cmds
# MotorCtrl.msg
uint16 name
float32 kp
float32 kd
float32 pos
float32 spd
float32 tor
3. 速度模式
-
说明:关节的速度控制接口,需要提供期望速度、最大电流,适用于天工行者·无疆。
-
控制方式:topic
-
话题名称:
/head/cmd_vel -
数据定义位置:
bodyctrl_msgs::msg::CmdSetMotorSpeed.msg -
数据格式:
std_msgs/Header header
SetMotorSpeed[] cmds
#SetMotorSpeed.msg
uint16 name # MotorName
float32 spd # rad/s
float32 cur # A
4. 关节标零
-
说明:头部关节的标零接口,适用于天工行者·无疆。
-
控制方式:topic
-
话题名称:
/head/cmd_set_zero -
数据定义位置:
std_msgs::msg::String -
数据格式:
以字符串形式发送关节的id实现标零;
头部关节id:1,2,3;