运动控制接口
- 关节控制:该节点负责控制手臂、躯干的每个关节。
- 手臂姿态控制:该节点负责控制手臂移动到目标末端执行器ee坐标帧,分为左臂的姿态控制和右臂的姿态控制。
- 夹爪控制:该节点负责控制夹爪的打开和关闭。
- 底盘控制:该节点使用矢量控制来控制 R1 Lite 底盘,可同时发送三个方向的速度命令:x、y 和 w 。
关节控制
调用以下接口前,请您确认已启动FDCAN通信及HDAS节点,操作方法参考分开启动章节。
ros2 launch moca_adapter moca_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 |
| /motion_target/target_joint_state_torso | Input | 躯干各关节的目标位 置 | sensor_msgs::msg::JointState |
| /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_control/control_arm_left | Output | 左臂电机控制 | hdas_msg::msg::MotorControl |
| /motion_control/control_arm_right | Output | 右臂电机控制 | hdas_msg::msg::MotorControl |
| /motion_control/control_torso | Output | 躯干电机控制 | hdas_msg::msg::MotorControl |
针对以上话题的具体字段及其详细描述如下表所示:
| 话题名称 | 字段 | 描述 |
|---|---|---|
| /motion_target/target_joint_state_arm_left /motion_target/target_joint_state_arm_right |
header | 标准消息头 |
| position | 这是一个包含六个元素的向量,代表每个关节的六个目标位置。 | |
| velocity | 这是一个包含六个元素的向量,代表每个关节在运动过程中的最大速度。 | |
| /motion_target/target_joint_state_torso | header | 标准消息头 |
| position | 这是一个包含三个元素的向量,代表三个关节的目标位置。 | |
| velocity | 这是一个包含三个元素的向量,代表三个关节在运动过程中的最大速度。 | |
| /hdas/feedback_arm_left | - | 请参考手臂驱动接口 |
| /hdas/feedback_arm_right | - | 请参考手臂驱动接口 |
| /motion_control/control_arm_left | - | 请参考手臂驱动接口 |
| /motion_control/control_arm_right | - | 请参考手臂驱动接口 |
| /motion_control/control_torso | - | 请参考躯干驱动接口 |
手臂姿态控制
手臂姿态控制是一个用于控制手臂移动到目标末端执行器(ee)坐标帧的ROS软件包。它主要包括两个launch文件,分别对应左臂的姿态控制和右臂的姿态控制。
调用以下接口前,请您确认已启动FDCAN通信及HDAS节点,操作方法参考分开启动章节。
ros2 launch teleoperation_ros2 vr_teleoperation_whole_body_launch.py independent_mode:=true
启动vr_teleoperation_whole_body_laucnh.py文件后,调用以下ros service切换话题控制手臂末端姿态:
ros2 service call /switch_control_mode_vr teleoperation_msg_ros2/srv/SwitchControlModeVR use_vr_mode:\ false\
注意:必须左右臂都输入目标姿态后,才能解算出关节的目标关节角度
# 输入:解算目标姿态
/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 moca_adapter moca_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 | 旋转四元数 |
夹爪控制
夹爪控制是一个用于控制末端执行器夹爪的控制器。
接口信息如下:
| 话题名称 | 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 |
- | 请参考手臂驱动接口 |
底盘控制
底盘控制是一个使用矢量控制来控制 R1 Lite 底盘的控制器,可同时发送三个方向的速度命令:x、y 和 w。 其接口如下所示:
| 话题名称 | I/O | 描述 | 消息类型 |
|---|---|---|---|
| /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 |
| /hdas/feedback_chassis | Input | R1 Lite 底盘控制订阅此话题并控制底盘的目标速度。 | sensor_msgs::msg::JointState |
| /motion_control/control_chassis | Output | R1 Lite 底盘控制发布此话题以控制电机。 | hdas_msg::msg::MotorControl |
针对以上话题的具体字段及其详细描述如下表所示:
| 消息名称 | 字段 | 描述 |
|---|---|---|
| /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 |
| /hdas/feedback_chassis | - | 请参考底盘驱动接口 |
| /motion_control/control_chassis | - | 请参考底盘驱动接口 |