跳转到内容

7.1 运动控制部分

A3 机器人出厂预搭载了运动控制程序,用户只需发送高层指令即可直接控制机器人行走,无需开发行走等功能的底层控制模型。

智元运控程序内部设计了状态机,在不同状态下会切换不同的模型。状态机如下图所示:

对于各个状态说明如下:

Action 类型 Action 代码 中文名称 详细说明 可调用的控制接口
安全 Action PASSIVE 默认模式 运控启动之后的默认 action
安全 Action DAMPING 阻尼模式 关节也可以认为移动,但是高阻尼,可固定
位控 Action PD_STAND 位控站立模式 机器人位控站立,进入力控模式前关节初始化
力控 Action MOTION 运动模式 该模式下可以行走,做上肢动作,跳舞等
  • /motion/control/arm_joint_command
力控 Action SIT_DOWN 坐下模式 与STAND_UP模式联用
力控 Action STAND_UP 站起模式 与SIT_DOWN模式联用
力控 Action LIE_DOWN 躺下模式 与GET_UP模式联用
力控 Action GET_UP 起身模式 与LIE_DOWN模式联用
力控 Action PACKAGE_LIE_DOWN 包装箱趟入模式 与PACKAGE_GET_UP模式联用
力控 Action PACKAGE_GET_UP 包装箱起身模式 与PACKAGE_LIE_DOWN模式联用

一般情况下不推荐使用程序进行力控之外的切换,仅推荐程序在各个力控状态下切换,其余切换因涉及机器人吊起放下等操作仅可手动操作。

控制类接口一般有 Action 要求,未注明 Action 要求的接口以及查询类接口一般无 Action 限制。

接口名 pb:/aimdk.protocol.MotionControlActionService/SetAction
功能概述 切换运动控制状态机
接口类型 HTTP JSON RPC
URL http://10.42.10.12:56322/rpc/aimdk.protocol.MotionControlActionService/SetAction
入参
{
  "header": {
    "timestamp": {
      "seconds": 1763614279,
      "nanos": 847810000,
      "ms_since_epoch": 1763614279847
    },
    "control_source": "ControlSource_SAFE"
  },
  "command": {
      "action": "MotionControlAction_GET_UP",
      "ext_action": "GET_UP"
  }
}
  • action: 从GetAvailableActions接口获取
  • ext_action: 从GetAvailableActions接口获取
出参
{
  "header": {
    "code": "0",
    "msg": "called successfully.",
    "timestamp": {
      "seconds": "1763643079",
      "nanos": 849593506,
      "ms_since_epoch": "0"
    },
    "trace_id": "",
    "domin": ""
  },
  "state": "CommonState_SUCCESS"
}
  • state: 调用请求状态
示例脚本 examples/mc/S_SetAction.py
备注
  • 异步接口,调用完成不代表切换即完成,需配合 GetAction 接口查询切换是否完成
  • 本接口无 Action 限制
接口名 pb:/aimdk.protocol.MotionControlActionService/GetAction
功能概述 查询运动控制状态机
接口类型 HTTP JSON RPC
URL http://10.42.10.12:56322/rpc/aimdk.protocol.MotionControlActionService/GetAction
入参
{}
出参
{
  "header": {
    "code": "0",
    "msg": "called successfully.",
    "timestamp": {
      "seconds": "1763643026",
      "nanos": 8207141,
      "ms_since_epoch": "0"
    },
    "trace_id": "",
    "domin": ""
  },
  "info": {
    "current_action": "MotionControlAction_PASSIVE",
    "ext_action": "",
    "status": "MotionControlActionStatus_RUNNING"
  }
}
  • current_action: 当前运行的 Action
  • ext_action: 扩展 Action,一般不使用
  • status:Action 状态,一般不使用
示例脚本 example/mc/S_GetAction.py
备注
  • 本接口无 Action 限制

7.1.3 机器人可用Action 查询 RPC 接口

Section titled “7.1.3 机器人可用Action 查询 RPC 接口”
接口名 pb:/aimdk.protocol.MotionControlActionService/GetAvailableActions
功能概述 获取可用动作
接口类型 HTTP JSON RPC
URL http://10.42.10.12:56322/rpc/aimdk.protocol.MotionControlActionService/GetAvailableActions
入参
{ 
    "header": {
      "timestamp": {
        "seconds": "0",
        "nanos": 0,
        "ms_since_epoch": "1744598548952"
      }
    }
}
出参
{
  "header": {
    "code": "0",
    "msg": "called successfully.",
    "timestamp": {
      "seconds": "1775639638",
      "nanos": 585833612,
      "ms_since_epoch": "0"
    },
    "trace_id": "module_mc",
    "domin": ""
  },
  "commands": [
    {
      "action": "MotionControlAction_DAMPING",
      "ext_action": "DAMPING"
    },
    {
      "action": "MotionControlAction_GET_UP",
      "ext_action": "GET_UP"
    },
    {
      "action": "MotionControlAction_LIE_DOWN",
      "ext_action": "LIE_DOWN"
    },
......
  ]
}
  • action:可切换的action名称,
  • ext_action:action代码名,与action出参对应
示例脚本 examples/mc/S_SetAction.py
备注 一般会通过GetAvailableActions接口查询当前可切换action状态,再通过SetAction接口设置action状态
接口名 /motion/control/locomotion_velocity
功能概述 行走控制指令
接口类型 ROS2 Topic
入参
{
  "data": {
    "mode": MotionControl_LocomotionMode_DEFAULT,
    "forward_velocity": 0.1,
    "lateral_velocity": 0.0,
    "angular_velocity": 0.0
  }
}
  • mode: 速度控制模式

    • MotionControl_LocomotionMode_DEFAULT为默认模式
    • MotionControl_LocomotionMode_NAVIGATION为导航模式
  • forward_velocity: 前进速度比例系数,发送比例系数范围-1.0~1.0 ,+为前进,-为后退,由mc计算速度

  • lateral_velocity: 水平速度比例系数,发送比例系数范围-1.0~1.0 ,+为左侧移动,-为右侧移动,由mc计算速度

  • angular_velocity: 旋转速度比例系数,发送比例系数范围-1.0~1.0 ,+为左旋转,-为右旋转,由mc计算速度

示例脚本 examples/mc/walk.py
备注
  • 该消息的 ROS2 类型为 ros2_plugin_proto/msg/RosMsgWrapper,需要 source prebuilt/ros2_plugin_proto_aarch64/share/ros2_plugin_proto/local_setup.bash 后使用。

  • 本接口有调用限制,仅可在 MOTION 状态调用。

7.1.5 手臂控制指令、状态 Topic 接口

Section titled “7.1.5 手臂控制指令、状态 Topic 接口”
接口名 /motion/control/arm_joint_command
功能概述 手臂关节控制指令
接口类型 ROS2 Topic
入参 sensor_msgs::msg::JointState
  • name:关节名称,固定填写为["left_shoulder_pitch_joint","left_shoulder_roll_joint","left_shoulder_yaw_joint", "left_elbow_joint", "left_wrist_roll_joint", "left_wrist_pitch_joint", "left_wrist_yaw_joint", "right_shoulder_pitch_joint", "right_shoulder_roll_joint", "right_shoulder_yaw_joint", "right_elbow_joint", "right_wrist_roll_joint", "right_wrist_pitch_joint", "right_wrist_yaw_joint"]
  • position:关节角度,必须填写 14 个关节的角度值
  • velocity: 无效字段,置为 0.0 即可
  • effort: 无效字段,置为 0.0 即可
示例脚本 examples/mc/arm.py
备注
  • 本接口推荐以 100 Hz 的频率进行调用,调用时需要注意相邻指令间隔不要超过 30ms,确保速度不超过 4 rad/s,并且指令尽量顺滑,否则可能会有抖动,推荐起码使用基本的低通滤波方法:y(k) = (1 - a) * y(k - 1) + a * x(k)。

  • 角度限位如下(单位 rad)

    • left_shoulder_pitch_joint: ±2.967
    • left_shoulder_roll_joint: ±1.588
    • left_shoulder_yaw_joint: ±2.793
    • left_elbow_joint: -1.047 ~ 2.444
    • left_wrist_roll_joint: ±0.576
    • left_wrist_pitch_joint: ±1.623
    • left_wrist_yaw_joint: ±2.793
    • right_shoulder_pitch_joint: ±2.967
    • right_shoulder_roll_joint: ±1.588
    • right_shoulder_yaw_joint: ±2.793
    • right_elbow_joint: -1.047 ~ 2.444
    • right_wrist_roll_joint: ±0.576
    • right_wrist_pitch_joint: ±1.623
    • right_wrist_yaw_joint: ±2.793
  • 本接口有调用限制,仅可在 MOTION 状态下调用

接口名 /motion/control/arm_joint_state
功能概述 手臂关节状态话题
接口类型 ROS2 Topic
出参 sensor_msgs::msg::JointState
  • name: 14 个关节名称
  • position: 14 个关节角度
  • velocity: 14 个关节速度
  • effort: 14 个关节力矩
示例脚本 examples/mc/joint_state.py
备注 本接口无 Action 限制