Skip to main content
Version: V2.0.5.1

8.6 Waist Joint


8.6.1 Status Interface

1. Waist Joint Status

  • Description: Obtain waist joint status, including current position, speed, current, and temperature. Applicable to Walker Tienkung · Voice & Vision and Walker Tienkung · Embodied Intelligence.

  • Communication type: topic

  • Topic name: /waist/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
    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

8.6.2 Control Interfaces

warning

After stopping the auto-start service for the waist joints (sudo systemctl stop proc_manager.service), you must manually start only the body service (ros2 launch body_control body.launch.py) and must not start the locomotion control service. Only under these conditions will the joint motors be controlled by these interfaces.

When the locomotion control service is running, all joint motors are controlled with higher priority by the locomotion controller.

1. Position Mode

  • Description: Position control interface for the waist joint. Requires desired position, desired speed, and maximum current. Applicable to Walker Tienkung · Voice & Vision and Walker Tienkung · Embodied Intelligence.

  • Communication type: topic

  • Topic name: /waist/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
  • Example commands:

    ros2 topic pub /waist/cmd_pos bodyctrl_msgs/msg/CmdSetMotorPosition "{header: {stamp: {sec: 0, nanosec: 0}, frame_id: ''}, cmds: [{name: 31, pos: -0.3, spd: 0.2, cur: 8.0}]}"

    ros2 topic pub /waist/cmd_pos bodyctrl_msgs/msg/CmdSetMotorPosition "{header: {stamp: {sec: 0, nanosec: 0}, frame_id: ''}, cmds: [{name: 31, pos: 0.0, spd: 0.2, cur: 8.0}]}"

    # When using ros2 topic pub, the header field can be omitted.
    ros2 topic pub /waist/cmd_pos bodyctrl_msgs/msg/CmdSetMotorPosition "{cmds: [{name: 31, pos: -0.3, spd: 0.2, cur: 8.0}]}"

    ros2 topic pub /waist/cmd_pos bodyctrl_msgs/msg/CmdSetMotorPosition "{cmds: [{name: 31, pos: 0.0, spd: 0.2, cur: 8.0}]}"

2. Hybrid Force‑Position Mode

  • Description: Hybrid force‑position control interface for the waist joint. Requires desired position, desired speed, feed‑forward torque, and kp/kd gains. Applicable to Walker Tienkung · Voice & Vision and Walker Tienkung · Embodied Intelligence.

  • Communication type: topic

  • Topic name: /waist/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
  • Example commands:

    ros2 topic pub /waist/cmd_ctrl bodyctrl_msgs/msg/CmdMotorCtrl "{cmds: [{name: 31, kp: 30.0, kd: 10.0, pos: -0.5, spd: 0.0, tor: 0.0}]}"

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

3. Velocity Mode

  • Description: Velocity control interface for the waist joint. Requires desired speed and maximum current. Applicable to Walker Tienkung · Voice & Vision and Walker Tienkung · Embodied Intelligence.

  • Communication type: topic

  • Topic name: /waist/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. Waist Joint Zeroing

  • Description: Zeroing interface for the waist joint. When this interface is called, the current position of the waist motor is set as the zero position. When the D button on the remote controller is used to return to zero, the waist 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 · Voice & Vision and Walker Tienkung · Embodied Intelligence.

  • Communication type: topic

  • Topic name: /waist/cmd_set_zero

  • Message definition: std_msgs::msg::String

  • Message format:

    Send the joint ID as a string to perform zeroing.
    Waist joint ID: 31