运控接口
- 关节控制:该节点控制R1 Pro躯干和手臂的每个关节。
- 手臂姿态控制:该节点控制手臂运动至目标末端执行器(ee)的坐标系。
- 夹爪控制:该节点控制末端执行器夹爪运动至目标位置。
- 躯干速度控制:该节点控制躯干运动至目标浮动基座坐标系。
- 底盘控制:该节点使用矢量控制来控制R1 Pro底盘,允许同时发送x、y和w三个方向的速度命令。
- 姿态估计:该节点接收来自HDAS的关节角反馈,并计算出对应三个坐标系的反馈。
关节控制
R1 Pro关节控制节点负责控制手臂的每个关节,总共有14个关节。可通过以下命令启动:
source {your_download_path}/install/setup.bash
ros2 launch mobiman r1_pro_jointTrackerdemo.py
该文件将启动 r1_pro_jointTracker_demo_node,该节点是负责控制每个关节的主要节点。接口信息如下所示::
值得注意的是:上述启动方法中,disable_torso这个参数默认为true。所以无法通过上诉方法启动的node来控制torso的关节运动。
| 话题名称 | I/O | 描述 | 消息类型 |
|---|---|---|---|
| /hdas/feedback_arm_left | Input | 左臂关节反馈 | sensor_msgs::msg::JointState |
| /hdas/feedback_arm_right | Input | 右臂关节反馈 | sensor_msgs::msg::JointState |
| /hdas/feedback_torso | Input | 躯干关节反馈 | sensor_msgs::msg::JointState |
| /motion_target/target_joint_state_arm_left | Input | 左臂各关节的目标位置 | sensor_msgs::msg::JointState |
| /motion_target/target_joint_state_arm_right | Input | 右臂各关节的目标位置 | sensor_msgs::msg::JointState |
| /motion_target/target_joint_state_torso | Input | 躯干各关节目标位置 | sensor_msgs::msg::JointState |
| /motion_control/control_arm_left | Output | 左臂电机控制 | hdas_msg::msg::MotorControl |
| /motion_control/control_arm_right | Output | 右臂电机控制 | hdas_msg::msg::MotorControl |
针对以上话题的具体字段及其详细描述如下表所示:
| 话题名称 | 字段 | 描述 |
|---|---|---|
| /hdas/feedback_arm_left | - | 请参考手臂驱动接口 |
| /hdas/feedback_arm_right | - | 请参考手臂驱动接口 |
| /hdas/feedback_torso | - | 请参考躯干驱动接口 |
| /motion_target/target_joint_state_arm_left /motion_target/target_joint_state_arm_right |
position | 这是一个包含7个元素的向量,代表每个关节的7个目标位置。 |
| velocity | 这是一个包含7个元素的向量,代表每个关节在运动过程中的最大速度。最大速度如下:{3, 3,3, 3, 5, 5, 5}。 加速度和加加速度限制设置为速度限制的1.5倍。 | |
| /motion_target/target_joint_state_torso | position | 这是一个包含四个元素的向量,代表每个关节的四个目标位置。 |
| velocity | 这是一个包含四个元素的向量,代表每个关节在运动过程中的速度。最大速度如下:{1.5, 1.5, 1.5, 1.5}。 加速度和加加速度限制设置为速度限制的1.5倍。 | |
| /motion_control/control_arm_left | - | 请参考手臂驱动接口 |
| /motion_control/control_arm_right | - | 请参考手臂驱动接口 |
带Torso的关节控制
R1 Pro关节控制节点负责控制R1 Pro躯干和手臂的每个关节,总共有18个关节。可通过以下命令启动:
source {your_download_path}/install/setup.bash
source /opt/galaxea/galaxeaKey/keys.env
ros2 launch mobiman r1_pro_jointTrackerdemo.py disable_torso:=false
该文件将启动 r1_pro_jointTracker_demo_node,该节点是负责控制每个关节的主要节点。接口信息如下所示::
请注意:上述启动方法中,disable_torso这个参数被设置为false。然后通过存放再/opt/galaxea/galaxeaKey/keys.env的密钥配对,即可实现torso的关节控制。该节点的node和上述没有差异,仅增加了一个躯干topic。
| 话题名称 | I/O | 描述 | 消息类型 |
|---|---|---|---|
| /motion_target/target_joint_state_torso | Input | 躯干各关节目标位置 | sensor_msgs::msg::JointState |
针对以上话题的具体字段及其详细描述如下表所示:
| 话题名称 | 字段 | 描述 |
|---|---|---|
| /motion_target/target_joint_state_torso | position | 这是一个包含四个元素的向量,代表每个关节的四个目标位置。 |
| velocity | 这是一个包含四个元素的向量,代表每个关节在运动过程中的速度。最大速度如下:{1.5, 1.5, 1.5, 1.5}。 加速度和加加速度限制设置为速度限制的1.5倍。 |
手臂姿态控制
R1 Pro手臂姿态 控制是一个用于控制手臂移动到目标末端执行器(ee)坐标帧的ROS软件包。它主要包括两个launch文件,分别对应 左臂的姿态控制和右臂的姿态控制, 可以通过以下命令启动:
source {your_download_path}/install/setup.bash
ros2 launch mobiman r1_pro_left_arm_relaxed_ik_launch.py
ros2 launch mobiman r1_pro_right_arm_relaxed_ik_launch.py
请注意:
-
由于姿态控制是根据目标ee姿态不断解算出目标关节角下发给
/motion_target/target_joint_state_arm_left和/motion_target/target_joint_state_arm_right,所以当双臂姿态控制器启动后,需要执行以下命令启动关节控制节点。source {your_download_path}/install/setup.bash
ros2 launch mobiman r1_pro_jointTrackerdemo_launch.py -
当双臂姿态控制器启动后,左右双臂将自动调整至左图所示的状态。请确保将R1 Pro置于双臂自然垂下的位置,以避免因运动角度过大导致初始化失败。
-
当前末端姿态控制的相对位姿是URDF中
gripper_link相对于torso_link4的姿态转换。以下图中的左臂为例,左臂的left_gripper_link坐标系相对于躯干的torso_link4坐标系的相对关系中,包含了x、y、z的偏移量以及orientation对应的旋转偏移。
接口信息如下所示:
| 话题名称 | I/O | 描述 | 消息类型 |
|---|---|---|---|
| /hdas/feedback_arm_left | Input | 左臂关节反馈 | sensor_msgs::msg::JointState |
| /hdas/feedback_arm_right | Input | 右臂关节反馈 | sensor_msgs::msg::JointState |
| /motion_target/target_pose_arm_left | Input | 目标左臂末端执行器位姿 | geometry_msgs::msg::PoseStamped |
| /motion_target/target_pose_arm_right | Input | 目标右臂末端执行器位姿 | geometry_msgs::msg::PoseStamped |
| /motion_target/target_joint_state_arm_left | Output | 左臂关节目标位置 | sensor_msgs::msg::JointState |
| /motion_target/target_joint_state_arm_right | Output | 右臂关节目标位置 | sensor_msgs::msg::JointState |
针对以上话题的具体字段及其详细描述如下表所示:
| 话题名称 | 字段 | 描述 |
|---|---|---|
| /hdas/feedback_arm_left /hdas/feedback_arm_right |
- | 请参考手臂驱动接口 |
| /motion_target/target_pose_arm_left /motion_target/target_pose_arm_right |
header | 标准消息头 |
| pose.position.x | X轴偏移 | |
| pose.position.y | Y轴偏移 | |
| pose.position.z | Z轴偏移 | |
| pose.orientation.x | 旋转四元数 | |
| pose.orientation.y | 旋转四元数 | |
| pose.orientation.z | 旋转四元数 | |
| pose.orientation.w | 旋转四元数 | |
| /motion_target/target_joint_state_arm_left /motion_target/target_joint_state_arm_right |
- | 请参考关节控制接口 |
夹爪控制
夹爪控制是一个用于控制末端执行器夹爪的ROS node,可通过以下命令启动:
source {your_download_path}/install/setup.bash
ros2 launch mobiman r1_gripperController_launch.py robot_type:=R1PRO
该文件将启动一个节点R1_Gripper_Controller (注意:此处不是R1_Pro_Gripper_Controller) 。接口信息如下所示::
| 话题名称 | I/O | 描述 | 消息类型 |
|---|---|---|---|
| /motion_target/target_position_gripper_left | Input | 左夹爪目标位置 | sensor_msgs::msg::JointState |
| /motion_target/target_position_gripper_right | Input | 右夹爪目标位置 | sensor_msgs::msg::JointState |
| /motion_control/control_gripper | Output | 夹爪电机控制 | sensor_msgs::msg::JointState |
针对以上话题的具体字段及其详细描述如下表所 示:
| 话题名称 | 字段 | 描述 |
|---|---|---|
| /motion_target/target_position_gripper_left /motion_target/target_position_gripper_right |
position | 表示左右夹爪的目标位置,[0,100],0为完全闭合,100为完全张开。 |
| /motion_control/control_gripper | - | 请参考手臂驱动接口 |
躯干速度控制
躯干速度控制是一个用于控制躯干移动到目标浮动基座坐标帧的ROS软件包。通过以下命令启动:
注意,此命令不能与:ros2 launch mobiman r1_pro_jointTrackerdemo.py 同时执行。
如果需要同时使用 joint_tracker,请使用如下命令,设置 disable_torso:=true
ros2 launch mobiman r1_pro_jointTrackerdemo_launch.py disable_torso:=true
# 躯干速度控制接口
source {your_download_path}/install/setup.bash
ros2 launch mobiman torso_control_r1.launch.py
该控制节点如图所显示,表示torsolink3相对base_link的的速度控制,其方向与base_link的frame相同。

v_x是torso frame相对于base_link的x方向的速度(最大速度是0.15m/s),正值表示基于base_link向前,负值表示向后;v_z是torso frame相对于base_link的z方向的速度(最大速度是0.15m/s),方向正值表示基于base_link向上,负值表示向下;w_pitch是torso frame相对于base_link的y方向的角速度(最大速度是0.3rad/s),方向符合右手坐标系;w_yaw是torso frame相对于base_link的z方向的角速度(最大速度是0.3rad/s),方向符合右手坐标系。
接口信息如下所示。
| 话题名称 | I/O | 描述 | 消息类型 |
|---|---|---|---|
| /hdas/feedback_torso | Input | 躯干关节反馈 | sensor_msgs::msg::JointState |
| /motion_target/target_speed_torso | Input | 浮动基座框架的目标速度 | geometry_msgs::msg::TwistStamped |
| /motion_control/(该接口不可主动发布消息) | Output | 躯干各关节目标位置 | hdas_msg::msg::MotorControl |
针对以上话题的具体字段及其详细描述如下表所示:
| 话题名称 | 字段 | 描述 |
|---|---|---|
| /hdas/feedback_torso | - | 请参考躯干驱动接口 |
| /motion_target/target_speed_torso | target_speed.v_x = msg.twist.linear.x | 躯干笛卡尔空间x方向线速度 |
| target_speed.v_z = msg.twist.linear.z | 躯干笛卡尔空间z方向线速度 | |
| target_speed.w_pitch =msg.twist.angular.y | 躯干笛卡尔空间y方向角速度 | |
| target_speed.w_yaw =msg.twist.angular.z | 躯干笛卡尔空间z方向角速度 |
底盘控制
底盘控制是一个矢量控制节点,允许同时发送三个方向的速度命令:x、y 和w。通过以下命令启动:
ros2 launch mobiman r1_pro_chassis_control_launch.py
该文件将启动两个节点:chassis_control_node 和 r1_pro_eepose_pub_node。chassis_control_node 负责R1底盘的速度控制。接口信息如下所示:
| 话题名称 | I/O | 描述 | 消息类型 |
|---|---|---|---|
| /hdas/feedback_chassis | Input | 底盘控制订阅此话题并控制底盘的目标速度。 | sensor_msgs::msg::JointState |
| /motion_target/target_speed_chassis | Input | 底盘的目标速度,包括vx, vy和omega. | geometry_msgs::msg::TwistStamped |
| /motion_target/chassis_acc_limit | Input | 底盘的加速度限制,最大值分别为2.5, 1.0, 1.0 | geometry_msgs::msg::TwistStamped |
| /motion_target/brake_mode | Input | 发出底盘是否进入制动模式的指令。如果处于制动模式,当速度为0时,底盘将通过将车轮转动一定角度来锁定自身。 | std_msgs::msg::Bool |
| /motion_control/control_chassis | Output | 底盘控制发布此话题以控制电机。 | hdas_msg::msg::MotorControl |
针对以上话题的具体字段及其详细描述如下表所示:
| 话题名称 | 字段 | 描述 |
|---|---|---|
| /hdas/feedback_chassis | - | 请参考底盘驱动接口 |
| /motion_target/target_speed_chassis | header | 标准消息头 |
| linear | 线速度 | |
| .x | 线速度x, 范围 (-1.5, 1.5) m/s | |
| .y | 线速度y, 范围 (-1.5, 1.5) m/s | |
| angular | 角速度 | |
| .z | 角速度, 范围 (-3 - 3) rad/s | |
| /motion_target/chassis_acc_limit | header | 标准消息头 |
| linear | 线速度 | |
| .x | 加速度限制x, 范围 (-2.5, 2.5) m/s² | |
| .y | 加速度限制y, 范围 (-1.0, 1.0) m/s² | |
| angular | 角速度 | |
| .z | 角速度限制, 范围 (-3, 3) rad/s² | |
| /motion_target/brake_mode | data | 布尔值 进入刹车模式:True 退出刹车模式:False |
| /motion_control/control_chassis | - | 请参考底盘驱动接口 |
姿态估计
在底盘控制的launch文件中,还会启动一个名为eepose_pub_node的节点。该节点接收来自HDAS的关节角反馈,并计算出对应于三个坐标系的反馈。eepose_pub_node定义了三个坐标帧:基座连接框架(Base Link Frame,左图)、浮动基座框架(Floating Base Frame,中图)和末端执行器姿态框架(End-Effector Pose Frame,右图)。

接口信息如下所示::
| 话题名称 | I/O | 描述 | 消息类型 |
|---|---|---|---|
| /hdas/feedback_arm_right | Input | 左臂电机反馈 | sensor_msgs::msg::JointState |
| /hdas/feedback_arm_left | Input | 右臂电机反馈 | sensor_msgs::msg::JointState |
| /hdas/feedback_torso | Input | 躯干电机反馈 | sensor_msgs::msg::JointState |
| /motion_control/pose_ee_arm_left | Output | 从浮动基座变换到左端执行器姿态 | geometry_msgs::msg::PoseStamped |
| /motion_control/pose_ee_arm_right | Output | 从浮动基座变换到右端执行器姿态 | geometry_msgs::msg::PoseStamped |
| /motion_control/pose_floating_base | Output | 从基座链接变换到浮动基座 | geometry_msgs::msg::PoseStamped |
针对以上话题的具体字段及其详细描述如下表所示:
| 话题名称 | 字段 | 描述 |
|---|---|---|
| /motion_control/pose_ee_arm_right /motion_control/pose_ee_arm_left /motion_control/pose_floating_base |
position | 平移信息 |
| pose.position.x | X轴偏移 | |
| pose.position.y | Y轴偏移 | |
| pose.position.z | Z轴偏移 | |
| orientation | 旋转信息 | |
| pose.orientation.x | 旋转四元数 | |
| pose.orientation.y | 旋转四元数 | |
| pose.orientation.z | 旋转四元数 | |
| pose.orientation.w | 旋转四元数 |