驱动接口
- 手臂驱动接口:该接口用于机械臂控制和状态反馈。
- 躯干驱动接口:该接口用于躯干控制和提供状态反馈。
- 底盘驱动接口:该接口是用于底盘状态反馈。
- 相机驱动接口:该接口用于相机的状态反馈。
- 激光雷达驱动接口:该接口用于激光雷达状态反馈。
- IMU接口:该接口用于IMU状态反馈。
- BMS接口:该接口用于BMS电量状态反馈。
- 遥控器接口:该接口用于躯干和底盘遥控器状态反馈。
手臂驱动接口
该接口是用于机械臂控制和状态反馈的ROS软件包,定义了多个话题用于发布和订阅臂的状态、控制命令和相关错误代码。接口信息如下所示:
| 话题名称 | I/O | 描述 | 消息类型 |
|---|---|---|---|
| /hdas/feedback_arm_left | Output | 左臂关节反馈 | sensor_msgs::msg::JointState |
| /hdas/feedback_arm_right | Output | 右臂关节反馈 | sensor_msgs::msg::JointState |
| /hdas/feedback_gripper_left | Output | 左夹爪行程 | sensor_msgs::msg::JointState |
| /hdas/feedback_gripper_right | Output | 右夹爪行程 | sensor_msgs::msg::JointState |
| /hdas/feedback_status_arm_left | Output | 左臂状态反馈* | hdas_msg::msg::FeedbackStatus |
| /hdas/feedback_status_arm_right | Output | 右臂状态反馈* | hdas_msg::msg::FeedbackStatus |
| /hdas/feedback_status_gripper_left | Output | 左夹爪状态反馈 | hdas_msg::msg::FeedbackStatus |
| /hdas/feedback_status_gripper_right | Output | 右夹爪状态反馈 | hdas_msg::msg::FeedbackStatus |
| /motion_control/control_arm_left | Input | 左臂电机控制 | hdas_msg::msg::MotorControl |
| /motion_control/control_arm_right | Input | 右臂电机控制 | hdas_msg::msg::MotorControl |
| /motion_control/control_gripper_left | Input | 左夹爪电机控制 | hdas_msg::msg::MotorControl |
| /motion_control/control_gripper_right | Input | 右夹爪电机控制 | hdas_msg::msg::MotorControl |
针对以上话题的具体字段及其详细描述如下表所示:
| 话题名称 | 字段 | 描述 |
|---|---|---|
| /hdas/feedback_arm_left | header | 标准消息头 |
| position | [关节1位置, 关节2位置, 关节3位置, 关节4位置, 关节5位置, 关节6位置, 关节7位置] | |
| velocity | [关节1速度, 关节2速度, 关节3速度, 关节4速度, 关节5速度, 关节6速度, 关节7速度] | |
| effort | [关节1力矩, 关节2力矩, 关节3力矩, 关节4力矩, 关节5力矩, 关节6力矩, 关节7力矩] | |
| /hdas/feedback_arm_right | header | 标准消息头 |
| position | [关节1位置, 关节2位置, 关节3位置, 关节4位置, 关节5位置, 关节6位置, 关节7位置] | |
| velocity | [关节1速度, 关节2速度, 关节3速度, 关节4速度, 关节5速度, 关节6速度, 关节7速度] | |
| effort | [关节1力矩, 关节2力矩, 关节3力矩, 关节4力矩, 关节5力矩, 关节6力矩, 关节7力矩] | |
| /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 | 包含错误码和对应的错误描述 | |
| /motion_control/control_arm_left (伺服模式) |
header | 标准消息头 |
| name | - | |
| p_des | [关节1位置, 关节2位置, 关节3位置, 关节4位置, 关节5位置, 关节6位置, 关节7位置] | |
| v_des | [关节1速度最大限制, 关节2速度最大限制, 关节3速度最大限制, 关节4速度最大限制, 关节5速度最大限制, 关节6速度最大限制, 关节7速度最大限制] | |
| t_ff | [关节1力矩最大限制, 关节2力矩最大限制, 关节3力矩最大限制, 关节4力矩最大限制, 关节5力矩最大限制, 关节6力矩最大限制, 关节7力矩最大限制] | |
| kp | 手臂电机kp | |
| kd | 手臂电机kd | |
| mode | - | |
| /motion_control/control_arm_right (伺服模式) |
header | 标准消息头 |
| name | - | |
| p_des | [关节1位置, 关节2位置, 关节3位置, 关节4位置, 关节5位置, 关节6位置, 关节7位置] | |
| v_des | [关节1速度最大限制, 关节2速度最大限制, 关节3速度最大限制, 关节4速度最大限制, 关节5速度最大限制, 关节6速度最大限制, 关节7速度最大限制] | |
| t_ff | [关节1力矩最大限制, 关节2力矩最大限制, 关节3力矩最大限制, 关节4力矩最大限制, 关节5力矩最大限制, 关节6力矩最大限制, 关节7力矩最大限制] | |
| kp | 手臂电机kp | |
| kd | 手臂电机kd | |
| 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/control_arm_left/motion_control/control_arm_right
下图为伺服模式模式架构:

p_des为控制的目标位置,v_des是用来限定运动过程中的最大绝对速度值。kp,kd为位置增益和速度增益的比例项;t_ff为前馈力矩;
注意:
-
以下是A2机械臂电机的推荐
kp和kd值,调整时请谨慎操作。R1_Pro_A2_left_kp = [2.0, 2.0, 2.0, 2.0, 2.0, 2.0, 2.0]R1_Pro_A2_left_kd = [25.0, 25.0, 25.0, 25.0, 25.0, 25.0, 25.0]R1_Pro_A2_right_kp = [2.0, 2.0, 2.0, 2.0, 2.0, 2.0, 2.0]R1_Pro_A2_right_kd = [25.0, 25.0, 25.0, 25.0, 25.0, 25.0, 25.0]
躯干驱动接口
该接口是用于躯干控制和提供状态反馈的ROS软件包,它定义了多个话题,用于发布和订阅躯干电机的状态和控制命令。接口信息如下所示:
| 话题名称 | I/O | 描述 | 消息类型 |
|---|---|---|---|
| /hdas/feedback_torso | Output | 躯干关节反馈 | sensor_msgs::msg::JointState |
| /hdas/feedback_status_torso | Output | 躯干状态反馈 | hdas_msg::msg::FeedbackStatus |
| /motion_control/control_torso | Input | 躯干电机控制(该接口不可主动发布消息) | hdas_msg::msg::MotorControl |
针对以上话题的具体字段及其详细描述如下表所示:
| 话题名称 | 字段 | 描述 |
|---|---|---|
| /hdas/feedback_torso | header | 标准消息头 |
| position | [关节1位置, 关节2位置, 关节3位置, 关节4位置] | |
| velocity | [关节1速度, 关节2速度, 关节3速度, 关节4速度] | |
| effort | 暂不使用 | |
| /hdas/feedback_status_torso | header | 标准消息头 |
| name_id | 关节名称 | |
| errors | 包含错误码和对应的错误描述 | |
| /motion_control/control_torso | header | 标准消息头(该接口不可主动发布消息) |
| name | - | |
| p_des | [关节1位置, 关节2位置, 关节3位置, 关节4位置] | |
| v_des | [关节1速度, 关节2速度, 关节3速度, 关节4速度] | |
| kp | [关节1kp, 关节2kp, 关节3kp, 关节4kp] | |
| kd | [关节1kd, 关节2kd, 关节3kd, 关节4kd] | |
| t_ff | [关节1力矩, 关节2力矩, 关节3力矩, 关节4力矩] | |
| mode | - |
底盘驱动接口
该接口是用于底盘状态反馈的ROS软件包,定义了多个话题以报告底盘电机的状态。以下是每个话题及其相关消息类型的详细描述:
| 话题名称 | I/O | 描述 | 消息类型 |
|---|---|---|---|
| /hdas/feedback_chassis | Output | 底盘轮毂和转向电机反馈 | sensor_msgs::msg::JointState |
| /hdas/feedback_status_chassis | Output | 底盘状态反馈 | hdas_msg::msg::FeedbackStatus |
| /motion_control/control_chassis | Input | 底盘轮毂和转向电机控制 | hdas_msg::msg::MotorControl |
针对以上话题的具体字段及其详细描述如下表所示:
| 话题名称 | 字段 | 描述 |
|---|---|---|
| /hdas/feedback_chassis | header | 标准消息头 |
| position | [左前轮角度, 右前轮角度, 后轮角度] | |
| velocity | [左前轮线速度, 右前轮线速度, 后轮线速度] [左前轮角速度, 右前轮角速度, 后轮角速度] |
|
| 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_chassis_front_left/rgb/compressed | Output | 底盘左前相机RGB压缩图 | sensor_msgs::msg::CompressedImage |
| /hdas/camera_chassis_front_right/rgb/compressed | Output | 底盘右前相机RGB压缩图 | sensor_msgs::msg::CompressedImage |
| /hdas/camera_chassis_left/rgb/compressed | Output | 底盘左相机RGB压缩图 | sensor_msgs::msg::CompressedImage |
| /hdas/camera_chassis_right/rgb/compressed | Output | 底盘右相机RGB压缩图 | sensor_msgs::msg::CompressedImage |
| /hdas/camera_chassis_rear/rgb/compressed | Output | 底盘后相机RGB压缩图 | sensor_msgs::msg::CompressedImage |
| /hdas/camera_wrist_left/color/image_raw/compressed | Output | 右腕相机RGB压缩图(如存在) | sensor_msgs::msg::CompressedImage |
| /hdas/camera_wrist_right/color/image_raw/compressed | Output | 左腕相机RGB压缩图(如存在) | sensor_msgs::msg::CompressedImage |
| /hdas/camera_head/left_raw/image_raw_color/compressed | Output | 头部相机RGB压缩图(如存在) | sensor_msgs::msg::CompressedImage |
| /hdas/camera_wrist_left/aligned_depth_to_color/image_raw | Output | 左腕相机深度图(如存在) | sensor_msgs::msg::Image |
| /hdas/camera_wrist_right/aligned_depth_to_color/image_raw | Output | 右腕相机深度图(如存在) | sensor_msgs::msg::Image |
| /hdas/camera_head/depth/depth_registered | Output | 头部相机深度图(如存在) | sensor_msgs::msg::Image |
针对以上话题的具体字段及其详细描述如下表所示:
| 话题名称 | 字段 | 描述 |
|---|---|---|
| /hdas/camera_chassis_front_left/rgb/compressed | header | 标准消息头 |
| format | JPEG | |
| data | 图像数据 | |
| /hdas/camera_chassis_front_right/rgb/compressed | header | 标准消息头 |
| format | JPEG | |
| data | 图像数据 | |
| /hdas/camera_chassis_left/rgb/compressed | header | 标 准消息头 |
| format | JPEG | |
| data | 图像数据 | |
| /hdas/camera_chassis_right/rgb/compressed | header | 标准消息头 |
| format | JPEG | |
| data | 图像数据 | |
| /hdas/camera_chassis_rear/rgb/compressed | header | 标准消息头 |
| format | JPEG | |
| data | 图像数据 | |
| /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_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 | 图像数据 | |
| /hdas/camera_head/depth/depth_registered | header | 标准消息头 |
| height | 取决于设置 | |
| width | 取决于设置 | |
| encoding | 32FC1 | |
| is_bigendian | 0 | |
| step | 取决于设置 | |
| data | 图像数据 |
激光雷达驱动接口
接口信息如下所示:
| 话题名称 | I/O | 描述 | 消息类型 |
|---|---|---|---|
| /hdas/lidar_chassis_left | Output | 雷达点云图 | sensor_msgs::msg::PointCloud2 |
针对以上话题的具体字段及其详细描述如下表所示:
| 话题名称 | 字段 | 描述 |
|---|---|---|
| /hdas/lidar_chassis_left | header | 标准消息头 |
| fields | 雷达数据 |
IMU 接口
接口信息如下所示::
| 话题名称 | I/O | 描述 | 消息类型 |
|---|---|---|---|
| /hdas/imu_chassis | Output | 底盘IMU反馈 | sensor_msgs::msg::Imu |
| /hdas/imu_torso | Output | 躯干IMU反馈 | sensor_msgs::msg::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::msg::Bms |
针对以上话题的具体字段及其详细描述如下表所示:
| 话题名称 | 字段 | 描述 |
|---|---|---|
| /hdas/bms | header | 标准消息头 |
| voltage | 电压 (V) | |
| current | 电流 (I) | |
| capital | 电量剩余 (%) |
遥控器接口
接口信息如下所示::
| 话题名称 | I/O | 描述 | 消息类型 |
|---|---|---|---|
| /controller | Output | 遥控器信号 | hdas_msg::msg::ControllerSignalStamped |
针对以上话题的具体字段及其详细描述如下表所示:
| 话题名称 | 字段 | 描述 |
|---|---|---|
| /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: 上位机控制 (底盘) |