[Documentation] [TitleIndex] [WordIndex

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.

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

Install "mimic_joint_plugin" for xArm Gripper simulation in Gazebo

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.

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_gazebo

xarm_controller

xarm_bringup

xarm7_moveit_config

$ 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:

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:

Starting xArm by ROS service:

$ roslaunch xarm_bringup xarm7_server.launch robot_ip:=192.168.1.128

$ rosservice call /xarm/motion_ctrl 8 1

$ rosservice call /xarm/set_mode 0

$ rosservice call /xarm/set_state 0

Joint space or Cartesian space command example:

1. Joint space motion:

$ rosservice call /xarm/move_joint [0,0,0,0,0,0,0] 0.35 7 0 0

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

2. Cartesian space motion in Base coordinate:

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

3. Cartesian space motion in Tool coordinate:

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

Motion service Return:

$ rosparam set /xarm/wait_for_finish true

Tool I/O Operations:

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)

Getting status feedback:

Setting Tool Center Point Offset:

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

$ rosservice call /xarm/set_tcp_offset 0 0 20 0 0 0

Clearing Errors:

$ rostopic echo /xarm/xarm_states

$ rosservice call /xarm/clear_err

$ rosservice call /xarm/moveit_clear_err

Gripper Control:

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

$ rosservice call /xarm/gripper_config 1500

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

$ rosservice call /xarm/gripper_move 500

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

$ rosservice call /xarm/gripper_state

2. Gripper action:

$ 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"

$ 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

=== Mode Explanation===

Proper way to change modes:

$ rosservice call /xarm/clear_err

$ rosservice call /xarm/set_mode 2

$ rosservice call /xarm/set_state 0

Other Examples


CategoryHomepage CategoryHomepage


2023-10-28 13:11