Skip to content

Galaxea A1 Software Guide

We developed an efficient driver for converting serial signals through the slave computer, which has been released as a ROS (Robot Operating System) topic. This driver not only enables control of the slave computer but also retrieves feedback information and error codes from the device, facilitating two-way communication and real-time control. The tutorials will guide you on how to use this program to develop and operate Galaxea A1.

Software Dependency

  1. Ubuntu 20.04 LTS
  2. ROS Noetic

Installation

This SDK does not require recompilation. Please refer to the Developing and Operating Tutorials for direct usage instructions.

First Move

cd A1_SDK/install
source setup.bash
roslaunch mobiman eeTrackerdemo.launch
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}
}
}"

Developing and Operating Tutorials

A1 Driver Kit

  1. For the first use, after confirming the power supply and USB connection, run the following command to modify the read and write permissions of the serial port files:

    sudo chmod 777 /dev/ttyACM0
    

  2. After confirming the modification, you can initialize the SDK:

    cd A1_SDK/install
    source setup.bash
    roslaunch signal_arm single_arm_node.launch
    

The interface section describes the various control and status feedback interfaces for A1 robot arm, helping users understand how to communicate with and control the arm through the ROS package.

Driver Interface

The interface is a ROS package designed for manipulator control and status feedback. This package defines several topics for publishing and subscribing to the robot arm’s status, control commands, and associated error codes. Below are detailed descriptions of each topic and its related message types:

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
Topic Name Field Description Data Type Unit Remarks
/joint_states_host header Standard ROS Header - - -
name Robot Arm Joint Names string[] - -
position Robot Arm Joint Positions float64[] rad -
velocity Robot Arm Joint Velocities float64[] rad/s -
effort Robot Arm Joint Efforts float64[] Nm -
/arm_status_host header Standard ROS Header - - -
data.name Robot Arm Joint Names string[] - -
data.motor_errors.error_code Robot Arm Joint Error Codes float32[] - -
data.motor_errors.error_description Robot Arm Joint Error Descriptions float32[] °C -
/arm_joint_command_host header Standard ROS Header - - -
p_des Desired Position float32[] rad -
v_des Desired Velocity float32[] rad/s -
t_ff Desired Torque float32[] Nm -
kp Position Proportional Gain float32[] - -
kd Position Derivative Gain float32[] - -
mode Control Mode uint8 - Default is 0, MIT control
/gripper_force_control_host header Standard ROS Header - - -
gripper_force Gripper Force float32 N -
/gripper_position_control_host header Standard ROS Header - - -
gripper_stroke Desired Gripper Stroke float32 mm -
/gripper_stroke_host header Standard ROS Header - - -
name Gripper Names string[] - -
position Gripper Stroke float64[] mm -
velocity Gripper Velocity float64[] - -
effort Gripper Effort float64[] - -

Gripper Control Examples

  1. Gripper Force Control Interface
# Control the gripper to a specified force
# Positive gripper_force closes the gripper; negative gripper_force opens it
rostopic pub /gripper_force_control_host signal_arm/gripper_joint_command "header:
  seq: 0
  stamp:
    secs: 0
    nsecs: 0
  frame_id: ''
gripper_force: 10.0"
  1. Gripper Position Control Interface
# Control the gripper to a specified position, 60 for open, 0 for closed
rostopic pub /gripper_position_control_host signal_arm/gripper_position_control "header:
  seq: 0
  stamp:
    secs: 0
    nsecs: 0
  frame_id: ''
gripper_stroke: 40.0"

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

Joint and End-Effector Movement Control

We provide joint and end-effector movement control interfaces for Galaxea A1, enabling efficient control through the ROS (Robot Operating System) framework. Before performing end-effector or joint movement, you must first activate the signal_arm interface; detailed operation instructions can be found in the signal_arm documentation. This project includes several primary functions:

  • End-Effector Pose Movement: Allows users to control the position and orientation of the Galaxea A1's end-effector by publishing target pose messages. This function is suitable for applications requiring precise positioning.

  • End-Effector Trajectory Movement: Facilitates the movement of Galaxea A1's end-effector along a specified trajectory by publishing a series of pose messages. This function is ideal for complex path planning and execution.

  • Joint Angle Movement: Provides a joint-level control interface where users can set the target positions for each individual joint, enabling coordinated whole-arm movements.

End-Effector Pose Movement

  1. First, initiate the end-effector pose movement script. This will launch an RViz visualization for Galaxea A1, with the default joint positions set to zero.
    cd A1_SDK/install
    source setup.bash
    roslaunch mobiman eeTrackerdemo.launch
    
  2. In the file 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.
    
  3. Publish messages to the end-effector movement topic, specifically named /a1_ee_target. This operation is non-blocking, allowing for continuous message sending and enabling seamless movement of the robot arm's end-effector. However, it's critical that the target endpoint is not too far from the current position of the end-effector to avoid overstraining the mechanics or risking a collision.
    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
    
  4. Usage Example:

End-Effector Trajectory Movement

  1. Firstly, initiate the end-effector trajectory movement script. This will launch an RViz visualization for Galaxea A1, with the default joint positions set to zero.
    cd A1_SDK/install
    source setup.bash
    roslaunch mobiman eeTrajTrackerdemo.launch
    
  2. In the file 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.
    
  3. PPublish messages to specify a trajectory for the end-effector movement on the /arm_target_trajectory topic. This operation is non-blocking, allowing for continuous publishing. Ensure that the trajectory does not deviate significantly from the current end-effector position. It is recommended to wait until the current trajectory is completed before sending the next one to avoid inaccuracies in tracking the desired path.
    #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;
    }
    
  4. Usage Example:
End-Effector Pose Movement Interface
Topic Name Description Message Type
/a1_ee_target Target pose of end arm joint Geometry_msgs::PoseStamped
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

  1. Firstly, initiate the joint angle movement script. This will launch an RViz visualization for Galaxea A1, with the default joint positions set to zero.

    cd A1_SDK/install
    source setup.bash
    roslaunch mobiman jointTrackerdemo.launch
    

  2. In the file 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.
    
    Publish messages for joint movement on the /arm_joint_target_position topic. This operation is non-blocking, allowing for continuous publishing and enabling uninterrupted movement of the robot arm's joints.
    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 Position Movement Interface

The /joint_move is a ROS package for single-joint control of Galaxea A1. This package allows you to specify the movement of each joint from its current position to a target position, with configurable maximum speed and acceleration. If these parameters are not specified, default values will be used. The default maximum speed is 20 rad/s, and the default maximum acceleration is 20 rad/s². The topic names and fields of the movement interface are detailed in the following table.

Topic Name Description Message Type
/arm_joint_target_position Target position of each joint Sensor_msgs/JointState
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