xArm

Introduction

This repository contains the 3D models of xArm series and demo packages for ROS development and simulations.Developing and testing environment: Ubuntu 16.04 + ROS Kinetic Kame + Gazebo 9. Instructions below is based on xArm7, other model user can replace 'xarm7' with 'xarm6' or 'xarm5' where applicable.

Update Summary

This package is still under development and improvement, tests, bug fixes and new functions are to be updated regularly in the future.

  • Add xArm 7 description files, meshes and sample controller demos for ROS simulation and visualization.
  • Add Moveit! planner support to control Gazebo virtual model and real xArm, but the two can not launch together.
  • Add Direct control of real xArm through Moveit GUI, please use it with special care.
  • Add xArm hardware interface to use ROS position_controllers/JointTrajectoryController on real robot.
  • Add xArm 6 and xArm 5 simulation/real robot control support.
  • Add simulation model of xArm Gripper.
  • Add demo to control dual xArm6 through Moveit.
  • Add xArm Gripper action control.
  • Add xArm-with-gripper Moveit development packages.

Go through the official tutorial documents


ROS Wiki: http://wiki.ros.org/
Gazebo Tutorial: http://gazebosim.org/tutorials
Gazebo ROS Control: http://gazebosim.org/tutorials/?tut=ros_control
Moveit tutorial: http://docs.ros.org/kinetic/api/moveit_tutorials/html/

Download the 'table' 3D model

  • In Gazebo simulator, navigate through the model database for 'table' item, drag and place the 3D model inside the virtual environment. It will then be downloaded locally, as 'table' is needed for running the demo.

Install "mimic_joint_plugin" for xArm Gripper simulation in Gazebo

  • If simulating xArm Gripper in Gazebo is needed, mimic_joint_plugin by courtesy of Konstantinos Chatzilygeroudis (@costashatz) needs to be installed in order to make the mimic joints behave normally in Gazebo. Usage of this plugin is inspired by this tutorial from @mintar.

Preparations before using this package

Install dependent package module

gazebo_ros_pkgs: http://gazebosim.org/tutorials?tut=ros_installing (if use Gazebo)
ros_control: http://wiki.ros.org/ros_control (remember to select your correct ROS distribution)
moveit_core: https://moveit.ros.org/install/

Getting started with 'xarm_ros'

Create a catkin workspace.

  • If you already have a workspace, skip and move on to next part. Follow the instructions in this page. Please note that this readme instruction assumes the user continues to use '~/catkin_ws' as directory of the workspace.

Obtain the package

$ cd ~/catkin_ws/src
$ git clone https://github.com/xArm-Developer/xarm_ros.git

Install other dependent packages:

$ rosdep update
$ rosdep check --from-paths . --ignore-src --rosdistro kinetic

Please change 'kinetic' to the ROS distribution you use. If there are any missing dependencies listed. Run the following command to install:

$ rosdep install --from-paths . --ignore-src --rosdistro kinetic -y

And chane 'kinetic' to the ROS distribution you use.

Package Description & Usage Guidance

xarm_description

  • xArm description files, mesh files and gazebo plugin configurations, etc. It's not recommended to change the xarm description file since other packages depend on it.

xarm_gazebo

  • Gazebo world description files and simulation launch files. User can add or build their own models in the simulation world file.

xarm_controller

  • Controller configurations, hardware_interface, robot command executable source, scripts and launch files. User can deploy their program inside this package or create their own. Note that effort controllers defined in xarm_controller/config are just examples for simulation purpose, when controlling the real arm, only 'position_controllers/JointTrajectoryController' interface is provided. User can add their self-defined controllers as well, refer to: http://wiki.ros.org/ros_control (controllers)

xarm_bringup

  • launch files to load xarm driver to enable direct control of real xArm hardware.

xarm7_moveit_config

  • Partially generated by moveit_setup_assistant, could use with Moveit Planner and Rviz visualization. If you have Moveit! installed, you can try the demo.

$ roslaunch xarm7_moveit_config demo.launch

To run Moveit! motion planner along with Gazebo simulator: If no xArm gripper needed, first run:

$ roslaunch xarm_gazebo xarm7_beside_table.launch

Then in another terminal:

$ roslaunch xarm7_moveit_config xarm7_moveit_gazebo.launch

If xArm gripper needs to be attached, first run:

$ roslaunch xarm_gazebo xarm7_beside_table.launch add_gripper:=true

Then in another terminal:

$ roslaunch xarm7_gripper_moveit_config xarm7_gripper_moveit_gazebo.launch

If you have a satisfied motion planned in Moveit!, hit the "Execute" button and the virtual arm in Gazebo will execute the trajectory.

To run Moveit! motion planner to control the real xArm: First make sure the xArm and the controller box are powered on, then execute:

$ roslaunch xarm7_moveit_config realMove_exec.launch robot_ip:=<your controller box LAN IP address>

Examine the terminal output and see if any error occured during the launch. If not, just play with the robot in Rviz and you can execute the sucessfully planned trajectory on real arm. But be sure it will not hit any surroundings before execution!

To run Moveit! motion planner to control the real xArm with xArm Gripper attached: First make sure the xArm and the controller box are powered on, then execute:

$ roslaunch xarm7_gripper_moveit_config realMove_exec.launch robot_ip:=<your controller box LAN IP address>

It is better to use this package with real xArm gripper, since Moveit planner will take the gripper into account for collision detection.

xarm_planner:

  • This implemented simple planner interface is based on move_group from Moveit! and provide ros service for users to do planning & execution based on the requested target, user can find detailed instructions on how to use it inside xarm_planner package.

To launch the xarm simple motion planner together with the real xArm:

$ roslaunch xarm_planner xarm_planner_realHW.launch robot_ip:=<your controller box LAN IP address> robot_dof:=<7|6|5>

Argument 'robot_dof' specifies the number of joints of your xArm (default is 7).

xarm_api/xarm_msgs:

  • These two packages provide user with the ros service wrapper of the functions in xArm SDK. There are 6 types of motion command (service names) supported:
  • move_joint: joint space point to point command, given target joint angles, max joint velocity and acceleration. Corresponding function in SDK is "set_servo_angle()".
  • move_line: straight-line motion to the specified Cartesian Tool Centre Point(TCP) target. Corresponding function in SDK is "set_position()"[blending radius not specified].
  • move_lineb: a list of via points followed by target Cartesian point. Each segment is straight-line with Arc blending at the via points, to make velocity continuous. Corresponding function in SDK is "set_position()"[blending radius specified].
  • move_line_tool: straight-line motion based on the Tool coordinate system rather than the base system. Corresponding function in SDK is "set_tool_position()".Please keep in mind that before calling the 4 motion services above, first set robot mode to be 0, then set robot state to be 0, by calling relavent services. Meaning of the commands are consistent with the descriptions in product user manual, other xarm API supported functions are also available as service call. Refer to xarm_msgs package for more details and usage guidance.
  • move_servo_cart/move_servoj: streamed high-frequency trajectory command execution in Cartesian space or joint space. Corresponding functions in SDK are set_servo_cartesian() and set_servo_angle_j(). An alternative way to implement velocity control. These two services operate the robot in mode 1. Special RISK ASSESMENT is required before using them. Please read the guidance carefully at chapter 7.2-7.3

Starting xArm by ROS service:

  • First startup the service server for xarm7, ip address is just an example:

$ roslaunch xarm_bringup xarm7_server.launch robot_ip:=192.168.1.128
  • Then make sure all the servo motors are enabled, refer to SetAxis.srv:

$ rosservice call /xarm/motion_ctrl 8 1
  • Before any motion commands, set proper robot mode(0: POSE) and state(0: READY) in order, refer to SetInt16.srv:

$ rosservice call /xarm/set_mode 0

$ rosservice call /xarm/set_state 0

Joint space or Cartesian space command example:

  • Please note that all the angles must use the unit of radian. All motion commands use the same type of srv request: Move.srv.

1. Joint space motion:

  • To call joint space motion with max speed 0.35 rad/s and acceleration 7 rad/s^2:

$ rosservice call /xarm/move_joint [0,0,0,0,0,0,0] 0.35 7 0 0
  • To go back to home (all joints at 0 rad) position with max speed 0.35 rad/s and acceleration 7 rad/s^2:

$ rosservice call /xarm/go_home [] 0.35 7 0 0

2. Cartesian space motion in Base coordinate:

  • To call Cartesian motion to the target expressed in robot BASE Coordinate, with max speed 200 mm/s and acceleration 2000 mm/s^2:

$ rosservice call /xarm/move_line [250,100,300,3.14,0,0] 200 2000 0 0

3. Cartesian space motion in Tool coordinate:

  • To call Cartesian motion expressed in robot TOOL Coordinate, with max speed 200 mm/s and acceleration 2000 mm/s^2, the following will move a relative motion (delta_x=50mm, delta_y=100mm, delta_z=100mm) along the current Tool coordinate, no orientation change:

$ rosservice call /xarm/move_line_tool [50,100,100,0,0,0] 200 2000 0 0

Motion service Return:

  • Please Note the above motion services will return immediately by default. If you wish to return until actual motion is finished, set the ros parameter "/xarm/wait_for_finish" to be true in advance. That is:

$ rosparam set /xarm/wait_for_finish true
  • Upon success, 0 will be returned. If any error occurs, 1 will be returned.

Tool I/O Operations:

  • We provide 2 digital, 2 analog input port and 2 digital output signals at the end I/O connector.

1. To get current 2 DIGITAL input states:

$ rosservice call /xarm/get_digital_in

2. To get one of the ANALOG input value: {{{$ rosservice call /xarm/get_analog_in 1 (last argument: port number, can only be 1 or 2) }}} 3. To set one of the Digital output:

$ rosservice call /xarm/set_digital_out 2 1  (Setting output 2 to be 1)
  • You have to make sure the operation is successful by checking responding "ret" to be 0.

Getting status feedback:

  • Having connected with a real xArm robot by running 'xarm7_server.launch', user can subscribe to the topic "xarm/xarm_states" for feedback information about current robot states, including joint angles, TCP position, error/warning code, etc. Refer to RobotMsg.msg for content details. Another option is subscribing to "/joint_states" topic, which is reporting in JointState.msg, however, currently only "position" field is valid; "velocity" is non-filtered numerical differentiation based on 2 adjacent position data, so it is just for reference; and we do not provide "effort" feedback yet.   In consideration of performance, current update rate of above two topics are set at 10Hz.

Setting Tool Center Point Offset:

  • The tool tip point offset values can be set by calling service "/xarm/set_tcp_offset". Refer to the figure below, please note this offset coordinate is expressed with respect to initial tool frame (Frame B), which is located at flange center, with roll, pitch, yaw rotations of (PI, 0, 0) from base frame (Frame A).

https://github.com/xArm-Developer/xarm_ros/blob/master/doc/xArmFrames.png

  • For example:

$ rosservice call /xarm/set_tcp_offset 0 0 20 0 0 0
  • This is to set tool frame position offset (x = 0 mm, y = 0 mm, z = 20 mm), and orientation (RPY) offset of ( 0, 0, 0 ) radians with respect to initial tool frame (Frame B in picture). Remember to set this offset each time the controller box is restarted !

Clearing Errors:

  • Sometimes controller may report error or warnings that would affect execution of further commands. The reasons may be power loss, position/speed limit violation, planning errors, etc. It needs additional intervention to clear. User can check error code in the message of topic "xarm/xarm_states" .

$ rostopic echo /xarm/xarm_states
  • If it is non-zero, the corresponding reason can be found out in the user manual. After solving the problem, this error satus can be removed by calling service "/xarm/clear_err" with empty argument.

$ rosservice call /xarm/clear_err
  • If using Moveit!, call "/xarm/moveit_clear_err" instead to avoid the need of setting mode 1 again manually.

$ rosservice call /xarm/moveit_clear_err
  • After calling this service, please check the err status again in 'xarm/xarm_states', if it becomes 0, the clearing is successful. Otherwise, it means the error/exception is not properly solved. If clearing error is successful, remember to set robot state to 0 to make it ready to move again!

Gripper Control:

  • If xArm Gripper (from UFACTORY) is attached to the tool end, the following services/actions can be called to operate or check the gripper.

1. Gripper services: (1) First enable the griper and configure the grasp speed:

$ rosservice call /xarm/gripper_config 1500
  • Proper range of the speed is from 1 to 5000. 1500 is used as an example. 'ret' value is 0 for success.

(2) Give position command (open distance) to xArm gripper:

$ rosservice call /xarm/gripper_move 500
  • Proper range of the open distance is from 0 to 850. 0 is closed, 850 is fully open. 500 is used as an example. 'ret' value is 0 for success.

(3) To get the current status (position and error_code) of xArm gripper:

$ rosservice call /xarm/gripper_state
  • If error code is non-zero, please refer to user manual for the cause of error, the "/xarm/clear_err" service can still be used to clear the error code of xArm Gripper.

2. Gripper action:

  • The xArm gripper move action is defined in Move.action. The goal consists of target pulse position and the pulse speed. By setting "true" of "use_gripper_action" argument in xarm_bringup/launch/xarm7_server.launch, the action server will be started. Gripper action can be called by:

$ rostopic pub -1 /xarm/gripper_move/goal xarm_gripper/MoveActionGoal "header:
  seq: 0
  stamp:
    secs: 0
    nsecs: 0
  frame_id: ''
goal_id:
  stamp:
    secs: 0
    nsecs: 0
  id: ''
goal:
  target_pulse: 500.0
  pulse_speed: 1500.0"
  • Alternatively:

$ rosrun xarm_gripper gripper_client 500 1500

Tool Modbus communication: If modbus communication with the tool device is needed, please first set the proper baud rate and timeout parameters through the "xarm/config_tool_modbus" service (refer to ConfigToolModbus.srv). For example:

$ rosservice call /xarm/config_tool_modbus 115200 20

The above command will configure the tool modbus baudrate to be 115200 bps and timeout threshold to be 20 ms. It is not necessary to configure again if these properties are not changed afterwards. Please note the first time to change the baud rate may return 1 (with error code 28), in fact it will succeed if the device is properly connected and there is no other exsisting controller errors. You can clear the error and call it once more to check if 0 is returned. Currently, only the following baud rates (bps) are supported: [4800, 9600, 19200, 38400, 57600, 115200, 230400, 460800, 921600, 1000000, 1500000, 2000000, 2500000].

Then the communication can be conducted like (refer to SetToolModbus.srv):

$ rosservice call /xarm/set_tool_modbus [0x01,0x06,0x00,0x0A,0x00,0x03] 7

First argument would be the uint8(unsigned char) data array to be sent to the modbus tool device, and second is the number of characters to be received as a response from the device. This number should be the expected data byte length +1 (without CRC bytes). A byte with value of 0x09 would always be attached to the head if received from tool modbus, and the rest bytes are response data from the device. For example, with some testing device the above instruction would reply:

ret: 0 respond_data: [9, 1, 6, 0, 10, 0, 3] and actual feedback data frame is: [0x01, 0x06, 0x00, 0x0A, 0x00, 0x03], with the length of 6 bytes.

Mode Change

  • xArm may operate under different modes depending on different controling methods. Current mode can be checked in the message of topic "xarm/xarm_states". And there are circumstances that demand user to switch between operation modes.

=== Mode Explanation===

  • Mode 0 : xArm controller (Position) Mode. Mode 1 : External trajectory planner (position) Mode. Mode 2 : Free-Drive (zero gravity) Mode.
  • Mode 0 is the default when system initiates, and when error occurs(collision, overload, overspeed, etc), system will automatically switch to Mode 0. Also, all the motion plan services in xarm_api package or the SDK motion functions demand xArm to operate in Mode 0. Mode 1 is for external trajectory planner like Moveit! to bypass the integrated xArm planner to control the robot. Mode 2 is to enable free-drive operation, robot will enter Gravity compensated mode, however, be sure the mounting direction and payload are properly configured before setting to mode 2.

Proper way to change modes:

  • If collision or other error happens during the execution of a Moveit! planned trajectory, Mode will automatically switch from 1 to default mode 0 for safety purpose, and robot state will change to 4 (error state). The robot will not be able to execute any Moveit command again unless the mode is set back to 1. The following are the steps to switch back and enable Moveit control again: (1) Make sure the objects causing the collision are removed. (2) clear the error:

$ rosservice call /xarm/clear_err
  • (3) switch to the desired mode (Mode 2 for example), and set state to 0 for ready:

$ rosservice call /xarm/set_mode 2

$ rosservice call /xarm/set_state 0
  • The above operations can also be done by calling relavant xArm SDK functions.

Other Examples

  • There are some other application demo examples in the example package, which will be updated in the future, feel free to explore it.


CategoryHomepage CategoryHomepage

Wiki: xarm (last edited 2020-07-01 10:40:44 by danielwang)