Skip to main content
Version: V2.0.5.1

8.5 Head Joints


8.5.1 Status Interface

1. Head Joint Status

  • Description: Obtain the status of head joints, including current position, speed, current, and temperature. Applicable to Walker Tienkung · Embodied Intelligence.

  • Communication type: topic

  • Topic name: /head/status

  • Message definition: bodyctrl_msgs::msg::MotorStatusMsg

  • Message format:

    std_msgs/Header header
    MotorStatus[] status

    # MotorStatus definition:
    uint16 name # MotorName
    float32 pos # rad
    float32 speed # rad
    float32 current # A
    float32 temperature # MOS temperature
    uint32 error

    error field definition:

    ValueDescription
    33072Device offline
    33073Joint position out of range
    1Motor over‑temperature
    2Over‑current
    3Under‑voltage
    4Joint MOS over‑temperature
    5Stall
    6Over‑voltage
    7Phase loss
    8Encoder error
    ros2 topic echo /head/status

8.5.2 Control Interfaces

warning

You need to ensure that the robot body service (body_control) is running; only then will the head motor rotation interface work properly. (The simplest way is to make sure the proc_manager service is started and that you have pressed the A button on the remote controller to complete the self-check.)

1. Position Mode

  • Description: Position control interface for head joints. Requires desired position, desired speed, and maximum current. Applicable to Walker Tienkung · Embodied Intelligence.

  • Communication type: topic

  • Topic name: /head/cmd_pos

  • Message definition: bodyctrl_msgs::msg::CmdSetMotorPosition

  • Message format:

    std_msgs/Header header
    SetMotorPosition[] cmds

    # SetMotorPosition.msg
    uint16 name # MotorName
    float32 pos # rad
    float32 spd # rad/s
    float32 cur # A
  • Command examples:

    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. Hybrid Force‑Position Mode

  • Description: Hybrid force‑position control interface for head joints. Requires desired position, desired speed, feed‑forward torque, and kp/kd gains. Applicable to Walker Tienkung · Embodied Intelligence.

  • Communication type: topic

  • Topic name: /head/cmd_ctrl

  • Message definition: bodyctrl_msgs::msg::CmdMotorCtrl

  • Message format:

    std_msgs/Header header
    MotorCtrl[] cmds

    # MotorCtrl.msg
    uint16 name
    float32 kp
    float32 kd
    float32 pos
    float32 spd
    float32 tor

3. Velocity Mode

  • Description: Velocity control interface for joints. Requires desired speed and maximum current. Applicable to Walker Tienkung · Embodied Intelligence.

  • Communication type: topic

  • Topic name: /head/cmd_vel

  • Message definition: bodyctrl_msgs::msg::CmdSetMotorSpeed

  • Message format:

    std_msgs/Header header
    SetMotorSpeed[] cmds

    # SetMotorSpeed.msg
    uint16 name # MotorName
    float32 spd # rad/s
    float32 cur # A

4. Head Joint Zeroing

  • Description: Zeroing interface for head joints. When this interface is called, the current position of the specified head motor is set as the zero position. When the D button on the remote controller is used to return to zero, the joint will move to this position. Typically used together with a dedicated zeroing tool; use with caution if such a tool is not available. Applicable to Walker Tienkung · Embodied Intelligence.

  • Communication type: topic

  • Topic name: /head/cmd_set_zero

  • Message definition: std_msgs::msg::String

  • Message format:

    Send the joint ID as a string to perform zeroing.
    Head joint IDs: 1, 2, 3