Galaxea A1 Software Guide
This guide will show you on how to develop and operate Galaxea A1.
Software Dependency
- OS Dependency: Ubuntu 20.04 LTS (Install dual systems on a PC without using a virtual machine.)
- Middleware Dependency: ROS Noetic
Obtain SDK
Click here to download SDK in our GitHub Community.It does not require recompilation. Please refer to the Developing and Operating Tutorials for direct usage instructions.
Alternatively, you can obtain the SDK using either of the following methods:
- Baidu Cloud:https://pan.baidu.com/s/1w-zctmpHBfk_Sqm2uihAaA?pwd=arm1
- Google Drive: https://drive.google.com/drive/folders/12oYeylWJWcaRDKeD2qG7xQNI7rFpBbel?usp=sharing
Developing and Operating Tutorial
Initial Setup
-
After confirming the power and USB connection, run the following command to modify the serial port file's read and write permissions:
-
After confirming the modification, initialize the SDK:
-
Click here to get the Demo scripts for A1.
Software Interface
Driver Interface
This interface is a ROS package for manipulator control and status feedback. It defines multiple topics for publishing and subscribing to the arm's status, control commands, and relevant error codes. Here's a detailed description of each topic and its related message type:
Topic Name | Description | Message Type |
---|---|---|
/joint_states_host | Robot Arm Joint State Feedback | sensor_msgs/JointState |
/arm_status_host | Robot Arm Motor State Feedback | signal_arm/arm_status |
/arm_joint_command_host | Robot Arm Control Interface | signal_arm/arm_control |
/gripper_force_control_host | Gripper Force Control Interface | signal_arm/gripper_joint_command |
/gripper_position_control_host | Gripper Position Control Interface | signal_arm/gripper_position_control |
/gripper_stroke_host | Gripper Stroke Feedback Interface | sensor_msgs/JointState |
The specific fields and their detailed descriptions for the above topic are shown in the table below:
Topic Name | Field | Description |
---|---|---|
/joint_states_host | header | Standard ROS Header |
name | Robot Arm Joint Names | |
position | Robot Arm Joint Positions | |
velocity | Robot Arm Joint Velocities | |
effort | Robot Arm Joint Efforts | |
/arm_status_host | header | Standard ROS Header |
data.name | Robot Arm Joint Names | |
data.motor_errors.error_code | Robot Arm Joint Error Codes | |
data.motor_errors.error_description | Robot Arm Joint Error Descriptions | |
/arm_joint_command_host | header | Standard ROS Header |
p_des | Desired Position | |
v_des | Desired Velocity | |
t_ff | Desired Torque | |
kp | Position Proportional Gain | |
kd | Position Derivative Gain | |
mode | Control Mode | |
/gripper_force_control_host | header | Standard ROS Header |
gripper_force | Gripper Force | |
/gripper_position_control_host | header | Standard ROS Header |
gripper_stroke | Desired Gripper Stroke | |
/gripper_stroke_host | header | Standard ROS Header |
name | Gripper Names | |
position | Gripper Stroke | |
velocity | Gripper Velocity | |
effort | Gripper Effort |
Gripper Control Examples
-
Gripper Force Control Interface
-
Gripper Position Control Interface
Diagnostic Trouble Code
DTC is used to feedback the error information of the MCU and the drive, and can be used to view the real-time status of each motor and the running status of the drive. The following is a detailed description of each fault code and its corresponding status.
DTC | Status |
---|---|
0 | Disabled |
1 | Disabled |
2 | Motor Disconnected |
3 | Position Jump |
4 | Continuous High Current |
5 | Excessive Torque |
6 | ECU -> MCU Timeout |
7 | Position Limit Exceeded |
8 | Speed Limit Exceeded |
9 | Torque Limit Exceeded |
10 | Overpressure |
11 | Low pressure |
12 | Overcurrent |
13 | MOS Overtemperature |
14 | Motor Winding Overtemperature |
15 | Communication loss |
16 | Overload |
17 | Serial Connection Disconnected (No Device File) |
18 | Device File Connected, No Messages |
19 | Serial Read/Write Failure |
20 | Feedback Reception Overflow |
Motion Control Interface
Galaxea A1 offers joint and end-effector motion control interfaces, enabling efficient control via the ROS framework. Activate the signal_arm
interface before executing end-effector or joint movements.
- End-Effector Pose Movement: Control the position and orientation of Galaxea A1's end-effector by publishing target pose messages. This is ideal for applications requiring precise positioning.
- End-Effector Trajectory Movement: Achieve Galaxea A1 end-effector motion along a specified trajectory by publishing a series of pose messages. This is suitable for complex path planning and execution.
- Joint Angle Movement: This interface allows joint-level control, letting you set target positions for each joint to coordinate the entire arm's movement.
End-Effector Pose Movement
- Launch the end-effector pose motion script. Start RViz visualization, with default joint positions set to zero.
- In the file
eeTrackerdemo.launch
, execute the following commands:<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.
- Publish messages on the
/a1_ee_target
topic to control end-effector motion. This operation is non-blocking, allowing continuous message publishing for seamless end-effector movement. However, ensure the target endpoint isn't too far from the current position to avoid over-stretching the mechanical structure or collision risks.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
- Demo Example:
End-Effector Trajectory Movement
-
Launch the end-effector trajectory motion script. Start RViz visualization, with default joint positions set to zero.
-
In the file
*
eeTrajTrackerdemo.launch`, execute the following commands:<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.
-
Publish messages on the
/arm_target_trajectory
topic to specify the trajectory for end-effector motion. This operation is non-blocking, allowing continuous publishing. Ensure the trajectory doesn't significantly deviate from the current end-effector position. It's advisable to wait for the current trajectory to complete before sending the next one to maintain path-tracking accuracy.#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; }
- Demo Example:
End-Effector Pose Movement Interface
Topic Name | Description | Message Type |
---|---|---|
/a1_ee_target | Target pose of end arm joint | Geometry_msgs::PoseStamped |
The specific fields and their detailed descriptions for the above topic are shown in the table below:
Topic Name | Field | Description |
---|---|---|
/a1_ee_target | header | Standard Header |
pose.position.x | Shift in x direction | |
pose.position.y | Shift in y direction | |
pose.position.z | Shift in z direction | |
pose.orientation.x | Orientation quaternion | |
pose.orientation.y | Orientation quaternion | |
pose.orientation.z | Orientation quaternion | |
pose.orientation.w | Orientation quaternion |
Joint Angle Movement
-
Launch the joint angle motion script. Start RViz visualization, with default joint positions set to zero.
-
In the file
jointTrackerdemo.launch
, execute the following commands:<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.
- Publish joint motion messages on the
/arm_joint_target_position
topic. This operation is non-blocking, allowing continuous publishing for uninterrupted joint motion.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) # 1 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 = [] joint_state.position = [0, 0, 0, 0, 0, 0] # Initial position steps = 100 # set steps target_position = [0.5, 0, 0, 0, 0, 0] # Target position # Calculate the step increment of each joint step_increment = [(target - current) / steps for target, current in zip(target_position, joint_state.position)] rospy.loginfo(f"Step increment: {step_increment}") # Waiting for subscribers to connect rospy.loginfo("Waiting for subscribers to connect...") while pub.get_num_connections() == 0 and not rospy.is_shutdown(): rospy.sleep(0.1) # 100ms waiting time rospy.loginfo("Subscribers connected, starting publishing...") # Start to publish JointState for step in range(steps): joint_state.header.stamp = rospy.Time.now() # Update time stamps 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 Position Movement Interface
/joint_move
is a ROS package for single-joint control of Galaxea A1. It allows specifying each joint's target position from its current position, with configurable maximum velocity and acceleration. If parameters aren't specified, default values are used. The default maximum velocity is 20 rad/s, and the default maximum acceleration is 20 rad/s². The topic name and fields of the motion interface are detailed in the table below.
Topic Name | Description | Message Type |
---|---|---|
/arm_joint_target_position | Target position of each joint | Sensor_msgs/JointState |
The specific fields and their detailed descriptions for the above topic are shown in the table below:
Topic Name | Field | Description |
---|---|---|
/arm_joint_target_position | header | Standard Header |
name | Name of each joint | |
position | Target position of each joint | |
velocity | Maximum velocity of each joint |