运动控制接口
- 手臂关节控制:该节点负责控制手臂的每个关节。
- 手臂姿态控制:该节点负责控制手臂移动到目标末端执行器(ee)坐标帧,分为左臂的姿态控制和右臂的姿态控制。
- 夹爪控制:该节点负责控制夹爪的打开和关闭。
- 躯干速度控制:该节点负责控制躯干移动到目标浮动基座坐标帧。
- 躯干关节控制:该节点负责控制躯干的单个关节运动。
- 底盘控制:该节点使用矢量控制来控制 R1 Lite 底盘,可同时发送三个方向的速度命令:x、y 和 w 。
手臂关节控制
手臂关节控制节点负责控制手臂的每个关节,总共有6个关节。
可通过以下命令启动:
# 调用以下接口前,请您确认已启动FDCAN通信及HDAS节点(操作方法参考分开启动章节)
# 以下两个Launch选择一个启动,本质是关节速度限制参数不一样
ros2 launch mobiman r1_lite_jointTrackerdemo_launch.py #(正常模式)
ros2 launch mobiman r1_lite_jointTrackerdemo_fast_launch.py #(高跟随模式)
接口信息如下:
| 话题名称 | I/O | 描述 | 消息类型 |
|---|---|---|---|
| /motion_target/target_joint_state_arm_left | Input | 左臂各关节的目标位置 | sensor_msgs::msg::JointState |
| /motion_target/target_joint_state_arm_right | Input | 右臂各关节的目标位置 | sensor_msgs::msg::JointState |
| /hdas/feedback_arm_left | Input | 左臂关节反馈 | sensor_msgs::msg::JointState |
| /hdas/feedback_arm_right | 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 |
针对以上话题的具体字段及其详细描述如下表所示:
| 话题名称 | 字段 | 描述 |
|---|---|---|
| /motion_target/target_joint_state_arm_left /motion_target/target_joint_state_arm_right |
header | 标准消息头 |
| position | 这是一个包含六个元素的向量,代表每个关节的六个目标位置。 | |
| velocity | 这是一个包含六个元素的向量,代表每个关节在运动过程中的最大速度。 | |
| /hdas/feedback_arm_left | - | 请参考手臂驱动接口 |
| /hdas/feedback_arm_right | - | 请参考手臂驱动接口 |
| /motion_control/control_arm_left | - | 请参考手臂驱动接口 |
| /motion_control/control_arm_right | - | 请参考手臂驱动接口 |
手臂姿态控制
手臂姿态控制是一个用于控制手臂移动到目标末端执行器(ee)坐标帧的ROS软件包。它主要包括两个launch文件,分别对应左臂的姿态控制和右臂的姿态控制。
可通过以下命令启动:
# 调用以下接口前,请您确认已启动FDCAN通信、HDAS节点及手臂关节控制节点;
# FDCAN通信及HDAS节点启动方式,操作方法参考分开启动章节;手臂关节控制节点的启动方式参考手臂关节控制章节;
ros2 launch mobiman r1_lite_left_arm_relaxed_ik_launch.py
#再新启一个终端
ros2 launch mobiman r1_lite_right_arm_relaxed_ik_launch.py
# 输入:解算目标姿态
/motion_target/target_pose_arm_left
/motion_target/target_pose_arm_right
# 输出:解算出的目标关节角
/motion_target/target_joint_state_arm_left
/motion_target/target_joint_state_arm_right
注意:由于姿态控制是根据目标姿态不断解算出目标关节角,所以必须提前启动关节角控制节点:
source {sdk_path}/install/setup.bash
ros2 launch mobiman r1_lite_jointTrackerdemo_launch.py
使用以下命令启动手臂姿态反馈节点:
source install setup.bash
ros2 launch mobiman r1_lite_eepose_launch.py
接口信息如下:
| 话题名称 | 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 |
| /motion_control/pose_ee_arm_left | Output | 实际左臂末端执行器姿态 | geometry_msgs::msg::PoseStamped |
| /motion_control/pose_ee_arm_right | Output | 实际右臂末端执行器姿态 | geometry_msgs::msg::PoseStamped |
针对以上话题的具体字段及其详细描述如下表所示:
| 话题名称 | 字段 | 描述 |
|---|---|---|
| /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 |
- | 请参考关节控制接口 |
| /motion_control/pose_ee_arm_left /motion_control/pose_ee_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 | 旋转四元数 |
夹爪控制
可通过以下命令启动:
# 调用以下接口前,请您确认已启动FDCAN通信、HDAS节点(操作方法参考分开启动章节)
ros2 launch mobiman r1_gripperController_launch.py robot_type:=R1LITE
注意:这个启动文件将启动 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_left | Output | 左夹爪电机控制 | hdas_msg::msg::MotorControl |
| /motion_control/control_gripper_right | Output | 右夹爪电机控制 | hdas_msg::msg::MotorControl |
针对以上话题的具体字段及其详细描述如下表所示:
| 话题名称 | 字段 | 描述 |
|---|---|---|
| /motion_target/target_position_gripper_left /motion_target/target_position_gripper_right |
position | 表示左右夹爪的目标位置[0,100], 0 为完全闭合,100 完全张开。 |
| /motion_control/control_gripper_left /motion_control/control_gripper_right |
- | 请参考手臂驱动接口 |
躯干速度控制
躯干速度控制是一个用于控制躯干移动到目标浮动基座坐标帧的ROS软件包。
可通过以下命令启动:
#调用以下接口前,请您确认已启动FDCAN通信、HDAS节点(操作方法参考分开启动章节)
ros2 launch mobiman torso_control_r1_lite.launch.py
接口信息如下:
| 话题名称 | I/O | 描述 | 消息类型 |
|---|---|---|---|
| /motion_target/target_speed_torso | Input | 浮动基座框架的目标速度 | geometry_msgs::msg::TwistStamped |
| /hdas/feedback_torso | Input | 躯干关节反馈 | sensor_msgs::msg::JointState |
| /motion_control/control_torso(该接口不可主动发布消息) | Output | 躯干关节控制 | hdas_msg::msg::MotorControl |
针对以上话题的具体字段及其详细描述如下表所示:
| 话题名称 | 字段 | 描述 |
|---|---|---|
| /motion_target/target_speed_torso | target_speed.v_x = msg->linear.x | 躯干笛卡尔空间x方向线速度,[-0.2,0.2]m/s; -0.1≤x≤0.2 |
| target_speed.v_z = msg->linear.z | 躯干笛卡尔空间z方向线速度,[-0.2,0.2]m/s; 0.1≤z≤0.7 |
|
| target_speed.v_pitch = msg->twist.angular.y | 躯干笛卡尔空间pitch角速度 | |
| target_speed.v_yaw = msg->twist.angular.z | 躯干笛卡尔空间yaw角速度 | |
| /hdas/feedback_torso | - | 请参考躯干驱动接口 |
| /motion_control/control_torso(该接口不可主动发布消息) | - | 请参考躯干驱动接口 |
该控制节点如图所显示,表示 torsolink3 相对 base_link 的速度控制,其方向与 base_link 的框架相同。
`
- v_x是torso frame相对于
base_link的x方向的速度(最大速度是0.1m/s),正值表示基于base_link向前,负值表示向后; - v_z是torso frame相对于
base_link的z方向的速度(最大速度是0.1m/s),方向正值表示基于base_link向上,负值表示向下; - w_pitch是torso frame相对于
base_link的y方向的角速度(最大速度是0.3rad/s),方向符合右手坐标系; - w_yaw是torso frame相对于
base_link的z方向的角速度(最大速度是0.3rad/s),方向符合右手坐标系。
躯干关节控制
躯干关节控制节点负责控制躯干的每个关节,总共有3个关节。
可通过以下命令启动:
source {your_download_path}/install/setup.bash
source /opt/galaxea/galaxeaKey/keys.env
# 以下两个launch选择一个启动
# 高跟随 和 正常 模式的区别主要是双臂的最大关节速度限制的差异,躯干跟随速度是相同的
# 调用以下接口前,请您确认已启动FDCAN通信、HDAS节点(操作方法参考分开启动章节)
ros2 launch mobiman r1_lite_jointTrackerdemo_fast_launch.py disable_torso:=false #(高跟随模式)(默认)
ros2 launch mobiman r1_lite_jointTrackerdemo_launch.py disable_torso:=false #(正常模式)
注意:躯干关节控制节点和手臂控制节点是一个节点
特别注意:虽然躯干速度控制节点 与关节控制节点可以一起启动,但是躯干速度控制信号和躯干关节控制信号不可以混用,否则会引起关节冲突和危险
# 即如下两个话题不可以在躯干速度控制节点与关节控制节点一起启动的状态下混用,只能二选一,否则会引起关节冲突与危险
/motion_target/target_speed_torso
/motion_target/target_joint_state_torso
值得注意的是:上述启动方法中,disable_torso这个参数被设置为false。然后通过存放再/opt/galaxea/galaxeaKey/keys.env的密钥配对,既可实现torso的关节控制。
接口信息如下: