Skip to main content
Version: V2.0.5.1

8.18 Reinforcement Learning Control Interfaces


warning

Before using these interfaces, ensure that both the body driver and the reinforcement‑learning motion‑control modules are running.
When the E key on the remote controller is pushed up, the robot state can be switched via the ROS Services below, and velocity commands are sent via Topics. In this state, remote controller buttons and sticks are disabled (only the C key remains effective). When the E key is returned to the middle position, remote controller control is restored.

8.18.1 Motion Mode Switching

  • Interface name: /hric/motion/set_motion_mode

  • Type: ROS Service

  • Description: Request to switch motion mode

  • Provider module: Motion control

  • Client module: Robot management

  • Message type: hric_msgs/SetMotionMode.srv

    Service msgField nameTypeRequiredDescription
    Requestwalk_mode_requestuint8YesRequested motion mode: 1: stop, 2: zero, 3: stand, 4: walk, 5: run
    Requestis_need_swing_armboolYesWhether arm swinging is required during walking
    true: Required (i.e., full-body control mode; the current locomotion controller will control both arms, and subsequent actions can still be triggered by calling /hric/motion/set_motion_number service.)
    false: Not required (i.e., upper-body / partial-body control mode; the current locomotion controller does not control the arms, If you immediately call /hric/motion/set_motion_number service, the corresponding action cannot be executed, because the current locomotion controller has already released control of the arms.)
    ResponsesucessboolYesWhether the Service call succeeded
    Responseerror_codeuint32YesError code: NONE = 0, UNKNOWN = 400
  • Example:

    cd ros2ws/
    source install/setup.bash

    # Stiff stop:
    ros2 service call /hric/motion/set_motion_mode hric_msgs/srv/SetMotionMode "{walk_mode_request: 1, is_need_swing_arm: false}"

    # Zero pose:
    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 walking (from zero pose after placing the robot on the ground; for safety, DO NOT switch directly from zero to walk—go via stand first):
    ros2 service call /hric/motion/set_motion_mode hric_msgs/srv/SetMotionMode "{walk_mode_request: 4, is_need_swing_arm: false}"

    # In‑place running:
    ros2 service call /hric/motion/set_motion_mode hric_msgs/srv/SetMotionMode "{walk_mode_request: 5, is_need_swing_arm: false}"

8.18.2 Motion ID Call Interface

  • Interface name: /hric/motion/set_motion_number

  • Type: ROS Service

  • Description: Request to trigger a predefined motion

  • Provider module: Motion control

  • Subscriber module: Robot management

  • Message type: hric_msgs/SetMotionNumber.srv

    Service msgField nameTypeRequiredDescription
    Requestis_motionboolYesValid only in stand + E‑up state. true: trigger an action immediately (one‑shot); false: no trigger
    Requestmotion_numberint32YesMotion ID in [1, 5]; e.g., 1 = wave hand
    ResponsesucessboolYesWhether the Service call succeeded
  • Example:

    cd ros2ws
    source install/setup.bash

    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: true, 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: true, motion_number: 4}"

    ros2 service call /hric/motion/set_motion_number hric_msgs/srv/SetMotionNumber "{is_motion: true, motion_number: 5}"

8.18.3 Vector Velocity Control Interface

  • Interface name: /hric/robot/cmd_vel

  • Type: topic

  • Description: Publish velocity commands to control robot motion.

  • Publisher module: Remote controller

  • Subscriber module: Robot management

  • Message type: geometry_msgs/msg/TwistStamped

    geometry_msgs/msg/TwistStamped  # Structure:
    std_msgs/Header header
    geometry_msgs/Twist twist

    # geometry_msgs/Twist:
    geometry_msgs/Vector3 linear
    geometry_msgs/Vector3 angular

    # linear: linear velocity in m/s
    # x: forward/backward
    # y: lateral (left/right)
    # z: up/down
    #
    # angular: angular velocity in rad/s
    # z: yaw rotation (left/right turn)
  • Message rate: 20 Hz

  • Examples:

    cd ros2ws
    source install/setup.bash

    # Forward at 0.15 m/s in x
    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}}}"

    # Forward at 0.20 m/s in x
    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 zero (in‑place stepping)
    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 with angular velocity 0.1 rad/s
    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 with angular velocity -0.1 rad/s
    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}}}"

    # To return the robot to in‑place stepping, publish cmd_vel again with all zeros.

8.18.4 Lower‑Body Motion Status Publishing

  • Interface name: /hric/motion/status

  • Type: topic

  • Description: Publish motion‑control status and velocity.

  • Publisher module: Motion control

  • Publish rate: 20 Hz

  • Subscriber modules: Robot management, localization, navigation

  • Message type: hric_msgs/MotionStatus.msg

    Field nameTypeRequiredDescription
    headerHeaderYesTimestamp and frame information
    velocitygeometry_msgs/TwistYesVelocity in the waist coordinate frame
    walk_modeuint8YesWalk state: 0: stop, 1: zero, 3: stand, 5: walk, 7: run
    is_console_controlboolYestrue: navigation control; false: remote controller control
    is_swing_armboolYesWhether arm swing is enabled in walk mode
    error_codeuint32YesError code: NONE = 0, UNKNOWN = 400
  • Example message:

    {
    "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
    }

🆕 8.18.5 Base Height and Attitude Control Interface

  • Interface name: /hric/robot/float_base_rpyz_cmd

  • Type: topic

  • Description: In stand mode, publish waist roll‑pitch‑yaw‑z (RPYZ) commands to control robot posture.

  • Subscriber module: Robot management

  • Message type: hric_msgs/FloatBaseRPYZ.msg

  • Message rate: 400 Hz

  • Control ranges:

    roll  [-0.2,  0.2] rad
    pitch [-0.3, 0.4] rad
    yaw [-1.0, 1.0] rad
    z [0.6, 0.89] m (default: 0.89 m)
  • Examples:

    # Run source command before all operations:
    cd ros2ws/
    source install/setup.bash

    # Set height to 0.88 m:
    ros2 topic pub /hric/robot/float_base_rpyz_cmd hric_msgs/msg/FloatBaseRPYZ "{ roll: 0.0, pitch: 0.0, yaw: 0.0, z: 0.88 }"

    # Roll left/right; positive roll tilts to the right:
    ros2 topic pub /hric/robot/float_base_rpyz_cmd hric_msgs/msg/FloatBaseRPYZ "{ roll: 0.02, pitch: 0.0, yaw: 0.0, z: 0.88 }"

    ros2 topic pub /hric/robot/float_base_rpyz_cmd hric_msgs/msg/FloatBaseRPYZ "{ roll: -0.02, pitch: 0.0, yaw: 0.0, z: 0.88 }"

    # Pitch forward/backward; positive pitch tilts forward:
    ros2 topic pub /hric/robot/float_base_rpyz_cmd hric_msgs/msg/FloatBaseRPYZ "{ roll: 0.0, pitch: 0.05, yaw: 0.0, z: 0.88 }"

    ros2 topic pub /hric/robot/float_base_rpyz_cmd hric_msgs/msg/FloatBaseRPYZ "{ roll: 0.0, pitch: -0.05, yaw: 0.0, z: 0.88 }"

    # Yaw left/right; positive yaw rotates to the left:
    ros2 topic pub /hric/robot/float_base_rpyz_cmd hric_msgs/msg/FloatBaseRPYZ "{ roll: 0.0, pitch: 0.0, yaw: 0.03, z: 0.88 }"

    ros2 topic pub /hric/robot/float_base_rpyz_cmd hric_msgs/msg/FloatBaseRPYZ "{ roll: 0.0, pitch: 0.0, yaw: -0.03, z: 0.88 }"

🆕 8.18.6 Base Height and Attitude Status Feedback

  • Interface name: /hric/robot/float_base_rpyz_status

  • Type: topic

  • Description: Publish the actual RPYZ of the floating base in stand mode.

  • Publisher module: Motion control

  • Publish rate: 400 Hz

  • Subscriber modules: Robot management, teleoperation

  • Message type: hric_msgs/FloatBaseRPYZ.msg

  • Example command:

    # Feedback for base height and attitude
    ros2 topic echo /hric/robot/float_base_rpyz_status
  • Example message:

    roll: 4.081035528590296e-05
    pitch: 0.02553808313186995
    yaw: -0.0002636909484863281
    z: 0.8828393155853616

🆕 8.18.7 Action Status Feedback Interface

  • Interface name: /hric/robot/action_status

  • Type: topic

  • Description: Obtain the current motion number and whether an action is being executed.

  • Publisher module: Motion control

  • Publish rate: 400 Hz

  • Subscriber modules: Robot management, teleoperation

  • Message type: hric_msgs/ActionStatus.msg

  • Example command

    # Example command to view action status
    ros2 topic echo /hric/robot/action_status
  • Example message:

    motion_number: 1
    is_motion: false

🆕 8.18.8 X‑Direction Velocity Limit Status Feedback

  • Interface name: /hric/robot/get_vel_limit

  • Type: topic

  • Description: Obtain the current x‑direction velocity limit settings.

  • Publisher module: Motion control

  • Publish rate: 400 Hz

  • Subscriber modules: Robot management, teleoperation

  • Message type: hric_msgs/GetVelLimit.msg

  • Example command

    # Example command to view x‑direction velocity limits
    ros2 topic echo /hric/robot/get_vel_limit
  • Example message:

    x_vel_limit_walk: 1.0
    x_vel_limit_run: 2.0

🆕 8.18.9 X‑Direction Velocity Limit Setting Interface

  • Interface name: /hric/robot/set_vel_limit

  • Type: topic

  • Description: Set x‑direction velocity limits in m/s. The setting only takes effect when the robot is in ZERO or STOP state and is reset after a reboot.

  • Publisher module: Motion control

  • Publish rate: 400 Hz

  • Subscriber modules: Robot management, teleoperation

  • Message type: hric_msgs/SetVelLimit.msg

  • Example:

    # Run source command before all operations:
    cd ros2ws/
    source install/setup.bash

    ros2 topic pub /hric/robot/set_vel_limit hric_msgs/msg/SetVelLimit "{ x_vel_limit_walk: 0.5, x_vel_limit_run: 1.5 }"