Motion Control
TITA controls robot movement services and provides machine status data to users through a ROS2 plugin. This plugin offers the necessary API interfaces, converting control information into ROS message.
Note
First, you need to open the API calling interface vim /usr/share/tita_bringup/params/default_param.yaml change locomotion_manager’s control_motion_mode value to 1 0: controller control moded 1: api control mode 2: autonomy control mode
Stand
Function Overview: Enter the standing mode to control the standing posture.
Topic: command/controller/lock
MsgType: tita_motion_msgs/msg/ControllerCommandLock
Code Example: ros2 topic pub /tita2303895/command/controller/lock tita_motion_msgs/msg/ControllerCommandLock "{lock_state: 2}" -1
Height
Function Overview: Control the robot’s postural elevation through programming.
Topic: locomotion/move_target/height
MsgType: tita_motion_msgs/msg/Height
Code Example: ros2 topic pub -r 30 /{ns}/locomotion/move_target/height tita_motion_msgs/msg/Height "{height: 0.2}"
Value Range: height:max 0.30 min 0.09
Note
Sending frequency ≥ 30 HZ.
Pitch and Roll
Function Overview: Pitch and roll commands need to be sent simultaneously; Currently Control: linear.x forward and backward velocity, angular.z left and right turn velocity, linear.y roll angular velocity, angular.y pitch angular velocity; Not Used (set as empty): linear.z and angular.x.
Topic: command/controller/api/move
MsgType: geometry_msgs/msg/TwistStamped
Code Example: ros2 topic pub /{ns}/command/controller/api/move geometry_msgs/msg/TwistStamped "{ twist: {linear: {x: 0.5, y: 0.0, z: 0.0}, angular: {x: 0.0, y: 0.0, z: 0.0}}}"
Value Range:
linear x min : ±0.82. max ±1.52
twist.angular.z min: ±0.42 max ±1.42
height min: 0.09 max: 0.30
linear.y: ±0.942(0.3 * PI)
angular.y: ±0.2
Note
Sending frequency ≥ 30 HZ.
Jump
Function Overview: This API is used to control the robot’s jumping action.
Topic: command/controller/jump
Msg Type: tita_motion_msgs/msg/ControllerCommandJump
Code Example: ros2 topic pub /{ns}/command/controller/jump tita_motion_msgs/msg/ControllerCommandJump "{jump_state: 2}" -1
Value Range:
jump_state = JUMP (0x02)
IDLE 0x00 /CHARGE 0x01 /JUMP 0x02
Machine Status
Function Overview: This interface is for monitoring the current posture of the machine, allowing you to know whether the current machine status and feedback information match.
Topic: locomotion/locomotion_status
Msg Type: tita_motion_msgs::msg::LocomotionStatus
Code Example: ros2 topic echo /{ns}/locomotion/locomotion_status
Value Range:
DIE = 0x00
INIT = 0x01
TRANSFORM_UP =0x02
STAND = 0x03
TRANSFORM_DOWN = 0x04
CRASH = 0x05
SUSPENDING = 0x06
JUMP = 0x07