跳到主要内容
版本:V2.0.5.x

8.18 强化学习控制接口


注意

请确保本体驱动和强化学习运控都已经启动。手柄向上拨动 E 键,可通过下述 ROS service 切换状态,通过 topic 下发速度指令,遥控器按键和摇杆无效(只有C 有效),E 置中恢复遥控器功能。

8.18.1 运控模式切换

  • 接口名称:/hric/motion/set_motion_mode

  • 类型:ROS service

  • 描述:请求切换运动模式

  • 发布模块:运动控制

  • client 模块:机器人管理

  • 消息类型:hric_msgs/SetMotionMode.srv

    Service msg参数名参数类型是否必填备注
    请求字段walk_mode_requestuint8请求切换的运动模式 1: stop 2: zero 3: stand 4: walk 5: run
    请求字段is_need_swing_armboolwalk 是否需要摆臂
    true: 需要(也就是全身控制模式,当前的运控会控制双臂,后续可继续用动作编号调用接口控制机器人执行动作)
    false: 不需要 (也就是半身控制模式,当前的运控不控制双臂,后续马上调用动作编号调用接口的话无法执行对应的动作,因为当前运控已放弃双臂的控制权)
    注意:如果这个字段传入false时,本接口调用无法切换运动状态,可将这个字段修改为true后再尝试调用本接口切换运动状态
    响应字段sucessbool表示服务调用是否成功
    响应字段error_codeuint32错误码 NONE = 0 UNKNOWN = 400
  • 发布示例:

    cd ros2ws/
    source install/setup.bash

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

    # 回零:
    ros2 service call /hric/motion/set_motion_mode hric_msgs/srv/SetMotionMode "{walk_mode_request: 2, is_need_swing_arm: false}"

    # 站立:
    ros2 service call /hric/motion/set_motion_mode hric_msgs/srv/SetMotionMode "{walk_mode_request: 3, is_need_swing_arm: false}"

    # 原地踏步(回零状态放到地面后,直接调用本接口的话可以从回零状态进入原地踏步状态,但是比较危险,不要这样操作,先进入站立状态,再进入原地踏步):
    ros2 service call /hric/motion/set_motion_mode hric_msgs/srv/SetMotionMode "{walk_mode_request: 4, is_need_swing_arm: false}"

    # 原地跑步:
    ros2 service call /hric/motion/set_motion_mode hric_msgs/srv/SetMotionMode "{walk_mode_request: 5, is_need_swing_arm: false}"

8.18.2 动作编号调用接口

  • 接口名称:/hric/motion/set_motion_number

  • 类型:ROS service

  • 描述:请求调用动作

  • 发布模块:运动控制

  • 订阅模块:机器人管理

  • 消息类型:hric_msgs/SetMotionNumber.srv

    Service msg参数名参数类型是否必填备注
    请求字段is_motionbool仅站立+E上拨状态下有效,置为 true 立即触发动作,false 不会打断动作,true 状态下动作仅触发1次
    请求字段motion_numberint321~5 ,1为挥手
    响应字段sucessbool表示服务调用是否成功
  • 发布示例:

    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 矢量速度控制接口

  • 接口名称:/hric/robot/cmd_vel

  • 类型:topic

  • 描述:发布速度指令 ,控制机器人运动。

  • 发布模块:遥控器

  • 订阅模块:机器人管理

  • 消息类型:geometry_msgs/TwistStamped.msg

    geometry_msgs/msg/TwistStamped #结构如下:
    std_msgs/Header header
    geometry_msgs/Twist twist

    #其中 geometry_msgs/Twist 结构又如下:
    geometry_msgs/Vector3 linear
    geometry_msgs/Vector3 angular

    linear #表示线速度 (单位 m/s),x 表示前后移动,y 表示左右平移,z 表示上下。

    angular #表示角速度 (单位 rad/s),z 表示绕 z 轴转动(左转、右转)。
  • 消息频率:20hz

  • 发布示例:

    cd ros2ws
    source install/setup.bash

    # x方向速度为0.15,也就是速度0.15前进
    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方向速度为0.20,也就是速度0.20前进
    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}}}"

    # 所有线速度角速度均为0.0,也就是原地踏步
    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}}}"

    # 以0.1的角速度左转
    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}}}"

    # 以0.1的角速度右转
    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}}}"

    # 最后为了让机器人再进入原地踏步状态需要再调用一次接口,线速度角速度均传0.0

8.18.4 机器人下肢运动状态发布

  • 接口名称:/hric/motion/status

  • 类型:topic

  • 描述:发布运动控制模块状态和速度

  • 发布模块:运动控制

  • 发布频率:20hz

  • 订阅模块:机器人管理、定位、导航

  • 消息类型:hric_msgs/MotionStatus.msg

    参数名参数类型是否必填备注
    headerHeader时间戳和坐标系
    velocitygeometry_msgs/Twist.msg机器人腰部坐标系速度
    walk_modeuint8行走状态 0: stop, 1: zero, 3: stand, 5: walk, 7: run
    is_console_controlbool是否为遥控器操控 true:导航操控 false:遥控器操纵
    is_swing_armbool是否为 walk 摆臂状态。
    error_codeuint32错误码 NONE = 0 UNKNOWN = 400
  • 消息格式示例:

    {
    "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 机身高度和姿态控制接口

  • 接口名称:/hric/robot/float_base_rpyz_cmd

  • 类型:topic

  • 描述:站立状态下发布腰部rpyz指令,控制机器人姿态。

  • 订阅模块:机器人管理

  • 消息类型:hric_msgs/FloatBaseRPYZ.msg

  • 消息频率:400hz

  • 控制范围:

    roll[-0.2,0.2]rad
    pitch[-0.3,0.4]rad
    yaw[-1.0,1.0]rad
    z[0.6,0.89]m,默认0.89m
  • 发布示例:

    #所有命令执行前都要先执行source命令:
    cd ros2ws/
    source install/setup.bash

    #位置调整到0.88:
    ros2 topic pub /hric/robot/float_base_rpyz_cmd hric_msgs/msg/FloatBaseRPYZ "{ roll: 0.0, pitch: 0.0, yaw: 0, z: 0.88 }"

    # 腰身左右横滚,r正值是右横滚:
    ros2 topic pub /hric/robot/float_base_rpyz_cmd hric_msgs/msg/FloatBaseRPYZ "{ roll: 0.02, pitch: 0.0, yaw: 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, z: 0.88 }"

    # 前后俯仰,p正值是前俯:
    ros2 topic pub /hric/robot/float_base_rpyz_cmd hric_msgs/msg/FloatBaseRPYZ "{ roll: 0.0, pitch: 0.05, yaw: 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, z: 0.88 }"

    # 腰身左右偏转,y正值是左转:
    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 机身高度和姿态状态反馈接口

  • 接口名称:/hric/robot/float_base_rpyz_status

  • 类型:topic

  • 描述:发布站立状态下机器人浮动基座的实际rpyz

  • 发布模块:运动控制

  • 发布频率:400hz

  • 订阅模块:机器人管理、操作

  • 消息类型:hric_msgs/FloatBaseRPYZ.msg

  • 示例命令:

    # 机身高度和姿态状态反馈接口,示例命令
    ros2 topic echo /hric/robot/float_base_rpyz_status
  • 消息格式示例:

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

🆕 8.18.7 动作状态反馈接口

  • 接口名称:/hric/robot/action_status

  • 类型:topic

  • 描述:获取机器人当前动作序号以及当前是否有动作在执行。

  • 发布模块:运动控制

  • 发布频率:400hz

  • 订阅模块:机器人管理、操作

  • 消息类型:hric_msgs/ActionStatus.msg

    # 动作状态反馈接口,示例命令
    ros2 topic echo /hric/robot/action_status
  • 消息格式示例:

    motion_number: 1 
    is_motion: false

🆕 8.18.8 x 方向速度限制状态反馈接口

  • 接口名称:/hric/robot/get_vel_limit

  • 类型:topic

  • 描述:获取机器人当前设置的x方向速度限制状态。

  • 发布模块:运动控制

  • 发布频率:400hz

  • 订阅模块:机器人管理、操作

  • 消息类型:hric_msgs/GetVelLimit.msg

    # x 方向速度限制状态反馈接口,示例命令
    ros2 topic echo /hric/robot/get_vel_limit
  • 消息格式示例:

    x_vel_limit_walk: 1.0 
    x_vel_limit_run: 2.0

🆕 8.18.9 x 方向速度限制设置接口

  • 接口名称:/hric/robot/set_vel_limit

  • 类型:topic

  • 描述:设置机器人的x方向速度限制,单位:m/s,仅在机器在“ZERO”或“STOP”状态响应,重启失效。

  • 发布模块:运动控制

  • 发布频率:400hz

  • 订阅模块:机器人管理、操作

  • 消息类型:hric_msgs/SetVelLimit.msg

  • 示例命令:

    # 所有命令执行前都要先执行source命令:
    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 }"