Galaxea A1 Software Guide
我们研发了一款高效的驱动程序,它能够将从站计算机的串行信号转换,并集成至 ROS(机器人操作系统)平台。这款驱动程序不仅能控制从站计算机,还能从设备获取反馈信息和错误代码,实现双向通信和实时控制。
本教程将指导您如何利用此程序来开发和操作Galaxea A1。
软件依赖
- Ubuntu 20.04 LTS
- ROS Noetic
安装
这款SDK无需重新编译。请参考开发与操作教程直接使用。
首次操作
rostopic pub /a1_ee_target geometry_msgs/PoseStamped "{
header: {
seq: 0,
stamp: {secs: 0, nsecs: 0},
frame_id: 'world'
},
pose: {
position: {x: 0.08, y: 0.0, z: 0.5},
orientation: {x: 0.5, y: 0.5, z: 0.5, w: 0.5}
}
}"
开发与操作教程
A1驱动套件
- 首次使用时,在确认电源和USB连接后,运行以下命令修改串口文件的读写权限:
- 确认修改后,您可以初始化SDK: 接口部分描述了A1机械臂的各种控制和状态反馈接口,帮助用户了解如何通过ROS包连接和控制机械臂。
驱动接口
该接口是一个用于机械臂控制和状态反馈的ROS包,定义了多个话题用于发布和订阅臂的状态、控制命令和相关错误代码。以下是每个话题及其相关消息类型的详细描述:
话题名称 | 描述 | 消息类型 |
---|---|---|
/joint_states_host | 机械臂关节状态反馈 | sensor_msgs/JointState |
/arm_status_host | 机械臂电机状态反馈 | signal_arm/arm_status |
/arm_joint_command_host | 机械臂控制接口 | signal_arm/arm_control |
/gripper_force_control_host | 夹爪力控制接口 | signal_arm/gripper_joint_command |
/gripper_position_control_host | 夹爪位置控制接口 | signal_arm/gripper_position_control |
/gripper_stroke_host | 夹爪行程反馈接口 | sensor_msgs/JointState |
话题名称 | 字段 | 描述 | 数据类型 | 单位 | 备注 |
---|---|---|---|---|---|
/joint_states_host | header | 标准消息头 | - | - | - |
name | 关节名称 | string[] | - | - | |
position | 关节位置 | float64[] | rad | - | |
velocity | 关节速度 | float64[] | rad/s | - | |
effort | 关节力矩 | float64[] | Nm | - | |
/arm_status_host | header | 标准消息头 | - | - | - |
data.name | 关节名称 | string[] | - | - | |
data.motor_errors.error_code | 关节错误码 | float32[] | - | - | |
data.motor_errors.error_description | 关节错误描述 | float32[] | °C | - | |
/arm_joint_command_host | header | 标准消息头 | - | - | - |
p_des | 目标关节位置 | float32[] | rad | - | |
v_des | 目标关节速度 | float32[] | rad/s | - | |
t_ff | 目标关节力矩 | float32[] | Nm | - | |
kp | 目标关节kp | float32[] | - | - | |
kd | 目标关节kd | float32[] | - | - | |
mode | 控制模式 | uint8 | - | 默认0, MIT控制 | |
/gripper_force_control_host | header | 标准消息头 | - | - | - |
gripper_force | 夹持力 | float32 | N | - | |
/gripper_position_control_host | header | 标准消息头 | - | - | - |
gripper_stroke | 目标行程 | float32 | mm | - | |
/gripper_stroke_host | header | 标准消息头 | - | - | - |
name | 夹爪名称 | string[] | - | - | |
position | 夹爪行程 | float64[] | mm | - | |
velocity | 夹爪速度 | float64[] | - | - | |
effort | 夹爪力矩 | float64[] | - | - |
夹爪控制示例
- 夹爪力控制接口
- 夹爪位置控制接口
诊断故障代码
DTC用于反馈MCU和驱动器的错误信息,可用于查看每个电机的实时状态和驱动器的运行状态。以下是每个故障代码及其对应状态的详细描述:
DTC | 状态 |
---|---|
0 | 禁用 |
1 | 禁用 |
2 | 电机断开 |
3 | 位置跳跃 |
4 | 持续高电流 |
5 | 扭矩过大 |
6 | ECU -> MCU 超时 |
7 | 超出位置限制 |
8 | 超出速度限制 |
9 | 扭矩限制超出 |
10 | 过压 |
11 | 低压 |
12 | 过电流 |
13 | MOS 过温 |
14 | 电机绕组过温 |
15 | 通信丢失 |
16 | 过载 |
17 | 串行连接断开(无设备文件) |
18 | 设备文件已连接,无消息 |
19 | 串行读写失败 |
20 | 反馈接收溢出 |
关节和末端执行器运动控制
我们为 Galaxea A1 提供了关节和末端执行器运动控制接口,通过ROS(机器人操作系统)框架实现高效控制。在执行末端执行器或关节运动之前,您必须首先激活signal_arm
接口;详细操作说明可在signal_arm
文档中找到。该项目包括几个主要功能:
-
末端执行器姿态运动:允许用户通过发布目标姿态消息来控制Galaxea A1的末端执行器的位置和方向。这个功能适用于需要精确定位的应用。
-
末端执行器轨迹运动:通过发布一系列姿态消息,实现Galaxea A1末端执行器沿指定轨迹的运动。这个功能非常适合复杂的路径规划和执行。
- 关节角度运动:提供一个关节级别的控制接口,用户可以为每个关节设置目标位置,实现协调的整个手臂运动。
末端执行器姿态运动
-
首先,启动末端执行器姿态运动脚本。这将为Galaxea A1启动一个RViz可视化,默认关节位置设置为零。
-
在文件
eeTrackerdemo.launch
中:<param name="joint_states_topic" value="/joint_states" /> # the topic /joint_states represents the channel for acquiring simulated values, specifically the states of the robot's joints, within a simulation environment. <param name="arm_joint_command_topic" value="/arm_joint_command_host" /> # the topic /arm_joint_command_host topic represents the channel for issuing commands to the motors.
-
在
/a1_ee_target
话题上发布消息以控制末端执行器运动。此操作是非阻塞的,允许连续发布消息,实现末端执行器的无缝运动。但是,目标端点不要离末端执行器的当前位置太远,以避免过度拉伸机械结构或碰撞风险。rostopic pub /a1_ee_target geometry_msgs/PoseStamped "{ header: { seq: 0, stamp: {secs: 0, nsecs: 0}, frame_id: 'world' }, pose: { position: {x: 0.08, y: 0.0, z: 0.5}, orientation: {x: 0.5, y: 0.5, z: 0.5, w: 0.5} } }"
#!/usr/bin/env python import rospy from geometry_msgs.msg import PoseStamped def publish_pose(): rospy.init_node('pose_stamped_publisher', anonymous=True) pose_pub = rospy.Publisher('/a1_ee_target', PoseStamped, queue_size=10) # Create PoseStamped message pose_msg = PoseStamped() pose_msg.header.seq = 0 pose_msg.header.stamp = rospy.Time.now() pose_msg.header.frame_id = 'world' pose_msg.pose.position.x = 0. pose_msg.pose.position.y = 0. pose_msg.pose.position.z = 0. pose_msg.pose.orientation.x = 0. pose_msg.pose.orientation.y = 0. pose_msg.pose.orientation.z = 0. pose_msg.pose.orientation.w = 0. # Wait for subscribers to connect rospy.sleep(1) # Publish message pose_pub.publish(pose_msg) rospy.loginfo("Published PoseStamped message to /a1_ee_target") if __name__ == '__main__': try: publish_pose() except rospy.ROSInterruptException: pass
-
使用示例:
末端执行器轨迹运动
-
首先,启动末端执行器轨迹运动脚本。这将为Galaxea A1启动一个RViz可视化,默认关节位置设置为零。
-
在文件
eeTrajTrackerdemo.launch
中:<param name="joint_states_topic" value="/joint_states" /> # the /joint_states topic represents the channel for acquiring simulated values, specifically the states of the robot's joints, within a simulation environment. <param name="joint_command" value="/arm_joint_command_host" /> #the /arm_joint_command_host topic represents the channel for issuing commands to the motors.
-
在
/arm_target_trajectory
话题上发布消息,为末端执行器运动指定轨迹。此操作是非阻塞的,允许连续发布。确保轨迹不会显著偏离当前末端执行器的位置。建议在发送下一个轨迹之前等待当前轨迹完成,以避免跟踪所需路径时不准确。#include <ros/ros.h> #include <geometry_msgs/PoseArray.h> geometry_msgs::Pose createPose(double x, double y, double z, double w, double ox, double oy, double oz) { geometry_msgs::Pose pose; pose.position.x = x; pose.position.y = y; pose.position.z = z; pose.orientation.w = w; pose.orientation.x = ox; pose.orientation.y = oy; pose.orientation.z = oz; return pose; } int main(int argc, char** argv) { ros::init(argc, argv, "pose_array_publisher"); ros::NodeHandle nh; ros::Publisher pose_pub = nh.advertise<geometry_msgs::PoseArray>("/arm_target_trajectory", 10); // Wait for subscribers to connect ros::Rate wait_rate(10); while (pose_pub.getNumSubscribers() == 0) { wait_rate.sleep(); } geometry_msgs::PoseArray poseArrayMsg; poseArrayMsg.poses.push_back(createPose(0.08, 0.0, 0.3, 0.5, 0.5, 0.5, 0.5)); poseArrayMsg.poses.push_back(createPose(0.08, 0.0, 0.4, 0.5, 0.5, 0.5, 0.5)); poseArrayMsg.poses.push_back(createPose(0.08, 0.0, 0.54, 0.5, 0.5, 0.5, 0.5)); pose_pub.publish(poseArrayMsg); ROS_INFO("Published PoseArray with 3 poses"); return 0; }
-
演示示例:
末端执行器姿态运动接口
话题名称 | 描述 | 消息类型 |
---|---|---|
/a1_ee_target | 臂末端关节的目标姿态 | Geometry_msgs::PoseStamped |
话题名称 | 字段 | 描述 |
---|---|---|
/a1_ee_target | 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 | 旋转四元数 |
关节角度运动
-
首先,启动关节角度运动脚本。这将为Galaxea A1启动一个RViz可视化,默认关节位置设置为零。
-
在文件
jointTrackerdemo.launch
中:<param name="joint_states_sub_topic" value="/joint_states" /> # the /joint_states topic represents the channel for acquiring simulated values, specifically the states of the robot's joints, within a simulation environment. <param name="joint_command" value="/arm_joint_command_host" /> #the /arm_joint_command_host topic represents the channel for issuing commands to the motors.
-
在
/arm_joint_target_position
话题上发布关节运动的消息。此操作是非阻塞的,允许连续发布,使关节运动不间断。import rospy from sensor_msgs.msg import JointState def publish_joint_state(): rospy.init_node('joint_state_publisher', anonymous=True) pub = rospy.Publisher('/arm_joint_target_position', JointState, queue_size=10) rate = rospy.Rate(10) # 10 Hz joint_state = JointState() joint_state.header.seq = 0 joint_state.header.stamp = rospy.Time.now() joint_state.header.frame_id = 'world' joint_state.name = ['joint1', 'joint2', 'joint3', 'joint4', 'joint5', 'joint6'] joint_state.velocity = [] joint_state.effort = [] # Initialize positions to zeros joint_state.position = [0, 0, 0, 0, 0, 0] steps = 100 # Number of steps #to reach the target position target_position = [0.5, 0, 0, 0, 0, 0] step_increment = [(target - current) / steps for target, current in zip(target_position, joint_state.position)] for step in range(steps): joint_state.header.stamp = rospy.Time.now() # Update the timestamp joint_state.position = [current + increment for current, increment in zip(joint_state.position, step_increment)] pub.publish(joint_state) rate.sleep() rospy.loginfo("Published JointState message to /arm_joint_target_position") if __name__ == '__main__': try: publish_joint_state() except rospy.ROSInterruptException: pass
关节位置运动接口
/joint_move
是一个用于Galaxea A1单关节控制的ROS包。该包允许您指定每个关节从当前位置移动到目标位置,可配置最大速度和加速度。如果这些参数没有指定,默认值将被使用。默认最大速度是20 rad/s,默认最大加速度是20 rad/s²。运动接口的话题名称和字段如下表详细说明。
话题名称 | 描述 | 消息类型 |
---|---|---|
/arm_joint_target_position | 每个关节的目标位置 | Sensor_msgs/JointState |
话题名称 | 字段 | 描述 |
---|---|---|
/arm_joint_target_position | header | 标准消息头 |
name | 每个关节的名称 | |
position | 每个关节的目标位置 | |
velocity | 每个关节的最大速度 |