Skip to content

运动控制模块

This content is not available in your language yet.

【当前运控有两种模式,传统弯腿行走模式和强化学习直腿行走模式,传统模式不建议使用,自 V1.0 版本起将不再维护传统模式下的接口并将完全移除传统行走模式,请使用强化学习模式及其对应接口】

本文档包含了运动控制模块(Motion Control, MC)包含的话题和服务的相关文档协议,以支持系统的运动控制功能。

本模块在旗舰款和基础款上均位于 x86 开发板上,http 后端监听的端口为 56322。

  1. 在 JOINT_SERVO 后缀的 action 下,包括 RL_LOCOMOTION_ARM_EXT_JOINT_SERVO 和 RL_WHOLE_BODY_EXT_JOINT_SERVO 模式,手臂、头部、手指、腰部会默认被动作播放模块接管,不会执行用户指令。

    • 调用 动作播放模块 的 DisableMotionPlayer 接口即可动态停止 MotionPlayer 服务,使用该接口无需重启 motion_player 服务。

      Terminal window
      curl -i -H 'content-type:application/json' \
      -H 'timeout: 1000' \
      -X POST 'http://192.168.100.100:56444/rpc/aimdk.protocol.MotionCommandService/DisableMotionPlayer' \
      -d '{}'
  2. 调用关节透传接口时,请严格遵守如下要求:

    • 传入的关节角度值必须符合关节限位以及动态范围限制,对应表格列在下方,其中手臂、头部、手指关节限位需要用户自行保证传入的关节角度值在限位范围内。
    • 透传指令接口推荐使用控制频率为 100 Hz,传入的关节指令不允许出现跳变和阶跃,也不允许传入值与当前状态相差过大,请严格计算关节速度和加速度保证关节运动的平滑性。

上肢关节控制的关节限位以及动态范围限制:

关节名称最小角度(rad)最大角度(rad)最大速度绝对值(rad/s)最大加速度绝对值(rad/s^2)
左臂 J1-2.912.913.006.28
左臂 J2-0.461.603.006.28
左臂 J3-2.912.913.006.28
左臂 J4-2.00-0.033.006.28
左臂 J5-2.942.943.006.28
左臂 J6-0.450.453.006.28
左臂 J7-0.350.353.006.28
右臂 J1-2.912.913.006.28
右臂 J2-1.600.463.006.28
右臂 J3-2.912.913.006.28
右臂 J40.032.003.006.28
右臂 J5-2.942.943.006.28
右臂 J6-0.450.453.006.28
右臂 J7-0.350.353.006.28

头部关节限位(仅支持位控):

关节名称最小角度(rad)最大角度(rad)
idx27_head_joint1(摇头)-0.7850.785
idx28_head_joint2(点头)-0.4010.401

灵巧手关节限位(支持位控和力控,左右手关节限位相同):

关节名称最小位置最大位置最小力矩数值最大力矩数值
left_thumb_00200005700
left_thumb_10200005700
left_index0200005700
left_middle0200005700
left_ring0200005700
left_pinky0200005700

腰部动作限位

自由度最小角度/位置(rad / m)最大角度/位置(rad / m)
lift-0.150.00
roll-0.52360.5236
pitch-0.52360.5236
yaw-0.52360.5236

手臂各个关节示意图

运动控制接口调用存在一定的规则,只有特定的状态(Action)下可以调用特定的接口,详细请参考以下 Action 列表(仅列出开放使用的 Action,其余 Action 请勿使用)

序号Action 类型Action 代码中文名称详细说明可调用接口
0安全 ActionDEFAULT默认模式运控启动之后的默认 action
1位控 ActionRL_JOINT_DEFAULT强化位控站立模式上机器人强化位控站立,直腿站立
2位控 ActionPASSIVE_UPPER_BODY_JOINT_SERVO下肢被动上肢伺服模式下肢不使能,手臂可以接收外部关节伺服指令T2
3位控 ActionPASSIVE_UPPER_BODY_PLANNING_MOVE下肢被动上肢 RRT 规划模式下肢不使能,上肢路径规划,rpc接收目标关节角或SE3位置S1
4位控 ActionPASSIVE_UPPER_BODY_COLLISION_ESCAPE下肢被动上肢躲避碰撞模式配合 PASSIVE_UPPER_BODY_PLANNING_MOVE 使用,可在发生碰撞后无法调用规划接口时使用,切到该action后可以自动分开(一般情况下不会使用)
4位控 ActionSIT_DOWN位控坐下模式下肢动作,上肢保持不动,配合椅子实现坐下
5位控 ActionSTAND_UP位控站起模式下肢动作,上肢保持不动,配合椅子实现站起
7位控 ActionMOBILE_PLATFORM_SIT_DOWN移动平台位控坐下模式下肢动作,上肢保持不动,配合坐姿开箱
6位控 ActionMOBILE_PLATFORM_STAND_UP移动平台位控站起模式下肢动作,上肢保持不动,配合坐姿开箱
8力控 ActionRL_LOCOMOTION_DEFAULT强化行走模式强化学习训练的拟人行走模式,走路时手臂会摆动T1
9力控 ActionRL_LOCOMOTION_ARM_EXT_JOINT_SERVO强化行走上肢伺服模式下肢拟人行走或站立,上肢接受外部关节伺服指令,行走或站立时做动作(使用全身控制的强化模型,更具有稳定性)T1、T2
10力控 ActionRL_LOCOMOTION_ARM_EXT_PLANNING_MOVE强化行走上肢 RRT 规划模式下肢站立,上肢路径规划,rpc接收目标关节角或SE3位置S1
11力控 ActionRL_LOCOMOTION_ARM_EXT_COLLISON_ESCAPE强化行走上肢躲避碰撞模式配合 RL_LOCOMOTION_ARM_EXT_PLANNING_MOVE 使用,可在发生碰撞后无法调用规划接口时使用,切到该action后可以自动分开(一般情况下不会使用)
12力控 ActionRL_WHOLE_BODY_EXT_JOINT_SERVO强化行走模式与 RL_LOCOMOTION_ARM_EXT_JOINT_SERVO 类似,额外可控制腰部动作,A2 机器人腰部无实际自由度,腰部动作是通过腿部电机配合实现T1、T2、T3
13力控 ActionRL_WHOLE_BODY_DANCE强化行走模式可运行指定的全身舞蹈动作S2

动作切换状态机: 动作切换状态机

接口调用码话题名话题描述订阅 or 发布消息类型备注通信后端
T1/motion/control/locomotion_velocity下肢控制指令订阅aimdk::protocol::McLocomotionVelocityChannelmode 有两种,一种用于基本遥控行走,填写 LocomotionMode_DEFAULT,对应枚举值 0,另一种用于导航行走,填写 LocomotionMode_NAVIGATION,对应枚举值 1,导航行走对速度指令响应更加灵敏,遥控行走则会更为顺滑;
前进最大速度为 0.8m/s,后退最大速度为 0.3m/s,横移最大速度为 0.25m/s,旋转最大速度为 1.0 rad/s;
不推荐使用后退,不建议使用横移速度,基本行走功能请使用正前进速度结合旋转实现
ros2
T2/motion/control/move_waist腰部控制指令订阅aimdk::protocol::McMoveWaistChannel仅在 RL_WHOLE_BODY_EXT_JOINT_SERVO 模式下可被调用ros2
T2/motion/control/move_waist_lift下蹲指令订阅aimdk::protocol::McMoveWaistLiftChannel限位为 -0.15 到 0.00,仅在 RL_WHOLE_BODY_EXT_JOINT_SERVO 模式下可被调用ros2
T2/motion/control/move_waist_sideways侧身指令订阅aimdk::protocol::McMoveWaistSidewaysChannel限位为 -0.5236 到 0.5236,仅在 RL_WHOLE_BODY_EXT_JOINT_SERVO 模式下可被调用ros2
T2/motion/control/move_waist_pitch弯腰指令订阅aimdk::protocol::McMoveWaistPitchChannel限位为 -0.5236 到 0.5236,仅在 RL_WHOLE_BODY_EXT_JOINT_SERVO 模式下可被调用ros2
T2/motion/control/move_waist_twist转身指令订阅aimdk::protocol::McMoveWaistTwistChannel限位为 -0.5236 到 0.5236,仅在 RL_WHOLE_BODY_EXT_JOINT_SERVO 模式下可被调用ros2
T3/motion/control/arm_joint_command透传手臂控制指令订阅sensor_msgs::msg::JointState仅在 JOINT_SERVO 模式下可被调用,运控不会对手臂关节进行规划,会直接透传到 HAL,只支持位控;
必须一次性传入 14 个关节角度值,前 7 个为左手,后 7 个为右手
ros2
T3/motion/control/neck_joint_command透传头部控制指令订阅sensor_msgs::msg::JointState仅在 JOINT_SERVO 模式下可被调用,头部有两个关节名称分别为 [idx27_head_joint1, idx28_head_joint2],只支持位控ros2
T3/motion/control/hand_joint_command透传手指控制指令订阅sensor_msgs::msg::JointState仅在 JOINT_SERVO 模式下可被调用,JointState 包含左右手指的十二个关节,各个关节名称分别为:
[left_thumb_0, left_thumb_1, left_index, left_middle, left_ring, left_pinky,right_thumb_0, right_thumb_1, right_index, right_middle, right_ring, right_pinky]
手指的力矩放在 effort 里面,范围是 0-5700;手指的位置放在 position,为 0~2000 的数字;手指的控制逻辑是力矩和位置二者满足其一就会停止运动,例如针对某根手指传入 1000 的位置,5700 的力矩,如果没有外物卡住手指,当位置达到 1000 时,力矩不会继续加大,此时力矩会处于一个较小的值,如果外物卡住手指(抓住某物体等),力矩会持续加大到 5700 附近,对应电缸输出 5.7N 的力矩;
ros2
T*/motion/control/arm_joint_state手臂关节状态发布sensor_msgs::msg::JointState手臂关节状态,包含两条手臂各 7 个关节,对于双臂前五个关节来说,position、velocity、effort 字段为有效值,后两个关节只有 position 字段为有效值(数值为等效串联关节的值);
发布频率为 100 hz
ros2
T*/motion/control/neck_joint_state头部关节状态发布sensor_msgs::msg::JointState头部关节状态,包含两个关节,position、velocity、effort 字段为有效值;
发布频率为 100 hz
ros2
T*/motion/control/hand_joint_state手部关节状态发布sensor_msgs::msg::JointState手部关节状态,包含两只灵巧手各 6 个关节,position、effort 字段为有效值,position 范围为 0-2000,effort 范围为 0-5700;
发布频率为 100 hz;
力矩因手指内的连杆机构、转轴、以及弹簧等级机构都会带来一些影响,可能会出现略小于 0 的负值(-1000 以内),为正常现象;
手指受外力影响时同样会出现负值,此时为正常现象
ros2

带星号的接口调用码表示可以在任何 action 下调用。

考虑目前软件日志以及网络资源占用问题,所有 RPC 服务接口建议以 1Hz 及以下的频率调用。

SetAction/GetAction 操作规范:

  • SetAction 接口为异步接口,调用后会立即返回,返回成功不代表 Action 切换完成,需要通过 GetAction 接口轮询确认 Action 切换完成后,方可进行下一步操作
  • GetAction 轮询间隔建议设置为 1 秒(避免高频 RPC 调用),如认为 1s 延迟过大,可设置为 500ms,更小间隔不推荐
接口调用码接口名接口描述请求消息类型答复消息类型备注通信后端
S*pb:/aimdk.protocol.McActionService/SetAction设置 Actionaimdk::protocol::McActionRequestaimdk::protocol::CommonResponsehttp
S*pb:/aimdk.protocol.McActionService/GetAction获取 Actionaimdk::protocol::CommonRequestaimdk::protocol::McActionResponsehttp
S*pb:/aimdk.protocol.McActionService/GetAvailableActions获取可用 Action 列表aimdk::protocol::CommonRequestaimdk::protocol::AvailableActionsResponsehttp
S*pb:/aimdk.protocol.McActionService/GetAvailableCommands获取 Action 切换命令aimdk::protocol::CommonRequestaimdk::protocol::AvailableCommandResponsehttp
S*pb:/aimdk.protocol.McDataService/GetTaskState获取任务状态aimdk::protocol::CommonTaskRequestaimdk::protocol::CommonTaskResponsehttp
S*pb:/aimdk.protocol.McDataService/GetJointState获取关节状态aimdk::protocol::CommonRequestaimdk::protocol::McJointStatesResponse获取所有关节位置、速度和力状态信息(包括上肢和下肢,头和手除外)http
S*pb:/aimdk.protocol.McDataService/GetJointAngle获取关节角度aimdk::protocol::CommonRequestaimdk::protocol::McJointAnglesResponse获取所有关节角度信息(包括上肢和下肢,头和手除外)http
S*pb:/aimdk.protocol.McMotionService/SetHandCommand设置手部命令aimdk::protocol::HandCommandRequestaimdk::protocol::CommonResponse位置的范围是 0-2000,力矩的范围是 0-5700;
手指的控制逻辑是力矩和位置二者满足其一就会停止运动,例如针对某根手指传入 1000 的位置,5700 的力矩,如果没有外物卡住手指,当位置达到 1000 时,力矩不会继续加大,此时力矩会处于一个较小的值,如果外物卡住手指(抓住某物体等),力矩会持续加大到 5700 附近,对应电缸输出 57N 的力矩;
http
S*pb:/aimdk.protocol.McDataService/GetHandState获取灵巧手状态aimdk::protocol::CommonRequestaimdk::protocol::HandStateResponse位置范围为 0-2000,力矩范围为 0-5700;
力矩因手指内的连杆机构、转轴、以及弹簧等级机构都会带来一些影响,可能会出现略小于 0 的负值(-1000 以内),为正常现象;
手指受外力影响时同样会出现负值,此时为正常现象
http
S*pb:/aimdk.protocol.McMotionService/SetNeckCommand设置头部命令aimdk::protocol::NeckCommandRequestaimdk::protocol::CommonResponse旗舰款支持点头和摇头控制,基础版仅支持摇头控制,SetNeckCommand.py脚本包含使用示例,可供参考;
第一个值代表摇头,范围 -0.785 - 0.785,第二个值代表点头,范围 -0.401 - 0.401;
http
S*pb:/aimdk.protocol.McDataService/GetNeckState获取头部状态aimdk::protocol::CommonRequestaimdk::protocol::NeckStateResponsehttp
S1pb:/aimdk.protocol.McMotionService/PlanningMove上肢规划运动aimdk::protocol::PlanningMoveRequestaimdk::protocol::CommonTaskResponse给左臂或右臂发送 SE3 目标点,机器人自行规划路径并执行;
返回的任务 ID,可用于查询任务状态;
有自碰撞检测,对环境的碰撞检测依赖于传感器数据,不能完全保证不与环境发生碰撞;
使用时必须指定需要运动的手臂和对应的位姿
http
S2pb:/aimdk.protocol.McMotionService/GetDanceTypeList获取舞蹈列表aimdk::protocol::CommonRequestaimdk::protocol::McDanceResponse跳舞 action 下获取可跳的舞蹈列表http
S2pb:/aimdk.protocol.McMotionService/SelectDanceType选择舞蹈aimdk::protocol::DanceTypeRequestaimdk::protocol::CommonResponse跳舞 action 下选择要跳的舞蹈http

通过 rpc 发给机器人期望的左臂或者右臂的 SE3 目标点,机器人会根据当前机器人状态进行规划,并执行规划后的运动到达目标点,该接口只有旗舰款可以使用。

  1. 切换到可以使用 PLANNING_MOVE 的 Action

    可以使用上肢规划功能的 Action 有:

    Action 名称描述开机后切换顺序
    PASSIVE_UPPER_BODY_PLANNING_MOVE下肢完全不使能,上肢执行规划运动DEFAULT -> PASSIVE_UPPER_BODY_PLANNING_MOVE
    RL_LOCOMOTION_ARM_EXT_PLANNING_MOVE下肢可以强化行走,上肢执行规划运动DEFAULT -> RL_JOINT_DEFAULT -> RL_LOCOMOTION_ARM_EXT_PLANNING_MOVE
  2. 发送目标位置

    发送方式为 rpc 服务,接口为 pb:/aimdk.protocol.McMotionService/PlanningMove

    发送示例如下:

    import numpy as np
    import json
    import requests
    import time
    from datetime import datetime
    def create_header():
    now = datetime.now()
    header = {
    "timestamp": {
    "seconds": int(now.timestamp()),
    "nanos": now.microsecond * 1000,
    "ms_since_epoch": int(now.timestamp() * 1000),
    },
    "control_source": "ControlSource_MANUAL"
    }
    return header
    def send_json_data(json_data, url):
    json_str = json.dumps(json_data, indent=2)
    print("Sending JSON data:")
    print(json_str)
    print("")
    headers = {'content-type': 'application/json'}
    response = requests.post(url, headers=headers, data=json_str)
    print(f"Response: {response.status_code}")
    print(response.text)
    print("")
    def main():
    url = "http://192.168.100.100:56322/rpc/aimdk.protocol.McMotionService/PlanningMove"
    leftTrl = [0.35, 0.35, 0.25]
    leftQuat = [0.818758, 0.570822, -0.0606913, -0.0106989]
    rightTrl = [0.35, -0.35, 0.25]
    rightQuat = [0.818761, -0.570817, -0.0606912, 0.0106992]
    data = {
    "header": create_header(),
    "group": "McPlanningGroup_LEFT_ARM",
    "mode": "McPlanningMode_DEFAULT",
    "target": {
    "type": "SE3",
    "left": {"position":{"x":leftTrl[0],"y":leftTrl[1],"z":leftTrl[2]},"orientation":{"x":leftQuat[1],"y":leftQuat[2],"z":leftQuat[3],"w":leftQuat[0]}},
    "right":{"position":{"x":rightTrl[0],"y":rightTrl[1],"z":rightTrl[2]},"orientation":{"x":rightQuat[1],"y":rightQuat[2],"z":rightQuat[3],"w":rightQuat[0]}},
    },
    "reference": {
    "joint_position": [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
    },
    }
    send_json_data(data, url)
    if __name__ == "__main__":
    main()

    对于发送的数据,

    • “group”表示本次要运动的手臂,“McPlanningGroup_LEFT_ARM”表示左臂,“McPlanningGroup_RIGHT_ARM”表示右臂
    • “target”表示手臂要运动到的目标点,
      • “position”表示目标点位置
      • “orientation”表示目标点四元数
    • “reference”中的”joint_position”表示参考关节角,一般设为 0 即可,若不全为 0,且长度与机器人手臂关节数一致,即 7 个参考值,机器人会以尽量接近该关节角到达目标点
  3. 查询任务状态(可选)

    参见 get_task_state.sh,调用 rpc 接口后会返回当前执行的任务状态,常见返回值和含义如下:

    序号状态描述
    0CommonState_UNKNOWN任务不存在
    1CommonState_SUCCESS规划运动成功完成
    2CommonState_FAILURE规划运动成功失败
    3CommonState_ABORTED当前状态不能进行规划运动,任务被取消
    4CommonState_PENDING前序任务规划或执行中,当前任务处于等待状态
    5CommonState_RUNNING任务规划或执行中

    若在轮巡查询任务状态时,已经返回了状态量 1,2,3 中任意一个,标志当前任务已经结束,运控将不再保存任务信息,所以如果后续继续查询同一任务,则会返回状态 0,表示任务不存在。

  1. 目标点的描述

    目标点表示在机器人的基座坐标系下,机器人掌心的位置和姿态。相对于 URDF 中的手臂末端有一定的偏移,偏移为:

    手臂末端连杆名称位置偏移(x,y,z)姿态偏移(四元数 w,x,y,z)
    左臂left_arm_link07[-0.1, 0.0, 0.0][0.0, 0.0, 0.70710678, 0.70710678]
    右臂right_arm_link07[ 0.1, 0.0, 0.0][-0.70710678, 0.70710678, 0.0, 1.0]

    这样是为了使左右手臂的末端连杆姿态一致,便于计算。如果要计算掌心的位姿,可以先订阅 ros2 的 tf 话题,然后再计算掌心位置,计算示例如下:

    import numpy as np
    from scipy.spatial.transform import Rotation as R
    def pose_array_to_se3(pose_array, w_first=True):
    trl = pose_array[:3]
    quat = np.array([pose_array[4], pose_array[5], pose_array[6], pose_array[3]]) if w_first else pose_array[3:]
    rotm = R.from_quat(quat).as_matrix()
    se3 = np.eye(4)
    se3[:3, :3] = rotm
    se3[:3, 3] = trl
    return se3
    def se3_to_pose_array(se3, w_first=True):
    rotm = se3[:3, :3]
    trl = se3[:3, 3]
    quat_xyzw = rot.as_quat()
    if w_first:
    quat = np.array([quat_xyzw[3], quat_xyzw[0], quat_xyzw[1], quat_xyzw[2]])
    else:
    quat = quat_xyzw
    return np.concatenate([trl, quat])
    def main():
    left_flange_array = np.array([0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0]) # 改成自己的从tf订阅到的数据
    right_flange_array = np.array([0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0]) # 改成自己的从tf订阅到的数据
    left_flange_tcp_array = np.array([-0.1, 0.0, 0.0, 0.0, 0.0, 0.70710678, 0.70710678])
    right_flange_tcp_array = np.array([0.1, 0.0, 0.0, -0.70710678, 0.70710678, 0.0, 0.0])
    left_flange_se3 = pose_array_to_se3(left_flange_array)
    right_flange_se3 = pose_array_to_se3(right_flange_array)
    left_flange_tcp_se3 = pose_array_to_se3(left_flange_tcp_array)
    right_flange_tcp_se3 = pose_array_to_se3(right_flange_tcp_array)
    left_tcp_se3 = left_flange_se3 @ left_flange_tcp_se3
    right_tcp_se3 = right_flange_se3 @ right_flange_tcp_se3
    left_tcp_array = se3_to_pose_array(left_tcp_se3)
    right_tcp_array = se3_to_pose_array(right_tcp_se3)
  2. 运动范围边界

    基于目前 URDF 的模型参数,对于左臂,1,2 轴的旋转中心点在(-0.03779, 0.191, 0.3421 ),因此,发给左臂的目标点位置至少满足 0.33690<||(x+0.03779, y-0.191, z-0.3421)||<0.60939

    类似的,发给右臂的目标点位置至少满足 0.33690<||(x-0.03779, y+0.191, z-0.3421)||<0.60939

    超过该范围的点位一定不可达,即使目标点位置满足要求,如果姿态不合理也会导致无法到达。

  3. 到点精度

    到点精度主要受三个方面影响:

    来源影响
    规划算法很小,位置最大误差为 0.005m 左右,机器人运动的路径越长,一般误差会越小
    机器硬件较大,位置最大误差一般为 0.02m 左右,受机器人之间的差异影响,可能会有浮动,具体以实测为准
    底座晃动较大,若机器处于下肢力控站立,当手臂运动目标较远,运动幅度较大时,机器人底座可能会移动,甚至踏步,来保持稳定站立;
    此时若机器人只是移动底座,位置最大误差为 0.02m 左右,若机器人为了保持平衡发生踏步,误差则不再可控;
    若机器人下肢不使能,底座固定,则该部分误差可忽略不计
FieldTypeDescription
ixxdouble惯量矩阵在X轴的主惯量 x 轴
iyydoubley 轴
izzdoublez 轴
ixydoublexy 平面
ixzdoublexz 平面
iyzdoubleyz 平面
FieldTypeDescription
massdouble负载质量
mass_centeraimdk::protocol::Vec3负载质心
ToolInertiaaimdk::protocol::ToolInertia负载惯量
FieldTypeDescription
idint32
namestring
config_filestring
payloadaimdk::protocol::McToolPayload
tcpaimdk::protocol::SE3Pose

设置机器人手部控制请求

FieldTypeDescription
headeraimdk::protocol::RequestHeader请求头
dataaimdk::protocol::McToolConfig[]请求数据

设置机器人手部控制请求

FieldTypeDescription
headeraimdk::protocol::RequestHeader请求头
dataaimdk::protocol::McToolConfig[]请求数据
FieldTypeDescription
left_armaimdk::protocol::McToolConfig
right_armaimdk::protocol::McToolConfig

设置机器人手部控制请求

FieldTypeDescription
headeraimdk::protocol::RequestHeader请求头
dataaimdk::protocol::McRobotToolConfig请求数据

设置机器人手部控制请求

FieldTypeDescription
headeraimdk::protocol::RequestHeader请求头
dataaimdk::protocol::McRobotToolConfig请求数据
FieldTypeDescription
left_armaimdk::protocol::McToolPayload
right_armaimdk::protocol::McToolPayload

AimMaster控制源

NameNumberDescription
AimMasterControlSource_AUTO0自主控制
AimMasterControlSource_MANUAL1手动控制

AimMaster控制操纵杆轴

FieldTypeDescription
up_downdouble上下方向摇杆
left_rightdouble左右方向摇杆

AimMaster控制操纵杆按钮

FieldTypeDescription
up_downoneof {bool up} {bool down}摇杆按钮: 上下
left_rightoneof {bool left} {bool right}摇杆按钮: 左右

AimMaster控制

FieldTypeDescription
typeaimdk::protocol::AimMasterControlInfo::Type摇杆类型
dataoneof {AimMasterControlAxis axis} {AimMasterControlButton button}摇杆数据

aimdk::protocol::AimMasterControlInfo::Type

Section titled “aimdk::protocol::AimMasterControlInfo::Type”
NameNumberDescription
Type_UNKNOWN0
Type_AXIS1摇杆类型:轴型,数据类型为 DOUBLE
Type_BUTTON2摇杆类型:按钮型,数据类型为 BOOL

AimMaster控制消息

FieldTypeDescription
modeaimdk::protocol::AimMasterControl::Mode控制模式
leftaimdk::protocol::AimMasterControlInfo摇杆: 左摇杆
rightaimdk::protocol::AimMasterControlInfo摇杆: 右摇杆
NameNumberDescription
Mode_UNKNOWN0
Mode_UPPER_BODY1控制模式:上半身控制
Mode_WHOLE_BODY2控制模式:全身控制
Mode_HEAD3控制模式:头部控制

aimdk::protocol::AimMasterControlSourceRequest

Section titled “aimdk::protocol::AimMasterControlSourceRequest”

与客户端交互的接口结构请求

FieldTypeDescription
headeraimdk::protocol::RequestHeader
targetaimdk::protocol::AimMasterControlSource

aimdk::protocol::AimMasterControlSourceResponse

Section titled “aimdk::protocol::AimMasterControlSourceResponse”

与客户端交互的接口结构响应

FieldTypeDescription
headeraimdk::protocol::ResponseHeader
currentaimdk::protocol::AimMasterControlSource

aimdk::protocol::AimMasterControlCommandRequest

Section titled “aimdk::protocol::AimMasterControlCommandRequest”

AimMaster控制操作命令请求

FieldTypeDescription
headeraimdk::protocol::RequestHeader请求头
commandaimdk::protocol::AimMasterControlCommandRequest::CommandAimMaster控制命令

aimdk::protocol::AimMasterControlCommandRequest::Command

Section titled “aimdk::protocol::AimMasterControlCommandRequest::Command”

AimMaster控制命令

NameNumberDescription
Command_UNKNOWN0未知命令
Command_ROBOT_INIT1姿态初始化命令

VR

FieldTypeDescription
poseaimdk::protocol::SE3PoseVR 位姿
axis_xdouble
axis_ydouble
index_trigdouble
hand_trigdouble
key_onebool
key_twobool

VR控制

FieldTypeDescription
leftaimdk::protocol::QuestProVr
rightaimdk::protocol::QuestProVr
NameNumberDescription
McRemoteControlMode_UNKNOWN0未知模式
McRemoteControlMode_AUTO100自主控制模式
McRemoteControlMode_FULL_BODY200全身控制模式
McRemoteControlMode_UPPER_BODY300上身控制模式

遥控控制操纵杆

FieldTypeDescription
up_downdouble上下方向摇杆 0-1: 上,-1-0: 下
left_rightdouble左右方向摇杆 -1-0: 左,0-1: 右

遥控控制按钮

FieldTypeDescription
upbool上下方向摇杆
downbool
leftbool左右方向摇杆
rightbool

完整的遥控控制消息

FieldTypeDescription
modeaimdk::protocol::McRemoteControlMode遥控控制模式
left_axisaimdk::protocol::McRemoteControlAxis左摇杆
right_buttonaimdk::protocol::McRemoteControlButton右按键

通用游戏手柄

FieldTypeDescription
left_left_rightfloataxis0
left_up_downfloataxis1
ltfloataxis2
right_left_rightfloataxis3
right_up_downfloataxis4
rtfloataxis5
aint32buttion0
bint32buttion1
xint32buttion2
yint32buttion3
lbint32buttion4
rbint32buttion5
backint32buttion6
startint32buttion7
logitechint32buttion8
left_gaint32buttion9
right_gaint32buttion10
hat0_xint32hat0_x
hat0_yint32hat0_y

aimdk::protocol::QuestProVrControllerChannel

Section titled “aimdk::protocol::QuestProVrControllerChannel”

VR控制通道

FieldTypeDescription
headeraimdk::protocol::Header消息头
dataaimdk::protocol::QuestProVrController数据

通用游戏手柄通道

FieldTypeDescription
headeraimdk::protocol::Header消息头
dataaimdk::protocol::UniversalGamepad数据

AimMaster控制通道

FieldTypeDescription
headeraimdk::protocol::Header消息头
dataaimdk::protocol::AimMasterControl数据

遥控器控制通道

FieldTypeDescription
headeraimdk::protocol::Header消息头
dataaimdk::protocol::McRemoteControlInfo数据

aimdk::protocol::ServoMoveGoalReachCondition

Section titled “aimdk::protocol::ServoMoveGoalReachCondition”

伺服运动抵达目标判定

FieldTypeDescription
position_tolerancedouble
orientation_tolerancedouble
keep_timedouble

伺服运动速度

FieldTypeDescription
lineardouble
angulardouble

伺服运动指令

FieldTypeDescription
leftaimdk::protocol::SE3Pose
rightaimdk::protocol::SE3Pose
servo_velocityaimdk::protocol::ServoMoveVelocity
goal_reach_conditionaimdk::protocol::ServoMoveGoalReachCondition

伺服运动姿态结果

FieldTypeDescription
statusaimdk::protocol::ServoMoveResult::Status
NameNumberDescription
SUCCESS0
FAILURE1

aimdk::protocol::GetPlanningMoveTargetResponse

Section titled “aimdk::protocol::GetPlanningMoveTargetResponse”
FieldTypeDescription
headeraimdk::protocol::ResponseHeader
planning_move_requestaimdk::protocol::PlanningMoveRequest
FieldTypeDescription
modeaimdk::protocol::ControlSource

机器人工作状态

NameNumberDescription
McWorkState_DISABLED0
McWorkState_ENABLED1

机器人状态

FieldTypeDescription
timestampuint64
work_stateaimdk::protocol::McWorkState
action_infoaimdk::protocol::McActionInfo
control_infoaimdk::protocol::McControlInfo
is_collisionedbool
sit_stand_stateaimdk::protocol::McSitStandState
is_walkingbool
enable_collisionbool
will_be_collidedbool
enable_future_collisionbool
FieldTypeDescription
headeraimdk::protocol::ResponseHeader响应头
stateaimdk::protocol::McWorkState
FieldTypeDescription
headeraimdk::protocol::ResponseHeader响应头
stateaimdk::protocol::McState

机器人坐下站起状态发布

NameNumberDescription
McSitStandState_DEFAULT0
McSitStandState_SIT_SOON1
McSitStandState_STAND_BACKWARD2
McSitStandState_STAND_FORWARD3
McSitStandState_STAND_SOON4
McSitStandState_SIT_DONE5
McSitStandState_STAND_DONE6
McSitStandState_SITING7
McSitStandState_STANDING8
McSitStandState_SIT_BCK9备用接口
McSitStandState_STAND_BCK10
McSitStandState_MOBILE_PLATFORM_SIT_SOON100
McSitStandState_MOBILE_PLATFORM_STAND_BACKWARD101
McSitStandState_MOBILE_PLATFORM_STAND_FORWARD102
McSitStandState_MOBILE_PLATFORM_STAND_SOON103
McSitStandState_MOBILE_PLATFORM_SIT_DONE104
McSitStandState_MOBILE_PLATFORM_STAND_DONE105

设置工作模式

FieldTypeDescription
headeraimdk::protocol::RequestHeader请求头
modeaimdk::protocol::ControlSource模式

获取工作模式

FieldTypeDescription
headeraimdk::protocol::ResponseHeader响应头
modeaimdk::protocol::ControlSource模式

遥控器控制通道

topic : /mc/base/state

FieldTypeDescription
headeraimdk::protocol::Header消息头
stateaimdk::protocol::McState

MC jaka工作状态

NameNumberDescription
McJakaWorkMode_DEFAULT0
McJakaWorkMode_SERVO1
FieldTypeDescription
headeraimdk::protocol::ResponseHeader响应头
work_modeaimdk::protocol::McJakaWorkMode

原地站立请求

FieldTypeDescription
headeraimdk::protocol::RequestHeader通用请求头
stanceaimdk::protocol::StandRequest::Stance

上肢控制类型:保持不动、回到标准姿态

NameNumberDescription
FREEZE0保持不动
STAND1回到标准姿态
FieldTypeDescription
namestring关节或末端名称
arm_typeuint321 左臂,2 右臂,3 双臂
modeaimdk::protocol::AdjustCommand::PressType按压模式
stepdouble步长
velocitydouble速度
NameNumberDescription
UNKNOWN0
Short1模式:1、点击;2、长按
Long2
FieldTypeDescription
headeraimdk::protocol::RequestHeader
commandaimdk::protocol::AdjustCommand
FieldTypeDescription
namestring末端名称
xdouble
ydouble
zdouble
r_xdouble
r_ydouble
r_zdouble
around_singularity_flagbool靠近奇异位置

aimdk::protocol::AdjustEndPositionsResponse

Section titled “aimdk::protocol::AdjustEndPositionsResponse”
FieldTypeDescription
headeraimdk::protocol::RequestHeader
end_positionsaimdk::protocol::AdjustEndPosition[]

碰撞功能请求消息

FieldTypeDescription
headeraimdk::protocol::RequestHeader
enablebool

碰撞功能状态响应消息

FieldTypeDescription
headeraimdk::protocol::ResponseHeader
CollisionDetectionStatebool

跳舞类型请求

FieldTypeDescription
headeraimdk::protocol::RequestHeader
dance_namestring选择舞蹈名称

跳舞列表获取

FieldTypeDescription
headeraimdk::protocol::ResponseHeader响应头
dance_namestring[]舞蹈名称
dance_model_pathstring[]模型存放路径
dance_data_pathstring[]舞蹈数据存放路径
dance_timedouble[]返回舞蹈运行持续时间

MovJ请求

FieldTypeDescription
headeraimdk::protocol::RequestHeader请求头
groupaimdk::protocol::McPlanningGroup规划组
paramaimdk::protocol::MotionParam运动参数,包括速度、加速度、减速度等
anglesdouble[]关节角度,单位:弧度

MovJ请求

FieldTypeDescription
headeraimdk::protocol::RequestHeader请求头
groupaimdk::protocol::JointControlRequest::JointGroup关节组
cmdsaimdk::protocol::JointControlRequest::Control[]控制指令

aimdk::protocol::JointControlRequest::JointGroup

Section titled “aimdk::protocol::JointControlRequest::JointGroup”
NameNumberDescription
UNKNOWN0
LEFT_ARM1
RIGHT_ARM4
DUAL_ARM7
WAIST_LIFT11
WAIST_PITCH12
HEAD13
FieldTypeDescription
namestring关节名称
modeaimdk::protocol::Control::Mode控制模式
angledouble关节角度,单位:弧度
NameNumberDescription
ABSOLUTE0绝对角度模式
RELATIVE1相对角度模式

运动参数

FieldTypeDescription
velocity_scaledouble
acceleration_scaledouble

aimdk::protocol::McLocomotionVelocityChannel

Section titled “aimdk::protocol::McLocomotionVelocityChannel”

遥控器控制通道

topic : /motion/control/locomotion_velocity

FieldTypeDescription
headeraimdk::protocol::Header消息头
dataaimdk::protocol::LocomotionVelocity数据

人形腰部控制

topic : /motion/control/move_waist

FieldTypeDescription
headeraimdk::protocol::Header消息头
dataaimdk::protocol::WaistMoveValue数据

人形腰部控制—腰部升降

topic : /motion/control/move_waist_lift

FieldTypeDescription
headeraimdk::protocol::Header消息头
waist_lift_valuedouble腰部垂直位移(范围-0.15 ~ +0.04,单位:m)

aimdk::protocol::McMoveWaistSidewaysChannel

Section titled “aimdk::protocol::McMoveWaistSidewaysChannel”

人形腰部控制—腰部左歪右歪

topic : /motion/control/move_waist_sideways

FieldTypeDescription
headeraimdk::protocol::Header消息头
waist_sideways_valuedouble数据

人形腰部控制—腰部前俯后仰

topic : /motion/control/move_waist_pitch

FieldTypeDescription
headeraimdk::protocol::Header消息头
waist_pitch_valuedouble数据

人形腰部控制—腰部扭动

topic : /motion/control/move_waist_twist

FieldTypeDescription
headeraimdk::protocol::Header消息头
waist_twist_valuedouble数据

手部指令通道

topic : /motion/control/hand_command

FieldTypeDescription
headeraimdk::protocol::Header消息头
dataaimdk::protocol::HandCommand手部指令

aimdk::protocol::MotorAckermannJoystickChannel

Section titled “aimdk::protocol::MotorAckermannJoystickChannel”

单摇杆阿克曼

FieldTypeDescription
headeraimdk::protocol::Header消息头
turn_posdoublerad s; + 逆时针, - 顺时针; gamepad_control: turn_range
move_veldoublem s; + 前进行, - 后退; gamepad_control: max_velocity

原地旋转

FieldTypeDescription
headeraimdk::protocol::Header消息头
rot_veldoublerad s; + 逆时针, - 顺时针; gamepad_control: max_w

头部俯仰

FieldTypeDescription
headeraimdk::protocol::Header消息头
head_pitch_veldoublerad s; + 下弯, - 上弯; arm_joint_limits: - name: “head_link”

腰部,弯腰

FieldTypeDescription
headeraimdk::protocol::Header消息头
waist_pitch_veldoublerad s; + 下弯, - 上弯; arm_joint_limits: - name: “idx10_joint_body_link3”

腰部,升降

FieldTypeDescription
headeraimdk::protocol::Header消息头
waist_lift_veldoublem s; + 上升, - 下降; arm_joint_limits: - name: “idx09_joint_body_link2”

双臂控制消息

topic : /motion/control/joint_arm_control

FieldTypeDescription
headeraimdk::protocol::Header消息头,序号和时间戳等信息
flaguint32控制标记位,0是左臂,1是右臂,2是双臂
positionsdouble[]关节角度、速度、加速度,力 一般包含14个元素, 前7个对应左臂,后7个对应右臂 The position of the trajectory. Unit rad
velocitiesdouble[]The velocity of the trajectory. Unit rad/s
accelerationsdouble[]The acceleration of the trajectory. Unit rad/s^2
effortdouble[]The effort of the trajectory. Unit N

直线运动姿态请求

FieldTypeDescription
leftaimdk::protocol::SE3Pose
rightaimdk::protocol::SE3Pose
FieldTypeDescription
headeraimdk::protocol::RequestHeader请求头
groupaimdk::protocol::McPlanningGroup规划组
paramaimdk::protocol::MotionParam运动参数,包括速度、加速度、减速度等
targetaimdk::protocol::LinearMoveTarget目标位姿

运动姿态请求

FieldTypeDescription
headeraimdk::protocol::RequestHeader请求头
typeaimdk::protocol::ArmType机械臂类型
modeaimdk::protocol::MovePoseMode运动模式,绝对位置或者相对位置
paramaimdk::protocol::MotionParam运动参数,包括速度、加速度、减速度等
is_blockbool是否阻塞
poseaimdk::protocol::SE3Pose目标位姿
FieldTypeDescription
leftaimdk::protocol::ScalarTrajectory左臂轨迹
rightaimdk::protocol::ScalarTrajectory右臂轨迹

运动轨迹请求

FieldTypeDescription
headeraimdk::protocol::RequestHeader请求头
targetaimdk::protocol::MoveTrajectoryTarget
FieldTypeDescription
xdouble腰部水平位移(x,y范围会设置成0,不允许调整)
ydouble
zdouble腰部垂直位移(范围-0.15 ~ +0.04,单位:m)
rolldouble腰部旋转角度(RPY的范围都是-30 ~ +30°) (数据传输使用弧度:-0.5236~0.5236,单位:rad)
pitchdouble
yawdouble
NameNumberDescription
LocomotionGaitType_UNKNOWN0步态: 未知,非行走action下应当设置
LocomotionGaitType_STANCE1步态: 站住
LocomotionGaitType_WALK2步态: 正常行走,无速度指令时踏步
LocomotionGaitType_SMART_WALK3步态: 正常行走,无速度指令时站住
LocomotionGaitType_RUN4步态: 跑步
LocomotionGaitType_JUMP5步态: 双脚跳
LocomotionGaitType_HOP6步态: 单脚跳
NameNumberDescription
LocomotionMode_DEFAULT0默认模式 适用于遥控场景
LocomotionMode_NAVIGATION1导航模式 速度响应更快,0.05m/s激活踏步,踏步后500ms内无速度指令会停止踏步,适用于自动行走的导航场景
FieldTypeDescription
modeaimdk::protocol::LocomotionMode速度控制模式
forward_velocitydouble前进速度 单位: m/s 方向: +为前进,-为后退 速度范围: 根据机器人实际速度限制
lateral_velocitydouble侧移动速度 单位: m/s 方向: +为左侧移动,-为右侧移动 速度范围: 根据机器人实际速度限制
angular_velocitydouble旋转速度(角速度) 单位: m/s 方向: +为左旋转,-为右旋转 速度范围: 根据机器人实际速度限制

机器人步态请求

FieldTypeDescription
headeraimdk::protocol::RequestHeader请求头
gaitaimdk::protocol::LocomotionGaitType机器人步态

机器人步态查询返回

FieldTypeDescription
headeraimdk::protocol::ResponseHeader请求头
gaitaimdk::protocol::LocomotionGaitType机器人步态
FieldTypeDescription
namestring
poseaimdk::protocol::SE3Pose
typeaimdk::protocol::PlanningMoveObjectInfo::GeometryType
parent_framestring

aimdk::protocol::PlanningMoveObjectInfo::GeometryType

Section titled “aimdk::protocol::PlanningMoveObjectInfo::GeometryType”
NameNumberDescription
UNKNOWN0
BOX1
CYLINDER2
SPHERE3
FieldTypeDescription
typeaimdk::protocol::PlanningTarget::Type
leftaimdk::protocol::SE3Pose
rightaimdk::protocol::SE3Pose
jointsdouble[]
NameNumberDescription
UNKNOWN0
SE31
JOINT2
EE3
FieldTypeDescription
joint_positiondouble[]参考的关节角度,数量需要与group的关节数量一致
trajectoryaimdk::protocol::ScalarTrajectory
FieldTypeDescription
headeraimdk::protocol::RequestHeader请求头
world_modelaimdk::protocol::McPlanningWorldModel
groupaimdk::protocol::McPlanningGroup规划组
modeaimdk::protocol::McPlanningMode模式
targetaimdk::protocol::PlanningTarget目标位置
targetsaimdk::protocol::PlanningTarget[]多目标位置
referenceaimdk::protocol::PlanningReference参考位置
obj_infoaimdk::protocol::PlanningMoveObjectInfo
paramaimdk::protocol::MotionParam运动参数
FieldTypeDescription
headeraimdk::protocol::RequestHeader请求头
groupaimdk::protocol::McPlanningGroup规划组
targetaimdk::protocol::PlanningTarget目标位置
referenceaimdk::protocol::PlanningReference参考位置

aimdk::protocol::ComputeKinematicsResponse

Section titled “aimdk::protocol::ComputeKinematicsResponse”
FieldTypeDescription
headeraimdk::protocol::ResponseHeader响应头
success_flagbool
ik_resultsaimdk::protocol::ScalarTrajectory规划的轨迹

aimdk::protocol::ActiveMotionControlRequest

Section titled “aimdk::protocol::ActiveMotionControlRequest”

主动动作暂停/继续rpc

FieldTypeDescription
headeraimdk::protocol::RequestHeader请求头
control_flagboolcontrol_flag: 0继续; 1暂停;
FieldTypeDescription
headeraimdk::protocol::ResponseHeader响应头
task_iduint64
stateaimdk::protocol::CommonState
trajectoryaimdk::protocol::ScalarTrajectory规划的轨迹
NameNumberDescription
McAction_DEFAULT0默认模式 运控启动之后的默认action
McAction_PASSIVE_UPPER_BODY_JOINT_SERVO1// 被动模式 // 初始启动需切换到当前action,才能进行后续操作 McAction_PASSIVE_DEFAULT = 1; 下肢被动上肢伺服模式 下肢不使能,手臂可以接收外部关节伺服指令
McAction_PASSIVE_UPPER_BODY_PLANNING_MOVE2下肢被动上肢RRT规划模式 下肢不使能,上肢路径规划,rpc接收目标关节角或SE3位置
McAction_PASSIVE_UPPER_BODY_COLLISON_ESCAPE3下肢被动上肢躲避碰撞模式 下肢不使能,上肢发生碰撞后,规划将失效,切到该模式可以移动到非碰撞位置
McAction_JOINT_DEFAULT100位控站立模式 上肢和下肢关节动作到标准站立位置
McAction_JOINT_FREEZE101位控关节锁定模式 上肢和下肢锁定在当前位置
McAction_STAND_DEFAULT201力控站立模式 下肢力控站立,上肢动作到设定的默认位置,不能控制手臂 此模式允许对机身(腰)进行伺服控制,包括下蹲、弯腰(pitch)、转身(yaw)和左右摇摆(roll)等。
McAction_STAND_ARM_FREEZE202力控站立上肢锁定模式 下肢力控站立,上肢锁定在当前位置
McAction_STAND_ARM_EXT_JOINT_SERVO203力控站立上肢伺服模式 下肢站立,手臂可以接受外部关节伺服指令
McAction_STAND_ARM_EXT_JOINT_TRAJ204力控站立上肢规划模式 用于客户实现上肢路径规划,rpc通信接收关节角度,支持任意数量路径点(建议500以下)
McAction_STAND_ARM_EXT_JOINT_ONLINE_TRAJ205力控站立上肢规划在线模式 用于客户实现上肢路径规划,实时话题接收14个关节角度、速度等,按点位队列顺序执行
McAction_LOCOMOTION_DEFAULT301行走模式 行走时手臂会摆动,支持平地和5°以下斜坡地形全向行走,允许驻坡,禁止外部对上肢进行控制
McAction_LOCOMOTION_ARM_EXT_JOINT_SERVO302下肢行走上肢伺服模式 支持平地地形全向行走,允许外部对上肢进行边走边控制
McAction_RL_JOINT_DEFAULT400强化位控站立模式 机器人强化位控站立,直腿站立
McAction_RL_LOCOMOTION_DEFAULT401强化行走模式 强化学习训练的行走模式,直腿行走
McAction_RL_LOCOMOTION_ARM_EXT_JOINT_SERVO402强化行走上肢伺服模式 下肢可以强化行走,上肢可以接受外部关节伺服指令,边走边做动作
McAction_RL_LOCOMOTION_ARM_EXT_PLANNING_MOVE403强化站立上肢RRT规划模式 下肢力控站立,上肢路径规划,rpc接收目标关节角或SE3位置
McAction_RL_LOCOMOTION_ARM_EXT_COLLISON_ESCAPE404强化站立上肢躲避碰撞模式 下肢力控站立,上肢躲避自碰撞
McAction_RL_WHOLE_BODY_EXT_JOINT_SERVO405带腰全身运控模式
McAction_RL_WHOLE_BODY_DANCE406全身舞蹈模式
McAction_SIT_DOWN501坐下模式 机器人坐下
McAction_STAND_UP502站起模式 机器人站起
McAction_MOBILE_PLATFORM_SIT_DOWN503移动平台位控坐下模式 机器人移动平台坐下
McAction_MOBILE_PLATFORM_STAND_UP504移动平台位控站起模式 机器人移动平台站起
McAction_USE_EXT_CMD5000机器人使用扩展命令
NameNumberDescription
McActionStatus_UNKNOWN0未知状态
McActionStatus_PREPARE100准备中
McActionStatus_RUNNING200运行中
McActionStatus_DONE300完成
FieldTypeDescription
current_actionaimdk::protocol::McAction当前运行的Action
ext_actionstring扩展Action
statusaimdk::protocol::McActionStatusAction状态
FieldTypeDescription
actionaimdk::protocol::McActionAction
ext_actionstring扩展Action

机器人Action命令请求

FieldTypeDescription
headeraimdk::protocol::RequestHeader请求头
commandaimdk::protocol::McActionCommand

机器人Action命令响应

FieldTypeDescription
headeraimdk::protocol::ResponseHeader响应头
infoaimdk::protocol::McActionInfo
FieldTypeDescription
headeraimdk::protocol::ResponseHeader响应头
actionsstring[]
FieldTypeDescription
headeraimdk::protocol::ResponseHeader响应头
commandsaimdk::protocol::McActionCommand[]

获取仿真对象请求

FieldTypeDescription
headeraimdk::protocol::RequestHeader请求头
obj_idstring[]物体id
FieldTypeDescription
headeraimdk::protocol::ResponseHeader响应头
obj_poseaimdk::protocol::SE3Pose[]物体位姿
error_codeint32错误码

臂类型

NameNumberDescription
ArmType_UNKNOWN0未定义
ArmType_LEFT1左臂
ArmType_RIGHT2右臂

运动位置模式: 绝对位置或者相对位置

NameNumberDescription
MovePoseMode_UNKNOWN0未定义
MovePoseMode_ABSOLUTE1绝对位置
MovePoseMode_RELATIVE2相对位置

规划组

NameNumberDescription
McPlanningGroup_UNKNOWN0未知
McPlanningGroup_LEFT_ARM1左臂
McPlanningGroup_LEFT_ARM_WAIST2左臂腰部
McPlanningGroup_LEFT_ARM_WAIST_WHEEL3左臂腰部轮子
McPlanningGroup_RIGHT_ARM4右臂
McPlanningGroup_RIGHT_ARM_WAIST5右臂腰部
McPlanningGroup_RIGHT_ARM_WAIST_WHEEL6右臂腰部轮子
McPlanningGroup_DUAL_ARM7双臂
McPlanningGroup_DUAL_ARM_WAIST8双臂腰部
McPlanningGroup_DUAL_ARM_WAIST_WHEEL9双臂腰部轮子
McPlanningGroup_DUAL_ARM_WAIST_HEAD10双臂腰部头部
McPlanningGroup_WAIST_LIFT11腰部升降
McPlanningGroup_WAIST_PITCH12腰部俯仰
McPlanningGroup_HEAD13头部
NameNumberDescription
McPlanningMode_DEFAULT0默认避障规划。left_target right_target
McPlanningMode_CLOSURE100闭链规划,抓物体后调用,obj_center
McPlanningMode_GRAB200抓取,obj_center
McPlanningMode_PLACE300放置
McPlanningMode_LINEAR_MOVE400线性运动

任务规划世界模型

本类型无字段

任务规划场景

本类型无字段

冲突恢复请求

FieldTypeDescription
headeraimdk::protocol::RequestHeader请求头
typeaimdk::protocol::ArmType手臂类型
  1. 装配任务相关动作指令接口
NameNumberDescription
PrimitiveType_UNKNOWN0
PrimitiveType_SLIDE_SPIRAL1螺旋线搜索
PrimitiveType_SLIDE_SPIRAL_DUAL2双臂螺旋线搜索
PrimitiveType_SLIDE_ZIGZAG3之字形搜索
PrimitiveType_SLIDE_ZIGZAG_DUAL4双臂之字形搜索
PrimitiveType_SLEEVE5力控插拔
PrimitiveType_SLEEVE_DUAL6双臂力控插拔
PrimitiveType_CONTACT7力控接触
PrimitiveType_CONTACT_DUAL8双臂力控接触
NameNumberDescription
PtTriggerConditionType_UNKNOWN0
PtTriggerConditionType_AND1AND
PtTriggerConditionType_OR2OR
PtTriggerConditionType_EQUAL3EQUAL
PtTriggerConditionType_LESS4LESS
PtTriggerConditionType_GREATER5GREATER
PtTriggerConditionType_GREATER_EQUAL6GREATER_EQUAL
PtTriggerConditionType_LESS_EQUAL7LESS_EQUAL

动作指令触发停止条件参数定义

FieldTypeDescription
namestring停止条件名称
datadouble停止条件判定标准值
statedouble停止条件状态值

动作指令触发停止条件

FieldTypeDescription
typeaimdk::protocol::PtTriggerConditionType停止条件类型(多类型:“AND”, “OR”,单类型:“EQUAL”, “LESS”, “GREATER”, “GREATER_EQUAL”, “LESS_EQUAL”)
paramaimdk::protocol::PtTriggerConditionParam停止条件参数

动作指令触发停止条件配置

FieldTypeDescription
typeaimdk::protocol::PtTriggerConditionType停止条件类型(通常用于组合多个 PtTriggerCondition)
conditionsaimdk::protocol::PtTriggerCondition[]停止条件列表

搜索时姿态震荡参数

FieldTypeDescription
rangedouble震动幅度
perioddouble震动周期

e 外力导纳参数

FieldTypeDescription
external_force_axisint32[]力控轴
external_goal_wrenchdouble[]目标力
external_kpdouble[]力增益
external_kvdouble[]阻尼
external_kidouble[]力积分
external_max_integraldouble[]积分限制

e 内力导纳参数

FieldTypeDescription
internal_force_axisint32[]力控轴
internal_goal_wrenchdouble[]目标力
internal_kpdouble[]力增益
internal_kvdouble[]阻尼
internal_kidouble[]力积分
internal_max_integraldouble[]积分限制

e 装配控制任务

FieldTypeDescription
external_admittanceaimdk::protocol::ExternalForceCtrlParam外力导纳
internal_admittanceaimdk::protocol::InternalForceCtrlParam[]内力导纳列表

力控搜索通用参数

FieldTypeDescription
contact_axisdouble[]接触轴
search_axisdouble[]搜索轴
contact_forcedouble接触力
start_densitydouble起始搜索轨迹密度
time_factorint32控制搜索轨迹快慢,越小轨迹运动速度越快
random_factordouble噪声叠加幅度控制系数
start_search_immediatelybool是否进入立即开始搜索

螺旋线搜索参数

FieldTypeDescription
search_radiusdouble搜索最大半径
wiggleaimdk::protocol::PtWiggleParam搜索时姿态震荡参数
commonaimdk::protocol::PtSlideCommonParam力控搜索通用参数
pt_slide_triggeraimdk::protocol::PtTriggerConfig动作指令触发停止条件
pt_control_paramaimdk::protocol::ExternalForceCtrlParam控制参数

双臂螺旋线搜索参数

FieldTypeDescription
search_radiusdouble搜索最大半径
wiggleaimdk::protocol::PtWiggleParam搜索时姿态震荡参数
commonaimdk::protocol::PtSlideCommonParam力控搜索通用参数
pt_dual_slide_triggeraimdk::protocol::PtTriggerConfig触发条件
pt_control_paramaimdk::protocol::AssemblyCtrlParam控制参数

之字形搜索参数

FieldTypeDescription
lengthdouble搜索区域长度
heightdouble搜索区域宽度
wiggleaimdk::protocol::PtWiggleParam搜索时姿态震荡参数
commonaimdk::protocol::PtSlideCommonParam力控搜索通用参数
pt_slide_triggeraimdk::protocol::PtTriggerConfig动作指令触发停止条件
pt_control_paramaimdk::protocol::ExternalForceCtrlParam控制参数

双臂之字形搜索参数

FieldTypeDescription
lengthdouble搜索区域长度
heightdouble搜索区域宽度
wiggleaimdk::protocol::PtWiggleParam搜索时姿态震荡参数
commonaimdk::protocol::PtSlideCommonParam力控搜索通用参数
pt_dual_slide_triggeraimdk::protocol::PtTriggerConfig动作指令触发停止条件
pt_control_paramaimdk::protocol::AssemblyCtrlParam控制参数

力控插拔及触发停止条件

FieldTypeDescription
insert_dirdouble[]插入方向 (tcp)
alignment_dirint32[]哪些方向需要开柔顺
max_contact_forcedouble最大力限制保护
insert_veldouble插入速度
deadband_scaledouble力控柔顺时调整死区系数
pt_sleeve_triggeraimdk::protocol::PtTriggerConfig触发条件
pt_control_paramaimdk::protocol::ExternalForceCtrlParam控制参数

双臂力控插拔及触发停止条件

FieldTypeDescription
insert_dirdouble[]插入方向 (tcp)
alignment_dirint32[]哪些方向需要开柔顺
max_contact_forcedouble最大力限制保护
insert_veldouble插入速度
deadband_scaledouble力控柔顺时调整死区系数
pt_dual_sleeve_triggeraimdk::protocol::PtTriggerConfig触发条件
pt_control_paramaimdk::protocol::AssemblyCtrlParam控制参数

力控接触及触发停止条件

FieldTypeDescription
refer_coordinatestring接触参考坐标系 (tcp/world)
freespace_veldouble自由空间内速度
contact_dirdouble[]接触方向
max_contact_forcedouble最大接触力保护
pt_contact_triggeraimdk::protocol::PtTriggerConfig力控接触通用参数

力控动作指令

FieldTypeDescription
namestring力控动作名称:未使用(不建议使用)
typeaimdk::protocol::PrimitiveType力控动作类型
paramgoogle.protobuf.Any力控动作参数 以下参数均为动作参数,具体取值请参考上面的定义 - PtSlideSpiralParam: 螺旋线搜索参数 - PtSlideZigzagParam: 之字形搜索参数 - PtSleeveParam: 柔顺参数 - PtContactParam: 接触参数 - PtDualSlideSpiralParam: 双臂螺旋线搜索参数 - PtDualSlideZigzagParam: 双臂之字形搜索参数 - PtDualSleeveParam: 双臂柔顺参数

力控动作组

FieldTypeDescription
actionsaimdk::protocol::PrimitiveAction[]
FieldTypeDescription
headeraimdk::protocol::RequestHeader
taskoneof {ForcePrimitive left} {ForcePrimitive right} {ForcePrimitive dual}

运控公共状态响应

FieldTypeDescription
headeraimdk::protocol::ResponseHeader响应头
statesaimdk::protocol::JointState[]关节状态,包括角度和速度、扭矩

运控公共状态响应

FieldTypeDescription
headeraimdk::protocol::ResponseHeader响应头
commandsaimdk::protocol::JointCommand[]关节指令

运控公共参数响应

FieldTypeDescription
headeraimdk::protocol::ResponseHeader响应头
paramsaimdk::protocol::JointParam[]关节参数
FieldTypeDescription
namestring关节名称
positiondouble关节角度

运控公共角度响应

FieldTypeDescription
headeraimdk::protocol::ResponseHeader响应头
jointsaimdk::protocol::McJointPosition[]关节角度,单位:弧度 or m

臂状态

FieldTypeDescription
error_codebool错误码
inposbool位置
enablebool是否可用
protective_stopbool碰撞保护
on_soft_limitbool软限位

臂状态请求

FieldTypeDescription
headeraimdk::protocol::RequestHeader请求头
arm_typeaimdk::protocol::ArmType臂类型

臂状态请求响应

FieldTypeDescription
headeraimdk::protocol::ResponseHeader响应头
arm_statusaimdk::protocol::ArmStatus臂状态信息

获得Tcp位置响应

FieldTypeDescription
headeraimdk::protocol::ResponseHeader响应头
tcp_positionaimdk::protocol::SE3Pose[]TCP位姿

运动GPT状态

NameNumberDescription
MotionGPTState_WAIT_MGPT_COMMAND0等待命令
MotionGPTState_MOVING_TO_FIRST_POINT1移动到第一个点
MotionGPTState_ARRIVED_FIRST_POINT2到达第一个点
MotionGPTState_MOVING_TO_FINAL_POINT3移动到最后一个点
MotionGPTState_ARRIVED_FINAL_POINT4到达最后一个点
MotionGPTState_MGPT_FINISHED5已完成

运动GPT状态请求

FieldTypeDescription
headeraimdk::protocol::RequestHeader请求头
stateaimdk::protocol::MotionGPTState状态

运动GPT状态响应

FieldTypeDescription
headeraimdk::protocol::ResponseHeader响应头 请求头
stateaimdk::protocol::MotionGPTState状态

aimdk::protocol::McPlanningGroupAvailableResponse

Section titled “aimdk::protocol::McPlanningGroupAvailableResponse”

任务规划组可用状态响应

FieldTypeDescription
headeraimdk::protocol::ResponseHeader响应头
groupsaimdk::protocol::McPlanningGroup[]可用组

逆向运动请求

FieldTypeDescription
headeraimdk::protocol::RequestHeader请求头
typeaimdk::protocol::ArmType手臂类型 手臂类型
ref_anglesdouble[]关节角度,单位:弧度 or m
cartesian_poseaimdk::protocol::SE3Pose目标位姿

逆向运动响应

FieldTypeDescription
headeraimdk::protocol::ResponseHeader响应头
typeaimdk::protocol::ArmType手臂类型
anglesdouble[]关节角度,单位:弧度 or m
error_codeint32错误码
error_msgstring错误信息

前向运动请求

FieldTypeDescription
headeraimdk::protocol::RequestHeader请求头
typeaimdk::protocol::ArmType手臂类型
anglesdouble[]关节角度,单位:弧度 or m

前向运动响应

FieldTypeDescription
headeraimdk::protocol::ResponseHeader响应头
typeaimdk::protocol::ArmType手臂类型
cartesian_poseaimdk::protocol::SE3Pose目标位姿
error_codeint32错误码
error_msgstring错误信息

足部运动学消息

topic : /mc/kinematics/foot_kine

FieldTypeDescription
headeraimdk::protocol::Header消息头
dataaimdk::protocol::FootKinematicsData足部运动学数据

逆向运动请求

FieldTypeDescription
typeaimdk::protocol::FootKinematics::Type
poseaimdk::protocol::SE3Posebody frame, xyz
velocityaimdk::protocol::SE3Velocitybody frame, m/s
contact_phasedouble0.0~1.0 : 0:swing; 1:contact
NameNumberDescription
UNKNOWN0
LEFT1
RIGHT2
FieldTypeDescription
footaimdk::protocol::FootKinematics[]一般情况下,存在2个数据,一个是左脚,一个是右脚

运动控制模块接口提供了多种运动控制功能,为此提供了一些示例脚本,位于 AimDK 包中 examples/mc 路径下,可以参考这些脚本进行运动控制相关的开发,一些脚本的说明如下:

名称功能备注
SetAction.py设置 Action需按照状态机切换机器人动作,具体见前述 Action 状态机
actions.py获取当前 Action获取当前 Action
GetAvailableCommands.py获取 action 切换命令接口获取所有 action 切换命令,可用于设置 action
GetJointState.py获取关节状态获取机器人所有关节状态信息(不含头和手),包括名称、位置、速度等
GetJointAngle.py获取关节角度获取机器人所有关节角度信息(不含头和手),包括名称、位置
GetHandState.py获取手部关节状态获取机器人手部状态信息,包括名称、位置、速度等
GetNeckState.py获取头部关节状态获取机器人头部状态信息,包括名称、位置、速度等
GetTaskState.py查询任务状态查询执行运动的任务状态,需要传入 task id,主要用于 PlanningMove 任务查询
SetHandCommand.py设置手势设置机器人双手的手指位置和扭矩
SetNeckCommand.py设置头部关节设置机器人头部关节的位置
PlanningMove.py规划运动规划运动,需要传入目标位置和参考位置
walk.py机器人运动指令设置机器人前向、侧向和旋转运动指令
arm.py透传手臂控制不会对手臂关节进行规划,会直接透传(需要进行数据平滑处理);需要传入 14 个关节角度值,前 7 个为左手,后 7 个为右手
hand.py透传手指头控制左右手指的十二个关节,拇指有两个关节
neck.py透传头部控制头部有两个关节
joint_state.py订阅上肢关节数据可通过修改话题名获取脖子和手部以及手臂关节数据
move_waist.py腰部运动腰部运动,包括腰部升降、腰部俯仰、腰部扭动、腰部侧歪
move_waist_lift.py腰部升降腰部升降,范围为 -0.15 ~ +0.00,单位为 m
SelectDanceType.py选择舞蹈选择要跳的舞蹈