8.19 Reinforcement Learning Control Interface
Please ensure that both the main body drive and reinforcement learning motion control are started. Toggle the E key on the handle upward to switch states via the following ROS service, issue velocity commands via topic. Remote control buttons and joysticks will be invalid (only C is valid). Return E to the center position to restore remote control functionality.
8.19.1 Motion Control Mode Switching
-
Interface Name:
/hric/motion/set_motion_mode -
Type: ROS service
-
Description: Request to switch motion modes
-
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: 1: stop,2: zero,3: stand,4: walk,5: runis_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 -
Publishing Examples:
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.19.2 Action Number Call Interface
-
Interface Name:
/hric/motion/set_motion_number -
Type: ROS service
-
Description: Request to call an action
-
Publishing Module: Motion Control
-
Subscribing Module: Robot Management
-
Message Type:
hric_msgs/SetMotionNumber.srvService msg Parameter Name Parameter Type Required Remarks Request Fields is_motion bool Yes Only valid in stand + F upward position, set to true to trigger action immediately, false won't interrupt action, will keep looping current action in true state motion_number int32 Yes 0~4, other values will be set to 0 (wave hand) Response Fields sucess bool Yes Indicates whether the service call was successful -
Publishing Examples:
cd ros2ws
source install/setup.bash
# Perform actions (5 groups of actions, the previous command executes the action, the next command cancels execution, if you don't execute the next command, it will keep repeating the action):
ros2 service call /hric/motion/set_motion_number hric_msgs/srv/SetMotionNumber "{is_motion: true, motion_number: 0}"
ros2 service call /hric/motion/set_motion_number hric_msgs/srv/SetMotionNumber "{is_motion: false, motion_number: 0}"
ros2 service call /hric/motion/set_motion_number hric_msgs/srv/SetMotionNumber "{is_motion: true, motion_number: 1}"
ros2 service call /hric/motion/set_motion_number hric_msgs/srv/SetMotionNumber "{is_motion: false, motion_number: 1}"
ros2 service call /hric/motion/set_motion_number hric_msgs/srv/SetMotionNumber "{is_motion: true, motion_number: 2}"
ros2 service call /hric/motion/set_motion_number hric_msgs/srv/SetMotionNumber "{is_motion: false, motion_number: 2}"
ros2 service call /hric/motion/set_motion_number hric_msgs/srv/SetMotionNumber "{is_motion: true, motion_number: 3}"
ros2 service call /hric/motion/set_motion_number hric_msgs/srv/SetMotionNumber "{is_motion: false, motion_number: 3}"
ros2 service call /hric/motion/set_motion_number hric_msgs/srv/SetMotionNumber "{is_motion: true, motion_number: 4}"
ros2 service call /hric/motion/set_motion_number hric_msgs/srv/SetMotionNumber "{is_motion: false, motion_number: 4}"
8.19.3 Vector Velocity Control Interface
-
Interface Name:
/hric/robot/cmd_vel -
Type:
topic -
Description: Publish velocity commands to control robot movement.
-
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, z represents up/down.
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.19.4 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,3:stand,5:walk,7:runis_console_control bool Yes Whether it is remote control operation, true: navigation operation, false: remote control 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": 1,
"error_code": 0,
}