跳到主要内容
版本:V2.0.5.x

8.7 双臂关节


8.7.1 状态获取接口

1. 获取双臂关节信息

  • 说明:获取双臂关节的状态信息,其中包含关节的当前位置、速度、电流、温度和告警,适用于天工行者全系列。

  • 控制方式:topic

  • 话题名称:/arm/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 error

    error 错误字段值定义如下:

    序号说明
    error = 33072,设备掉线
    error = 33073,关节位置超限
    error = 1,关节电机过温
    error = 2,过流
    error = 3,电压过低
    error = 4,关节 mos 过温
    error = 5,堵转
    error = 6,电压过高
    error = 7,缺相
    error = 8,编码器错误

8.7.2 控制接口

注意

双臂关节如下两种情况下都可受自定义程序控制:

  1. 关闭自启动服务后(sudo systemctl stop proc_manager.service),然后仅手动启动本体服务(ros2 launch body_control body.launch.py),不能启动运控服务。
  2. 确保 proc_manager.service 正常运行,按A自检后,按正常流程落地后,再用遥控器手动进入半身控制模式(G 中 + E 中 + F 下,然后长按A,听到短滴一声,即进入半身控制模式,目前仅支持天工行者无疆且要求软件版本2.0.5.2以上)。

1. 位置模式

  • 说明:关节的位置控制接口,需要提供期望位置、期望速度、最大电流,适用于天工行者全系列。

  • 控制方式:topic

  • 话题名称:/arm/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 # 电流
  • 示例命令:

    ros2 topic pub /arm/cmd_pos bodyctrl_msgs/msg/CmdSetMotorPosition "{cmds: [{name: 12, pos: 0.3, spd: 0.2, cur: 8.0 }]}"
    ros2 topic pub /arm/cmd_pos bodyctrl_msgs/msg/CmdSetMotorPosition "{cmds: [{name: 22, pos: -0.3, spd: 0.2, cur: 8.0 }]}"

2. 力位混合模式

  • 说明:关节的力位混合控制接口,需要提供期望位置、期望速度、前馈力矩、kp、kd系数,适用于天工行者全系列。

  • 控制方式:topic

  • 话题名称:/arm/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
  • 示例命令:

    ros2 topic pub /arm/cmd_ctrl bodyctrl_msgs/msg/CmdMotorCtrl "{cmds: [{name: 13, kp: 30.0, kd: 10.0, pos: 0.2, spd: 0.0, tor: 0.0}]}"

    ros2 topic pub /arm/cmd_ctrl bodyctrl_msgs/msg/CmdMotorCtrl "{cmds: [{name: 23, kp: 30.0, kd: 10.0, pos: 0.2, spd: 0.0, tor: 0.0}]}"

3. 速度模式

  • 说明:关节的速度控制接口,需要提供期望速度、最大电流,适用于天工行者全系列。注意这个消息一旦发布,该电机将以该速度持续转动,直到该话题收到一个spd为0.0的消息,因此需要谨慎使用。

  • 控制方式:topic

  • 话题名称:/arm/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

  • 话题名称:/arm/cmd_current

  • 数据定义位置:bodyctrl_msgs::msg::CmdSetMotorCurTor.msg

  • 数据格式:

    std_msgs/Header header
    SetMotorCurTor[] cmds

    #SetMotorCurTor.msg
    uint16 name # MotorName
    float32 cur_tor
    uint8 ctrl_status # 当前只⽀持电流模式

5. 手臂关节标零

  • 说明:双臂关节的标零接口,调用此接口时会将手臂指定的电机当前位置设置为零位,需要配合标零工具使用,没有标零工具时请谨慎使用,适用于天工行者全系列。

  • 控制方式:topic

  • 话题名称:/arm/cmd_set_zero

  • 数据定义位置:std_msgs::msg::String

  • 数据格式:

    以字符串形式发送关节的id实现标零;
    双臂关节id:
    左臂:11---17,
    右臂:21---27;