8.7 Arm Joints
8.7.1 Status Interface
1. Arm Joint Status
-
Description: Obtain the status of both arm joints, including current position, speed, current, and temperature. Applicable to all Walker Tienkung models.
-
Communication type: topic
-
Topic name:
/arm/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 errorerrorfield definition:Value Description 33072 Device offline 33073 Joint position out of range 1 Motor over‑temperature 2 Over‑current 3 Under‑voltage 4 Joint MOS over‑temperature 5 Stall 6 Over‑voltage 7 Phase loss 8 Encoder error
8.7.2 Control Interfaces
The arm joints can be controlled by custom programs under any of the following two conditions:
-
After stopping the auto-start service (sudo systemctl stop proc_manager.service), manually start only the body service (ros2 launch body_control body.launch.py), and do not start the locomotion control service.
-
Ensure that proc_manager.service is running normally, complete the self-check by pressing A, and then use the remote controller to manually enter upper-body (half-body) control mode (G middle + E middle + F down, then long press A, hear a short beep, then the robot is in half-body control mode. Currently supported only on TienKung Walker Wujiang, and requires software version 2.0.5.2 or above).
1. Position Mode
-
Description: Position control interface for arm joints. Requires desired position, desired speed, and maximum current. Applicable to all Walker Tienkung models.
-
Communication type: topic
-
Topic name:
/arm/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 /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. Hybrid Force‑Position Mode
-
Description: Hybrid force‑position control interface for arm joints. Requires desired position, desired speed, feed‑forward torque, and
kp/kdgains. Applicable to all Walker Tienkung models. -
Communication type: topic
-
Topic name:
/arm/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 /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. Velocity Mode
-
Description: Velocity control interface for arm joints. Requires desired speed and maximum current. Applicable to all Walker Tienkung models.
-
Note: Once this message is published, the motor will continue to run at the specified speed until a message with
spd = 0.0is received on the same topic. Use with caution. -
Communication type: topic
-
Topic name:
/arm/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. Current mode
-
Description: The current control interface of the joint requires the supply of the desired current.
-
Communication type: topic
-
Topic name:
/arm/cmd_current -
Message definition:
bodyctrl_msgs::msg::CmdSetMotorCurTor -
Message format:
std_msgs/Header header
SetMotorCurTor[] cmds
#SetMotorCurTor.msg
uint16 name # MotorName
float32 cur_tor
uint8 ctrl_status
5. Arm Joint Zeroing
-
Description: Zeroing interface for arm joints. When this interface is called, the current position of the specified arm motors is set as the zero position. When the D button on the remote controller is used to return to zero, those joints 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 all Walker Tienkung models.
-
Communication type: topic
-
Topic name:
/arm/cmd_set_zero -
Message definition:
std_msgs::msg::String -
Message format:
Send joint IDs as a string to perform zeroing.
Arm joint IDs:
Left arm: 11–17
Right arm: 21–27