8.18 Traditional Method Control Interface
Please ensure that both the main body drive and traditional motion control are started. Toggle the H key on the handle to the right to switch states via the following ROS service, issue velocity commands via topic. Remote control buttons and joysticks will be invalid (only the C key 'freeze' is valid). Return H to the center position to restore remote control functionality.
8.18.1 Motion Mode Switching
-
Interface Name:
/hric/motion/set_motion_mode -
Type:
service -
Description: Request to switch motion modes, applicable to all Tienkung Walker series.
-
Publishing Module: Motion Control
-
Client Module: Robot Management
-
Message Type:
hric_msgs/SetMotionMode.srvService msg Parameter Name Parameter Type Required Remarks Request Fields walk_mode_request uint8 Yes # Requested motion mode to switch, 0: start1: stop2: zero3: stand4: walkis_need_swing_arm bool Yes Whether arm swinging is needed for walk, true: needed, false: not needed (due to operation version, locomotion does not control arms, so setting true or false both work) Response Fields sucess bool Yes Indicates whether the service call was successful error_code uint32 Yes Error code NONE=0 UNKNOWN=400 -
Example Commands
cd ros2ws
source install/setup.bash
# Freeze:
ros2 service call /hric/motion/set_motion_mode hric_msgs/srv/SetMotionMode "{walk_mode_request: 1, is_need_swing_arm: false}"
# Zero Position:
ros2 service call /hric/motion/set_motion_mode hric_msgs/srv/SetMotionMode "{walk_mode_request: 2, is_need_swing_arm: false}"
# Stand:
ros2 service call /hric/motion/set_motion_mode hric_msgs/srv/SetMotionMode "{walk_mode_request: 3, is_need_swing_arm: false}"
# In-place Step (After zero position is placed on the ground, directly calling this interface can enter in-place step state from zero state, but it is dangerous, do not operate this way. First enter stand state, then enter in-place step):
ros2 service call /hric/motion/set_motion_mode hric_msgs/srv/SetMotionMode "{walk_mode_request: 4, is_need_swing_arm: false}"
# In-place Run:
ros2 service call /hric/motion/set_motion_mode hric_msgs/srv/SetMotionMode "{walk_mode_request: 5, is_need_swing_arm: false}"
8.18.2 Vector Velocity Control Interface
-
Interface Name:
/hric/robot/cmd_vel -
Type:
topic -
Description: Publish velocity commands to control robot movement, applicable to all Tienkung Walker series.
-
Publishing Module: Remote Control
-
Subscribing Module: Robot Management
-
Message Type:
geometry_msgs/TwistStamped.msggeometry_msgs/msg/TwistStamped structure is as follows:
std_msgs/Header header
geometry_msgs/Twist twist
Among them, geometry_msgs/Twist structure is as follows:
geometry_msgs/Vector3 linear
geometry_msgs/Vector3 angular
linear represents linear velocity (unit m/s), x represents forward/backward movement, y represents left/right translation.
angular represents angular velocity (unit rad/s), z represents rotation around the z-axis (left turn, right turn). -
Message Frequency: 20hz
-
Publishing Examples:
cd ros2ws
source install/setup.bash
# x-direction velocity is 0.15, i.e., move forward at 0.15 speed
ros2 topic pub /hric/robot/cmd_vel geometry_msgs/msg/TwistStamped "{header: {frame_id: 'base_link' }, twist: {linear: {x: 0.15, y: 0.0, z: 0.0}, angular: {x: 0.0, y: 0.0, z: 0.0}}}"
# x-direction velocity is 0.20, i.e., move forward at 0.20 speed
ros2 topic pub /hric/robot/cmd_vel geometry_msgs/msg/TwistStamped "{header: {frame_id: 'base_link' }, twist: {linear: {x: 0.20, y: 0.0, z: 0.0}, angular: {x: 0.0, y: 0.0, z: 0.0}}}"
# All linear and angular velocities are 0.0, i.e., in-place step
ros2 topic pub /hric/robot/cmd_vel geometry_msgs/msg/TwistStamped "{header: {frame_id: 'base_link' }, twist: {linear: {x: 0.0, y: 0.0, z: 0.0}, angular: {x: 0.0, y: 0.0, z: 0.0}}}"
# Turn left at 0.1 angular velocity
ros2 topic pub /hric/robot/cmd_vel geometry_msgs/msg/TwistStamped "{header: {frame_id: 'base_link' }, twist: {linear: {x: 0.0, y: 0.0, z: 0.0}, angular: {x: 0.0, y: 0.0, z: 0.1}}}"
# Turn right at 0.1 angular velocity
ros2 topic pub /hric/robot/cmd_vel geometry_msgs/msg/TwistStamped "{header: {frame_id: 'base_link' }, twist: {linear: {x: 0.0, y: 0.0, z: 0.0}, angular: {x: 0.0, y: 0.0, z: -0.1}}}"
# Finally, to make the robot enter in-place step state again, call the interface once more, passing 0.0 for both linear and angular velocities
8.18.3 Robot Lower Limb Motion Status Publication
-
Interface Name:
/hric/motion/status -
Type:
topic -
Description: Publish motion control module status and velocity
-
Publishing Module: Motion Control
-
Publishing Frequency: 20hz
-
Subscribing Module: Robot Management, Positioning, Navigation
-
Message Type:
hric_msgs/MotionStatus.msgParameter Name Parameter Type Required Remarks header Header Yes Timestamp and coordinate system velocity geometry_msgs/Twist.msg Yes Robot waist coordinate system velocity walk_mode uint8 Yes Walking state, 0:stop,1:zero,2:zero_2_stand,3:stand,4:stand_2_walk,5:walk,6:startis_console_control bool Yes Whether it is remote control operation, true: remote control operation false: navigation operation is_swing_arm bool Yes Whether it is walk arm swing state. error_code uint32 Yes Error code NONE=0 UNKNOWN=400 -
Message Format Example:
{
"header": {
"seq": 1,
"stamp": {
"secs": 1622548800,
"nsecs": 0
},
"frame_id": ""
},
"velocity": {
"linear": {
"x": 1.0,
"y": 0.0,
"z": 0.0
},
"angular": {
"x": 0.0,
"y": 0.0,
"z": 0.0
}
},
"walk_mode": 6,
"error_code": 0
}