R1 Lite 软件介绍
环境依赖
- 硬件依赖:R1 Lite 计算单元
- 操作系统依赖:Ubuntu 20.04 LTS
- 中间件依赖:ROS Noetic
软件版本日志
访问 Galaxea R1 Lite 软件版本更新日志 查看,获取最新的SDK包及更新信息。
首次操作指引
访问 Galaxea R1 Lite 开箱启动指南 ,并按照说明操作 Galaxea R1 Lite 。
启动SDK
当前支持 分开启动 和 一键启动 两种方式启动软件接口。为了您的安全,建议使用分开启动的方式启动SDK。
操作指引如下:
模块名称 | 包含组件 | 路径 | 启动文件 |
---|---|---|---|
HDAS | Arms Driver Torso Driver Chassis Driver IMU Driver BMS Driver |
{{sdk_path}/install}/install/share/HDAS/launch | r1lite.launch |
camera_driver | Head Camera Interface | {{sdk_path}/install}/install/share/camera_driver/launch | run.launch |
realsense2_camera | Wrist Camera Interface | {{sdk_path}/install}/install/share/realsense2_camera/launch | rs_multiple_devices.launch |
mobiman | Arm Control Chassis Control Torso Control Gripper Control End Effector Pose interfase |
{{sdk_path}/install}/install/share/mobiman/launch | r1_lite_jointTrackerdemo_fast.launch r1_lite_chassis_control.launch torso_control_r1_lite.launch r1_gripperController.launch r1_lite_eepose.launch |
robot_monitor | robot monitor Interface | {{sdk_path}/install}/install/share/system_monitor_node/launch | robot_monitor.launch |
data collection | data collection | {{sdk_path}/install}/install/share/data_collection/launch | data_collection.launch |
robot diagnosis system | rds_ros | {{sdk_path}/install}/install/share/rds_ros/launch | Rds.launch |
分开启动
所有节点可通过以下命令模板启动,配置方法如下:
注意:启动节点前,请您确认已正确配置CAN驱动。
bash ~/can.bash
# 可能需要再次输入密码:1
# 若出现“RTNETLINK answers: Device or resource busy”这个错误信息,通常表示你尝试配置的设备(如网络接口或CAN收发器)已经被配置并且正在运行中。
各节点启动命令如下:
source ~{{sdk_path}/install}/install/setup.bash
roslaunch <Package Name> <Launch File>
# Example
roslaunch HDAS r1lite.launch
一键启动
注意:执行以下命令将启动所有驱动和运控接口。
cd ~{{sdk_path}/install}/install/share/startup_config/script/
./robot_startup.sh boot ../session.d/ATCStandard/R1LITEBody.d
软件接口
当前的 Galaxea R1 Lite 由 6 主要部分组成:手臂关节控制、手臂姿态控制、夹爪控制、躯干速度控制、躯干关节控制和底盘控制。整个软件包被简称为“mobiman”,表示移动操作。
驱动接口
手臂驱动接口
该接口是用于机械臂控制和状态反馈的ROS软件包,定义了多个话题用于发布和订阅臂的状态、控制命令和相关错误代码。 以下是每个话题及其对应消息类型的详细描述:
话题名称 | I/O | 描述 | 消息类型 |
---|---|---|---|
/hdas/feedback_arm_left | Output | 左臂关节反馈 | sensor_msgs::JointState |
/hdas/feedback_arm_right | Output | 右臂关节反馈 | sensor_msgs::JointState |
/hdas/feedback_gripper_left | Output | 左夹爪行程 | sensor_msgs::JointState |
/hdas/feedback_gripper_right | Output | 右夹爪行程 | sensor_msgs::JointState |
/hdas/feedback_status_arm_left | Output | 左臂状态反馈 | hdas_msg::feedback_status |
/hdas/feedback_status_arm_right | Output | 右臂状态反馈 | hdas_msg::feedback_status |
/hdas/feedback_status_gripper_left | Output | 左夹爪状态反馈 | hdas_msg::feedback_status |
/hdas/feedback_status_gripper_right | Output | 右夹爪状态反馈 | hdas_msg::feedback_status |
/motion_control/control_arm_left | Input | 左臂电机控制 | hdas_msg::motor_control |
/motion_control/control_arm_right | Input | 右臂电机控制 | hdas_msg::motor_control |
/motion_control/control_gripper_left | Input | 左夹爪电机控制 | hdas_msg::motor_control |
/motion_control/control_gripper_right | Input | 右夹爪电机控制 | hdas_msg::motor_control |
针对以上话题的具体字段及其详细描述如下表所示:
话题名称 | 字段 | 描述 |
---|---|---|
/hdas/feedback_arm_left | header | 标准消息头 |
position | [关节1位置, 关节2位置, 关节3位置, 关节4位置, 关节5位置, 关节6位置, 夹爪关节位置] | |
velocity | [关节1速度, 关节2速度, 关节3速度, 关节4速度, 关节5速度, 关节6速度, 夹爪关节速度] | |
effort | [关节1力矩, 关节2力矩, 关节3力矩, 关节4力矩, 关节5力矩, 关节6力矩, 夹爪关节力矩] | |
/hdas/feedback_arm_right | header | 标准消息头 |
position | [关节1位置, 关节2位置, 关节3位置, 关节4位置, 关节5位置, 关节6位置, 夹爪关节位置] | |
velocity | [关节1速度, 关节2速度, 关节3速度, 关节4速度, 关节5速度, 关节6速度, 夹爪关节速度] | |
effort | [关节1力矩, 关节2力矩, 关节3力矩, 关节4力矩, 关节5力矩, 关节6力矩, 夹爪关节力矩] | |
/hdas/feedback_gripper_left | header | 标准消息头 |
position | 夹爪行程 (0-100mm) | |
velocity | 暂不使用 | |
effort | 暂不使用 | |
/hdas/feedback_gripper_right | header | 标准消息头 |
position | 夹爪行程 (0-100mm) | |
velocity | 暂不使用 | |
effort | 暂不使用 | |
/hdas/feedback_status_arm_left | header | 标准消息头 |
name_id | 关节名称 | |
errors | 包含错误码和对应的错误描述 | |
/hdas/feedback_status_arm_right | header | 标准消息头 |
name_id | 关节名称 | |
errors | 包含错误码和对应的错误描述 | |
/hdas/feedback_status_gripper_left | header | 标准消息头 |
name_id | 关节名称 | |
errors | 包含错误码和对应的错误描述 | |
/hdas/feedback_status_gripper_right | header | 标准消息头 |
name_id | 关节名称 | |
errors | 包含错误码和对应的错误描述 | |
/motion_control/control_arm_left(MIT) | header | 标准消息头 |
name | - | |
p_des | [关节1位置, 关节2位置, 关节3位置, 关节4位置, 关节5位置, 关节6位置, 夹爪关节位置] | |
v_des | [关节1速度, 关节2速度, 关节3速度, 关节4速度, 关节5速度, 关节6速度, 夹爪关节速度] | |
kp | [关节1kp, 关节2kp, 关节3kp, 关节4kp, 关节5kp, 关节6kp, 夹爪关节kp] | |
kd | [关节1kd, 关节2kd, 关节3kd, 关节4kd, 关节5kd, 关节6kd, 夹爪关节kd] | |
t_ff | [关节1力矩, 关节2力矩, 关节3力矩, 关节4力矩, 关节5力矩, 关节6力矩, 夹爪关节力矩] | |
mode | - | |
/motion_control/control_arm_left(PID) | header | 标准消息头 |
name | - | |
p_des | [关节1位置, 关节2位置, 关节3位置, 关节4位置, 关节5位置, 关节6位置, 夹爪关节位置] | |
v_des | - | |
t_ff | - | |
mode | - | |
/motion_control/control_arm_right(MIT) | header | 标准消息头 |
name | - | |
p_des | [关节1位置, 关节2位置, 关节3位置, 关节4位置, 关节5位置, 关节6位置, 夹爪关节位置] | |
v_des | [关节1速度, 关节2速度, 关节3速度, 关节4速度, 关节5速度, 关节6速度, 夹爪关节速度] | |
kp | [关节1kp, 关节2kp, 关节3kp, 关节4kp, 关节5kp, 关节6kp, 夹爪关节kp] | |
kd | [关节1kd, 关节2kd, 关节3kd, 关节4kd, 关节5kd, 关节6kd, 夹爪关节kd] | |
t_ff | [关节1力矩, 关节2力矩, 关节3力矩, 关节4力矩, 关节5力矩, 关节6力矩, 夹爪关节力矩] | |
mode | - | |
/motion_control/control_arm_right(PID) | header | 标准消息头 |
name | - | |
p_des | [关节1位置, 关节2位置, 关节3位置, 关节4位置, 关节5位置, 关节6位置, 夹爪关节位置] | |
v_des | [关节1速度最大限制, 关节2速度最大限制, 关节3速度最大限制, 关节4速度最大限制, 关节5速度最大限制,关节6速度最大限制, 夹爪关节速度最大限制] | |
t_ff | [关节1力矩最大限制, 关节2力矩最大限制, 关节3力矩最大限制, 关节4力矩最大限制, 关节5力矩最大限制, 关节6力矩最大限制, 夹爪关节力矩最大限制] | |
mode | - | |
/motion_control/control_gripper_left | header | 标准消息头 |
name | - | |
p_des | 夹爪电机位置 | |
v_des | 夹爪电机速度 | |
kp | 夹爪电机kp | |
kd | 夹爪电机kd | |
t_ff | 夹爪力矩 | |
mode | - | |
/motion_control/control_gripper_right | header | 标准消息头 |
name | - | |
p_des | 夹爪电机位置 | |
v_des | 夹爪电机速度 | |
kp | 夹爪电机kp | |
kd | 夹爪电机kd | |
t_ff | 夹爪力矩 | |
mode | - | |
/motion_control/position_control_gripper_left | header | 标准消息头 |
data | 夹爪行程期待值 (0-100mm) | |
/motion_control/position_control_gripper_right | header | 标准消息头 |
data | 夹爪行程期待值 (0-100mm) |
机械臂关节电机控制接口说明
1. MIT-力位混合控制模式架构电机的输出扭矩公式用于计算电流环给定跟踪的力矩值 Tref
,公式如下:
\(K_p(p_d - p_e) + K_d(v_d - v_e)+t_{ff} = T_{ref}\)
其中:
Kp
,Kd
为位置增益和速度增益的比例项;
p_des
,v_des
为期望的位置和速度;
t_ff
为前馈力矩
p_e
为编码器反馈的位置,v_e
为微分得到的电机转速。
- 输入项包括:
Kp
,Kd
,pd
,vd
,t_ff
。反馈项pe
和ve
无需手动输入。
使用技巧:
- 前馈力矩:该值为必须项。由于位置项和速度项无法弥补过大的力矩误差,所以前馈力矩至少应补偿机械臂自身重力的影响。
- 增益设置推荐:以下是A1X电机的推荐 kp
和 kd
值,调整时请谨慎操作。
`A1X_kp = [ 140.0, 200.0, 120.0, 80.0, 80.0, 80.0 ]`
`A1X_kd = [ 10.0, 30.0, 5.0, 10.0, 10.0, 10.0 ]`
2. PID-伺服控制模式架构
伺服控制模式为三环PID(位置环、速度环、电流环)控制,该模式引入积分环节,稳态误差较小.为保持接口一致性,在控制数据格式上,与MIT接口相同。
其中:
p_des
:表示设定角度(rad);
v_des
:无意义;
k_p
,k_d
:无意义;
t_ff
:无意义。
躯干驱动接口
该接口是用于躯干控制和提供状态反馈的ROS软件包,它定义了多个话题,用于发布和订阅躯干电机的状态和控制命令。以下是每个话题及其对应消息类型的详细描述:
话题名称 | I/O | 描述 | 消息类型 |
---|---|---|---|
/hdas/feedback_torso | Output | 躯干关节反馈 | sensor_msgs::JointState |
/hdas/feedback_status_torso | Output | 躯干状态反馈 | hdas_msg::feedback_status |
/motion_control/control_torso | Input | 躯干电机控制 | hdas_msg::motor_control |
针对以上话题的具体字段及其详细描述如下表所示:
话题名称 | 字段 | 描述 |
---|---|---|
/hdas/feedback_torso | header | 标准消息头 |
position | [关节1位置, 关节2位置, 关节3位置, 0] | |
velocity | [关节1速度, 关节2速度, 关节3速度, 0] | |
effort | [关节1力矩, 关节2力矩, 关节3力矩, 0] | |
/hdas/feedback_status_torso | header | 标准消息头 |
name_id | 关节名称 | |
errors | 包含错误码和对应的错误描述 | |
/motion_control/control_torso | header | 标准消息头 |
name | - | |
p_des | [关节1位置, 关节2位置, 关节3位置, 0] | |
v_des | [关节1最大速度, 关节2最大速度, 关节3最大速度, 0] | |
kp | [-, -, -, -] | |
kd | [-, -, -, -] | |
t_ff | [-, -, -, -] | |
mode | - |
底盘驱动接口
该接口是用于底盘状态反馈的ROS软件包,定义了多个话题以报告底盘电机的状态。以下是每个话题及其相关消息类型的详细描述:
话题名称 | I/O | 描述 | 消息类型 |
---|---|---|---|
/hdas/feedback_chassis | Output | 底盘轮毂和转向电机反馈 | sensor_msgs::JointState |
/hdas/feedback_status_chassis | Output | 底盘状态反馈 | hdas_msg::feedback_status |
/motion_control/control_chassis | Input | 底盘轮毂和转向电机控制 | hdas_msg::motor_control |
针对以上话题的具体字段及其详细描述如下表所示:
话题名称 | 字段 | 描述 |
---|---|---|
/hdas/feedback_chassis | header | 标准消息头 |
position | [左前轮角度, 右前轮角度, 后轮角度] | |
velocity | [左前轮线速度, 右前轮线速度, 后轮线速度] [0.0, 0.0, 0.0] |
|
effort | [0.0, 0.0, 0.0, 0.0, 0.0, 0.0] | |
/hdas/feedback_status_chassis | header | 标准消息头 |
name_id | 关节名称 | |
errors | 包含错误码和对应的错误描述 | |
/motion_control/control_chassis | header | 标准消息头 |
name | - | |
p_des | [左前轮角度, 右前轮角度, 后轮角度] | |
v_des | [左前轮线速度, 右前轮线速度, 后轮线速度] | |
kp | - | |
kd | - | |
t_ff | - | |
mode | - |
相机接口
话题名称 | I/O | 描述 | 消息类型 |
---|---|---|---|
/hdas/camera_wrist_left/color/image_raw/compressed | Output | 左腕相机RGB压缩图 | sensor_msgs::CompressedImage |
/hdas/camera_wrist_right/color/image_raw/compressed | Output | 右腕相机RGB压缩图 | sensor_msgs::CompressedImage |
/hdas/camera_head/left_raw/image_raw_color/compressed | Output | 头部相机左目RGB压缩图 | sensor_msgs::CompressedImage |
/hdas/camera_head/right_raw/image_raw_color/compressed | Output | 头部相机右目RGB压缩图 | sensor_msgs::CompressedImage |
/hdas/camera_wrist_left/aligned_depth_to_color/image_raw | Output | 左腕相机深度图 | sensor_msgs::Image |
/hdas/camera_wrist_right/aligned_depth_to_color/image_raw | Output | 右腕相机深度图 | sensor_msgs::Image |
针对以上话题的具体字段及其详细描述如下表所示:
话题名称 | 字段 | 描述 |
---|---|---|
/hdas/camera_wrist_left/color/image_raw/compressed | header | 标准消息头 |
format | JPEG | |
data | 图像数据 | |
/hdas/camera_wrist_right/color/image_raw/compressed | header | 标准消息头 |
format | JPEG | |
data | 图像数据 | |
/hdas/camera_head/left_raw/image_raw_color/compressed | header | 标准消息头 |
format | JPEG格式 | |
data | 图像数据 | |
/hdas/camera_head/right_raw/image_raw_color/compressed | header | 标准消息头 |
format | JPEG格式 | |
data | 图像数据 | |
/hdas/camera_wrist_left/aligned_depth_to_color/image_raw | header | 标准消息头 |
height | 取决于设置 | |
width | 取决于设置 | |
encoding | 16UC1 | |
is_bigendian | 0 | |
step | 取决于设置 | |
data | 图像数据 | |
/hdas/camera_wrist_right/aligned_depth_to_color/image_raw | header | 标准消息头 |
height | 取决于设置 | |
width | 取决于设置 | |
encoding | 16UC1 | |
is_bigendian | 0 | |
step | 根据配置决定 | |
data | 图像数据 |
IMU 接口
话题名称 | I/O | 描述 | 消息类型 |
---|---|---|---|
/hdas/imu_chassis | Output | 底盘IMU反馈 | sensor_msgs::Imu |
/hdas/imu_torso | Output | 躯干IMU反馈 | sensor_msgs::Imu |
针对以上话题的具体字段及其详细描述如下表所示:
话题名称 | 字段 | 描述 |
---|---|---|
/hdas/imu_chassis | header | 标准消息头 |
orientation.x | 四元数x | |
orientation.y | 四元数y | |
orientation.z | 四元数z | |
orientation.w | 四元数w | |
angular_velocity.x | 陀螺仪角速度x | |
angular_velocity.y | 陀螺仪角速度y | |
angular_velocity.z | 陀螺仪角速度z | |
linear_acceleration.x | 线加速度x | |
linear_acceleration.y | 线加速度y | |
linear_acceleration.z | 线加速度z | |
/hdas/imu_torso | header | 标准消息头 |
orientation.x | 四元数x | |
orientation.y | 四元数y | |
orientation.z | 四元数z | |
orientation.w | 四元数w | |
angular_velocity.x | 陀螺仪角速度x | |
angular_velocity.y | 陀螺仪角速度y | |
angular_velocity.z | 陀螺仪角速度z | |
linear_acceleration.x | 线加速度x | |
linear_acceleration.y | 线加速度y | |
linear_acceleration.z | 线加速度z |
BMS 接口
话题名称 | I/O | 描述 | 消息类型 |
---|---|---|---|
/hdas/bms | Output | 电池BMS消息 | hdas_msg::bms |
针对以上话题的具体字段及其详细描述如下表所示:
话题名称 | 字段 | 描述 |
---|---|---|
/hdas/bms | header | 标准消息头 |
voltage | 电压 (V) | |
current | 电流 (I) | |
capital | 电量剩余 (%) |
遥控器接口
话题名称 | I/O | 描述 | 消息类型 |
---|---|---|---|
/controller | Output | 遥控器信号 | hdas_msg::controller_signal_stamped |
针对以上话题的具体字段及其详细描述如下表所示:
话题名称 | 字段 | 描述 |
---|---|---|
/controller | header | 标准消息头 |
data.left_x_axis | 左摇杆x方向 | |
data.left_y_axis | 左摇杆y方向 | |
data.right_x_axis | 右摇杆x方向 | |
data.right_y_axis | 右摇杆y方向 | |
mode | 2: 遥控器控制 (底盘)5: 上位机控制 (底盘) |
运动控制接口
- 手臂关节控制:该节点负责控制手臂的每个关节。
- 手臂姿态控制:该节点负责控制手臂移动到目标末端执行器(ee)坐标帧,分为左臂的姿态控制和右臂的姿态控制。
- 躯干速度控制:该节点负责控制躯干移动到目标浮动基座坐标帧。
- 底盘控制:该节点使用矢量控制来控制 R1 Lite 底盘,可同时发送三个方向的速度命令:x、y 和 w 。
手臂关节控制
手臂关节控制节点负责控制手臂的每个关节,总共有6个关节。
可通过以下命令启动:
# 调用以下接口前,请您确认已启动FDCAN通信及HDAS节点(操作方法参考分开启动章节)
# 以下两个Launch选择一个启动,本质是关节速度限制参数不一样
roslaunch mobiman r1_lite_jointTrackerdemo.launch #(正常模式)
roslaunch mobiman r1_lite_jointTrackerdemo_fast.launch #(高跟随模式)
接口信息如下:
话题名称 | I/O | 描述 | 消息类型 |
---|---|---|---|
/motion_target/target_joint_state_arm_left | Input | 左臂各关节的目标位置 | sensor_msgs::JointState |
/motion_target/target_joint_state_arm_right | Input | 右臂各关节的目标位置 | sensor_msgs::JointState |
/hdas/feedback_arm_left | Input | 左臂关节反馈 | sensor_msgs::JointState |
/hdas/feedback_arm_right | Input | 右臂关节反馈 | sensor_msgs::JointState |
/motion_control/control_arm_left | Output | 左臂电机控制 | hdas_msg::motor_control |
/motion_control/control_arm_right | Output | 右臂电机控制 | hdas_msg::motor_control |
针对以上话题的具体字段及其详细描述如下表所示:
话题名称 | 字段 | 描述 |
---|---|---|
/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节点启动方式,操作方法参考分开启动章节;手臂关节控制节点的启动方式参考手臂关节控制章节;
roslaunch mobiman r1_lite_left_arm_relaxed_ik.launch
#再新启一个终端
roslaunch mobiman r1_lite_right_arm_relaxed_ik.launch
# 输入:解算目标姿态
/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
使用以下命令启动手臂姿态反馈节点:
接口信息如下:
话题名称 | I/O | 描述 | 消息类型 |
---|---|---|---|
/motion_target/target_pose_arm_left | Input | 目标左臂末端执行器姿态 | Geometry_msgs::PoseStamped |
/motion_target/target_pose_arm_right | Input | 目标右臂末端执行器姿态 | Geometry_msgs::PoseStamped |
/hdas/feedback_arm_left | Input | 左臂关节反馈 | Sensor_msgs::JointState |
/hdas/feedback_arm_right | Input | 右臂关节反馈 | Sensor_msgs::JointState |
/motion_control/control_arm_left | Output | 左臂电机控制 | hdas_msg::motor_control |
/motion_control/control_arm_right | Output | 右臂电机控制 | hdas_msg::motor_control |
/motion_control/pose_ee_arm_left | Output | 实际左臂末端执行器姿态 | Geometry_msgs::PoseStamped |
/motion_control/pose_ee_arm_right | Output | 实际右臂末端执行器姿态 | Geometry_msgs::PoseStamped |
针对以上话题的具体字段及其详细描述如下表所示:
话题名称 | 字段 | 描述 |
---|---|---|
/motion_target/pose_ee_arm_left/motion_target/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 | 旋转四元数 | |
/hdas/feedback_arm_left | - | 请参考手臂驱动接口 |
/hdas/feedback_arm_right | - | 请参考手臂驱动接口 |
/motion_control/control_arm_left | - | 请参考手臂驱动接口 |
/motion_control/control_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 | 旋转四元数 |
夹爪控制
夹爪控制是一个用于控制末端执行器夹爪的ROS软件包。
可通过以下命令启动:
# 调用以下接口前,请您确认已启动FDCAN通信、HDAS节点(操作方法参考分开启动章节)
roslaunch mobiman r1_gripperController.launch robot_type:=R1LITE
注意:这个启动文件将启动 R1_Gripper_Controller
,此处不是 R1_Pro_Gripper_Controller
。
接口信息如下:
话题名称 | I/O | 描述 | 消息类型 |
---|---|---|---|
/motion_target/target_position_gripper_left | Input | 左夹爪目标位置 | Sensor_msgs::JointState |
/motion_target/target_position_gripper_right | Input | 右夹爪目标位置 | Sensor_msgs::JointState |
/motion_control/control_gripper_left | Output | 左夹爪电机控制 | hdas_msg/motor_control |
/motion_control/control_gripper_right | Output | 右夹爪电机控制 | hdas_msg/motor_control |
针对以上话题的具体字段及其详细描述如下表所示:
话题名称 | 字段 | 描述 |
---|---|---|
/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软件包。
可通过以下命令启动:
接口信息如下:
话题名称 | I/O | 描述 | 消息类型 |
---|---|---|---|
/motion_target/target_speed_torso | Input | 浮动基座框架的目标速度 | Geometry_msgs::TwistStamped |
/hdas/feedback_torso | Input | 躯干关节反馈 | Sensor_msgs::JointState |
/motion_control/control_torso | Output | 躯干关节控制 | hdas_msg::motor_control |
针对以上话题的具体字段及其详细描述如下表所示:
话题名称 | 字段 | 描述 |
---|---|---|
/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个关节。
可通过以下命令启动:
# 以下两个launch选择一个启动,本质是关节速度限制参数不一样
# 调用以下接口前,请您确认已启动FDCAN通信、HDAS节点(操作方法参考分开启动章节)
roslaunch mobiman r1_lite_jointTrackerdemo_fast.launch #(高跟随模式)(默认)
roslaunch mobiman r1_lite_jointTrackerdemo.launch #(正常模式)
注意:躯干关节控制节点和手臂控制节点是一个节点
特别注意:虽然躯干速度控制节点与关节控制节点可以一起启动,但是躯干速度控制信号和躯干关节控制信号不可以混用,否则会引起关节冲突和危险
# 即如下两个话题不可以在躯干速度控制节点与关节控制节点一起启动的状态下混用,只能二选一,否则会引起关节冲突与危险
/motion_target/target_speed_torso
/motion_target/target_joint_state_torso
接口信息如下:
话题名称 | I/O | 描述 | 消息类型 |
---|---|---|---|
/motion_target/target_joint_state_torso | Input | 躯干各关节目标位置 | Sensor_msgs::JointState |
/hdas/feedback_torso | Input | 躯干关节反馈 | Sensor_msgs::JointState |
/motion_control/control_torso | Output | 躯干电机控制 | hdas_msg::motor_control |
针对以上话题的具体字段及其详细描述如下表所示:
消息名称 | 字段 | 描述 |
---|---|---|
/motion_target/target_joint_state_torso | header | 标准消息头 |
position | 这是一个包含六个元素的向量,代表每个关节的六个目标位置。 | |
velocity | 这是一个包含六个元素的向量,代表每个关节在运动过程中的最大速度。 | |
/hdas/feedback_torso | - | 请参考手臂驱动接口 |
/motion_control/control_torso | - | 请参考手臂驱动接口 |
底盘控制
底盘控制是一个使用矢量控制来控制 R1 Lite 底盘的节点,可同时发送三个方向的速度命令:x、y 和 w。
可通过以下命令启动:
该文件将启动一个节点:r1_lite_chassis_control_node
,负责 R1 Lite 底盘的速度控制。其接口如下所示:
话题名称 | I/O | 描述 | 消息类型 |
---|---|---|---|
/motion_target/target_speed_chassis | Input | 底盘的目标速度,包括vx, vy 和 omega | geometry_msgs::Twist |
/motion_target/chassis_acc_limit | Input | 底盘的加速度限制,最大值分别为2.5, 1.0, 1.0 | geometry_msgs::Twist |
/motion_target/brake_mode | Input | 发出底盘是否进入制动模式的指令。如果处于制动模式,当速度为0时,底盘将通过将车轮转动一定角度来锁定自身。 | std_msgs::Bool |
/hdas/feedback_chassis | Input | R1 Lite 底盘控制订阅此话题并控制底盘的目标速度。 | sensor_msgs::JointState |
/motion_control/control_chassis | Output | R1 Lite 底盘控制发布此话题以控制电机。 | hdas_msg::motor_control |
针对以上话题的具体字段及其详细描述如下表所示:
消息名称 | 字段 | 描述 |
---|---|---|
/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 | - | 请参考底盘驱动接口 |