A1XY Software Introduction ROS2
环境依赖
- 操作系统依赖:Ubuntu 22.04 LTS
- 中间件依赖:ROS Humble
软件版本日志
访问 Galaxea A1XY 软件版本更新日志 查看,获取最新的SDK包及更新信息。
首次操作指引
访问 Galaxea A1XY 开箱启动指南 ,并按照说明操作 Galaxea A1XY 。
启动SDK
当前支持 分开启动 方式启动软件接口。
操作指引如下:
模块名称 | 包含组件 | 路径 | 启动文件 |
---|---|---|---|
HDAS | Arms Driver |
{sdk_path}/install/HDAS/share/HDAS/launch | a1xy.py |
mobiman | Arm Control Gripper Control End Effector Pose Control |
{sdk_path}/install/mobiman/share/mobiman/launch/simpleExample/A1X | A1x_jointTrackerdemo_launch.py A1y_jointTrackerdemo_launch.py A1xy_gripperController_launch.py A1x_arm_relaxed_ik_launch.py A1y_arm_relaxed_ik_launch.py |
分开启动
所有节点可通过以下命令模板启动,配置方法如下:
注意:启动节点前,请您确认已正确配置CAN驱动。
sudo ip link set can0 type can bitrate 1000000 sample-point 0.875 dbitrate 5000000 fd on dsample-point 0.875
sudo ip link set up can0
# 若出现“RTNETLINK answers: Device or resource busy”这个错误信息,通常表示你尝试配置的设备(如网络接口或CAN收发器)已经被配置并且正在运行中。
各节点启动命令如下: - 环境变量设置(每个terminal运行程序前必须进行配置)
- 机械臂驱动(使用所有运控算法前必须启动) - 关节控制#A1X
ros2 launch mobiman A1x_jointTrackerdemo_launch.py
#A1Y
ros2 launch mobiman A1y_jointTrackerdemo_launch.py
#A1X
ros2 launch mobiman A1x_arm_relaxed_ik_launch.py
#A1Y
ros2 launch mobiman A1y_arm_relaxed_ik_launch.py
软件接口
驱动接口
话题名称 | I/O | 描述 | 消息类型 |
---|---|---|---|
/hdas/feedback_arm | Output | 各关节反馈位置/速度/力矩 | sensor_msgs::msg::JointState |
/hdas/feedback_gripper | Output | 末端夹爪反馈行程 | sensor_msgs::msg::JointState |
/hdas/feedback_status_arm | Output | 各关节状态反馈 | hdas_msg::msg::feedback_status |
/motion_control/control_arm | Input | 各关节电机控制接口 | hdas_msg::msg::motor_control |
hdas_msg/msg/MotorControl | Input | 末端夹爪电机控制接口 | hdas_msg::msg::motor_control |
/motion_control/position_control_gripper | Input | 末端夹爪行程控制接口 | std_msgs::msg::Float32 |
/hdas/function_frame_arm | Input | 机械臂功能帧 | hdas_msg::srv::FunctionFrame |
针对以上话题的具体字段及其详细描述如下表所示:
话题名称 | 字段 | 描述 |
---|---|---|
/hdas/feedback_arm | 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 | header | 标准消息头 |
position | [夹爪行程反馈] | |
velocity | 未使用 | |
effort | 未使用 | |
/hdas/feedback_status_arm | header | 标准消息头 |
name_id | 关节名称 | |
errors | 包含错误代码及描述 | |
/motion_control/control_arm | header | 标准消息头 |
name | - | |
p_des | [关节1目标位置, 关节2目标位置, 关节3目标位置, 关节4目标位置, 关节5目标位置, 关节6目标位置] | |
v_des | [关节1目标速度, 关节2目标速度, 关节3目标速度, 关节4目标速度, 关节5目标速度, 关节6目标速度] | |
kp | [关节1目标Kp, 关节2目标Kp, 关节3目标Kp, 关节4目标Kp, 关节5目标Kp, 关节6目标Kp] | |
kd | 关节1目标Kd, 关节2目标Kd, 关节3目标Kd, 关节4目标Kd, 关节5目标Kd, 关节6目标Kd] | |
t_ff | [关节1目标力矩, 关节2目标力矩, 关节3目标力矩, 关节4目标力矩, 关节5目标力矩, 关节6目标力矩] | |
mode | - | |
hdas_msg/msg/MotorControl | header | 标准消息头 |
name | - | |
p_des | [夹爪电机目标位置] | |
v_des | [夹爪电机目标速度] | |
kp | [夹爪电机目标Kp] | |
kd | [夹爪电机目标Kd] | |
t_ff | [夹爪电机目标力矩] | |
mode | - | |
/motion_control/position_control_gripper | header | 标准消息头 |
data | 目标夹爪行程, 控制范围 (0 to 100) mm | |
/hdas/function_frame_arm | command | 1: 使能 2: 失能 3: 整臂标定 4: 清除错误 5: MIT模式(嵌入式固件版本需大于2.1.3) 6: PID模式(嵌入式固件版本需大于2.1.3) |
运控接口
关节控制
接口信息如下:
话题名称 | I/O | 描述 | 消息类型 |
---|---|---|---|
/hdas/feedback_arm | Output | 手臂关节反馈 | hdas_msg::msg::motor_control |
/motion_control/control_arm | Input | 手臂电机控制 | hdas_msg::msg::otor_control |
/motion_target/target_joint_state_arm | Input | 各关节目标位置 | sensor_msgs::msg::JointState |
针对以上话题的具体字段及其详细描述如下表所示:
话题名称 | 字段 | 描述 |
---|---|---|
/motion_target/target_joint_state_arm | position | 这是一个包含六个元素的向量,代表每个关节的六个目标位置。 |
velocity | 这是一个包含六个元素的向量,代表每个关节在运动过程中的最大速度。最大速度如下:{3, 3, 3, 5, 5, 5, 5}。 加速度和加加速度限制设置为速度限制的1.5倍。 | |
/hdas/feedback_arm | - | 请参考手臂驱动接口 |
/motion_control/control_arm | - | 请参考手臂驱动接口 |
手臂姿态控制
- 当前末端姿态控制的相对位姿是URDF中gripper_link相对于base_link的姿态转换。以A1X为例,下图展示了gripper_link坐标系相对于base_link坐标系的相对关系,包含了x、y、z的偏移量以及orientation对应的旋转偏移。
该接口如下所示:
话题名称 | I/O | 描述 | 消息类型 |
---|---|---|---|
/hdas/pose_ee_arm | Output | 末端实际位姿 | geometry_msgs::msg::PoseStamped |
/hdas/feedback_arm | Output | 手臂关节反馈 | hdas_msg::msg::motor_control |
/motion_target/target_joint_state_arm | Input | 手臂关节目标 | sensor_msgs::msg::JointState |
/motion_control/pose_ee_arm | Input | 目标手臂末端执行器姿态 | geometry_msgs::PoseStamped |
针对以上话题的具体字段及其详细描述如下表所示:
话题名称 | 字段 | 描述 |
---|---|---|
/motion_target/target_pose_arm | 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 | - | 请参考手臂驱动接口 |
/motion_target/target_joint_state_arm | - | 请参考关节控制接口 |
夹爪控制
接口信息如下:
话题名称 | I/O | 描述 | 消息类型 |
---|---|---|---|
/motion_target/target_position_gripper | Input | 夹爪目标位置 | sensor_msgs::msg::JointState |
hdas_msg/msg/MotorControl | Input | 夹爪电机控制 | sensor_msgs::msg::JointState |
针对以上话题的具体字段及其详细描述如下表所示:
话题名称 | 字段 | 描述 |
---|---|---|
/motion_target/target_position_gripper | position | 表示夹爪的目标位置,[0,100],0为完全闭合,100为完全张开。 |
hdas_msg/msg/MotorControl | - | 请参考驱动接口 |