For simplified Chinese version: 简体中文版
This repository contains simulation models, and corresponding motion planning and controlling demos of the xArm series from UFACTORY. The development and test environment is as follows
- Ubuntu 20.04 + ROS Foxy
- Ubuntu 20.04 + ROS Galactic
- Ubuntu 22.04 + ROS Humble
Please switch to the corresponding code branch according to different ros2 versions (no corresponding code branch means it has not been tested in this version)
- moveit dual arm control (under single rviz GUI), each arm can be separately configured(e.g. DOF, add_gripper, etc)
- add support for Gazebo simulation, can be controlled by moveit.
- support adding customized tool model.
- (2022-09-07) Change the parameter type of service (set_tgpio_modbus_timeout/getset_tgpio_modbus_data), and add parameters to support transparent transmission
- (2022-09-07) Change topic name (xarm_states to robot_states)
- (2022-09-07) Update submodule xarm-sdk to version 1.11.0
- (2022-09-09) [Beta]Support Humble version
- (2022-10-10) xarm_api adds some services
-
3.1 Install ROS2
-
3.2 Install Moveit2
-
3.3 Install Gazebo
-
3.4 Install gazebo_ros_pkgs
-
# Skip this step if you already have a target workspace $ cd ~ $ mkdir -p dev_ws/src
-
$ cd ~/dev_ws/src # DO NOT omit "--recursive",or the source code of dependent submodule will not be downloaded. $ git clone https://github.com/xArm-Developer/xarm_ros2.git --recursive
-
$ cd ~/dev_ws/src/xarm_ros2 $ git pull $ git submodule sync $ git submodule update --init --remote
-
# Remember to source ros2 environment settings first $ cd ~/dev_ws/src/ $ rosdep update $ rosdep install --from-paths . --ignore-src --rosdistro $ROS_DISTRO -y
-
# Remember to source ros2 and moveit2 environment settings first $ cd ~/dev_ws/ # build all packages $ colcon build # build selected packages $ colcon build --packages-select xarm_api
Reminder 1: If there are multiple people using ros2 in the current LAN, in order to avoid mutual interference, please set ROS_DOMAIN_ID
Reminder 2: Remember to source the environment setup script before running any applications in xarm_ros2
$ cd ~/dev_ws/
$ source install/setup.bash
Reminder 3: All following instructions will base on xArm6,please use proper parameters or filenames for xArm5 or xArm7
-
This package contains robot description files and 3D models of xArm. Models can be displayed in RViz by the following launch file:
$ cd ~/dev_ws/ # set 'add_gripper=true' to attach xArm gripper model # set 'add_vacuum_gripper=true' to attach xArm vacuum gripper model # Notice:Only one end_effector can be attached (set to 'true'). $ ros2 launch xarm_description xarm6_rviz_display.launch.py [add_gripper:=true] [add_vacuum_gripper:=true]
-
This package contains all interface definitions for xarm_ros2, please check the instructions in the files before using them. README
-
This package serves as a submodule of this project,the corresponding git repository is: xArm-CPLUS-SDK, for interfacing with real xArms, please refer to the documentation in "xArm-CPLUS-SDK" if interested.
-
This package is a ros wrapper of "xarm_sdk",functions are implemented as ros service or ros topic,communications with real xArm in "xarm_ros2" are based on the services and topics provided in this part. All the services and topics are under xarm/ namespace by default(unless 'hw_ns' parameter is specified),e.g. full name for "joint_states" is actually "xarm/joint_states".
-
services: the name of provided services are the same with the corresponding function in SDK, however, whether to activate the service is up to the configuration under the "services" domain in
xarm_api/config/xarm_params.yaml
andxarm_api/config/xarm_user_params.yaml
. The defined service can only be activated at initialization if that service is configured totrue
. If you need to customize the parameters, please create a filexarm_api/config/xarm_user_params.yaml
to modify, the format, refer toxarm_api/config/xarm_params.yaml
.services: motion_enable: true set_mode: true set_state: true clean_conf: false ...
-
topics:
joint_states: is of type sensor_msgs::msg::JointState
robot_states: is of type xarm_msgs::msg::RobotMsg
xarm_cgpio_states: is of type xarm_msgs::msg::CIOState
uf_ftsensor_raw_states: is of type geometry_msgs::msg::WrenchStamped
uf_ftsensor_ext_states: is of type geometry_msgs::msg::WrenchStamped
Note:: some of the topics are only available when specific report_type is set at launch stage. Refer here.
-
Launch and test (xArm):
$ cd ~/dev_ws/ # launch xarm_driver_node $ ros2 launch xarm_api xarm6_driver.launch.py robot_ip:=192.168.1.117 # service test $ ros2 run xarm_api test_xarm_ros_client # topic test $ ros2 run xarm_api test_robot_states
-
Use command line (xArm):
$ cd ~/dev_ws/ # launch xarm_driver_node: $ ros2 launch xarm_api xarm6_driver.launch.py robot_ip:=192.168.1.117 # enable all joints: $ ros2 service call /xarm/motion_enable xarm_msgs/srv/SetInt16ById "{id: 8, data: 1}" # set proper mode (0) and state (0) $ ros2 service call /xarm/set_mode xarm_msgs/srv/SetInt16 "{data: 0}" $ ros2 service call /xarm/set_state xarm_msgs/srv/SetInt16 "{data: 0}" # Cartesian linear motion: (unit: mm, rad) $ ros2 service call /xarm/set_position xarm_msgs/srv/MoveCartesian "{pose: [300, 0, 250, 3.14, 0, 0], speed: 50, acc: 500, mvtime: 0}" # joint motion for xArm6: (unit: rad) $ ros2 service call /xarm/set_servo_angle xarm_msgs/srv/MoveJoint "{angles: [-0.58, 0, 0, 0, 0, 0], speed: 0.35, acc: 10, mvtime: 0}"
-
Use command line (lite6):
$ cd ~/dev_ws/ # launch ufactory_driver_node: $ ros2 launch xarm_api lite6_driver.launch.py robot_ip:=192.168.1.161 # enable all joints: $ ros2 service call /ufactory/motion_enable xarm_msgs/srv/SetInt16ById "{id: 8, data: 1}" # set proper mode (0) and state (0) $ ros2 service call /ufactory/set_mode xarm_msgs/srv/SetInt16 "{data: 0}" $ ros2 service call /ufactory/set_state xarm_msgs/srv/SetInt16 "{data: 0}" # Cartesian linear motion: (unit: mm, rad) $ ros2 service call /ufactory/set_position xarm_msgs/srv/MoveCartesian "{pose: [250, 0, 250, 3.14, 0, 0], speed: 50, acc: 500, mvtime: 0}" # joint motion: (unit: rad) $ ros2 service call /ufactory/set_servo_angle xarm_msgs/srv/MoveJoint "{angles: [-0.58, 0, 0, 0, 0, 0], speed: 0.35, acc: 10, mvtime: 0}"
Note: please study the meanings of Mode, State and available motion instructions before testing on the real robot. Please note the services provided by xArm series and Lite 6 have different namespaces.
-
-
This package defines the hardware interface for real xArm control under ros2.
$ cd ~/dev_ws/ # For xArm(xarm6 as example): set 'add_gripper=true' to attach xArm gripper model $ ros2 launch xarm_controller xarm6_control_rviz_display.launch.py robot_ip:=192.168.1.117 [add_gripper:=true] # For lite6: set 'add_gripper=true' to attach Lite6 gripper model $ ros2 launch xarm_controller lite6_control_rviz_display.launch.py robot_ip:=192.168.1.161 [add_gripper:=true]
-
This package provides abilities for controlling xArm/Lite6 (simulated or real arm) by moveit.
-
【simulated】Launch moveit, controlling robot in rviz.
$ cd ~/dev_ws/ # For xArm(xarm6 as example): set 'add_gripper=true' to attach xArm gripper model $ ros2 launch xarm_moveit_config xarm6_moveit_fake.launch.py [add_gripper:=true] # For Lite6: set 'add_gripper=true' to attach Lite6 gripper model $ ros2 launch xarm_moveit_config lite6_moveit_fake.launch.py [add_gripper:=true]
-
【real arm】Launch moveit, controlling robot in rviz.
$ cd ~/dev_ws/ # For xArm(xarm6 as example): set 'add_gripper=true' to attach xArm gripper model $ ros2 launch xarm_moveit_config xarm6_moveit_realmove.launch.py robot_ip:=192.168.1.117 [add_gripper:=true] # For Lite6: set 'add_gripper=true' to attach Lite6 gripper model $ ros2 launch xarm_moveit_config lite6_moveit_realmove.launch.py robot_ip:=192.168.1.161 [add_gripper:=true]
-
【Dual simulated】Launch single moveit process, and controlling two xArms in one rviz.
$ cd ~/dev_ws/ # set 'add_gripper=true' to attach xArm gripper model # 'add_gripper_1': can separately decide whether to attach gripper for left arm,default for same value with 'add_gripper' # 'add_gripper_2': can separately decide whether to attach gripper for right arm,default for same value with 'add_gripper' # 'dof_1': can separately configure the model DOF of left arm,default to be the same DOF specified in filename. # 'dof_2': can separately configure the model DOF of right arm,default to be the same DOF specified in filename. # For xArm (xarm6 here): $ ros2 launch xarm_moveit_config dual_xarm6_moveit_fake.launch.py [add_gripper:=true] # For Lite6: $ ros2 launch xarm_moveit_config dual_lite6_moveit_fake.launch.py [add_gripper:=true]
-
【Dual real arm】Launch single moveit process, and controlling two xArms in one rviz.
$ cd ~/dev_ws/ # 'robot_ip_1': IP address of left arm # 'robot_ip_2': IP address of right arm # set 'add_gripper=true' to attach xArm gripper model # 'add_gripper_1': can separately decide whether to attach gripper for left arm,default for same value with 'add_gripper' # 'add_gripper_2': can separately decide whether to attach gripper for right arm,default for same value with 'add_gripper' # 'dof_1': can separately configure the model DOF of left arm,default to be the same DOF specified in filename. # 'dof_2': can separately configure the model DOF of right arm,default to be the same DOF specified in filename. # For xArm (xarm6 here): $ ros2 launch xarm_moveit_config dual_xarm6_moveit_realmove.launch.py robot_ip_1:=192.168.1.117 robot_ip_2:=192.168.1.203 [add_gripper:=true] # For Lite6: $ ros2 launch xarm_moveit_config dual_lite6_moveit_realmove.launch.py robot_ip_1:=192.168.1.117 robot_ip_2:=192.168.1.203 [add_gripper:=true]
-
-
This package provides functions for controlling xArm (simulated or real arm) through moveit API
$ cd ~/dev_ws/ # 【simulated xArm】launch xarm_planner_node $ ros2 launch xarm_planner xarm6_planner_fake.launch.py [add_gripper:=true] # 【real xArm】launch xarm_planner_node $ ros2 launch xarm_planner xarm6_planner_realmove.launch.py robot_ip:=192.168.1.117 [add_gripper:=true] # 【simulated Lite6】launch xarm_planner_node $ ros2 launch xarm_planner lite6_planner_fake.launch.py [add_gripper:=true] # 【real Lite6】launch xarm_planner_node $ ros2 launch xarm_planner lite6_planner_realmove.launch.py robot_ip:=192.168.1.117 [add_gripper:=true] # In another terminal, run test program (control through API, specify 'robot_type' as 'xarm' or 'lite') $ ros2 launch xarm_planner test_xarm_planner_api_joint.launch.py dof:=6 robot_type:=<xarm | lite> $ ros2 launch xarm_planner test_xarm_planner_api_pose.launch.py dof:=6 robot_type:=<xarm | lite>
Below additional tests are just for xArm:
# run test program(control through service) $ ros2 launch xarm_planner test_xarm_planner_client_joint.launch.py dof:=6 $ ros2 launch xarm_planner test_xarm_planner_client_pose.launch.py dof:=6 # run test program(control gripper through API) $ ros2 launch xarm_planner test_xarm_gripper_planner_api_joint.launch.py dof:=6 # run test program(control gripper through service) $ ros2 launch xarm_planner test_xarm_gripper_planner_client_joint.launch.py dof:=6
-
This package is for supporting xArm simulation with Gazobo.
Notice:
(1) Installation of gazebo_ros2_control from source may be needed, as well as setting up environment variables of gazebo_ros2_control.
(2) minic_joint_plugin was developed for ROS1, we have modified a version for ROS2 compatibility and it is already integrated in this package for xArm Gripper simulation.-
Testing xarm on gazebo independently:
$ cd ~/dev_ws/ # For xArm (xarm6 here): $ ros2 launch xarm_gazebo xarm6_beside_table_gazebo.launch.py # For Lite6: $ ros2 launch xarm_gazebo lite6_beside_table_gazebo.launch.py
-
Simulation with moveit+gazebo (xArm controlled by moveit).
$ cd ~/dev_ws/ # For xArm (xarm6 here): $ ros2 launch xarm_moveit_config xarm6_moveit_gazebo.launch.py # For Lite6: $ ros2 launch xarm_moveit_config lite6_moveit_gazebo.launch.py
-
-
This package serves as a demo for jogging xArm with devices such as joystick, through moveit_servo.
-
Controlling with XBOX360 joystick:
- left stick for X and Y direction.
- right stick for ROLL and PITCH adjustment.
- left and right trigger (LT/RT) for Z direction.
- left and right bumper (LB/RB) for YAW adjustment.
- D-PAD for controlling joint1 and joint2.
- buttons X and B for controlling last joint.
- buttons Y and A for controlling second last joint.
$ cd ~/dev_ws/ # XBOX Wired -> joystick_type=1 # XBOX Wireless -> joystick_type=2 # For controlling simulated xArm: $ ros2 launch xarm_moveit_servo xarm_moveit_servo_fake.launch.py joystick_type:=1 # Or controlling simulated Lite6: $ ros2 launch xarm_moveit_servo xarm_moveit_servo_fake.launch.py dof:=6 robot_type:=lite joystick_type:=1 # For controlling real xArm: (use xArm 5 as example) $ ros2 launch xarm_moveit_servo xarm_moveit_servo_realmove.launch.py robot_ip:=192.168.1.123 dof:=5 joystick_type:=1 # Or controlling real Lite6: $ ros2 launch xarm_moveit_servo xarm_moveit_servo_realmove.launch.py robot_ip:=192.168.1.123 dof:=6 robot_type:=lite joystick_type:=1
-
Controlling with 3Dconnexion SpaceMouse Wireless:
- 6 DOFs of the mouse are mapped for controlling X/Y/Z/ROLL/PITCH/YAW
- Left button clicked for just X/Y/Z adjustment
- Right button clicked for just ROLL/PITCH/YAW adjustment
$ cd ~/dev_ws/ # For controlling simulated xArm: $ ros2 launch xarm_moveit_servo xarm_moveit_servo_fake.launch.py joystick_type:=3 # Or controlling simulated Lite6: $ ros2 launch xarm_moveit_servo xarm_moveit_servo_fake.launch.py dof:=6 robot_type:=lite joystick_type:=3 # For controlling real xArm: (use xArm 5 as example) $ ros2 launch xarm_moveit_servo xarm_moveit_servo_realmove.launch.py robot_ip:=192.168.1.123 dof:=5 joystick_type:=3 # Or controlling real Lite6: $ ros2 launch xarm_moveit_servo xarm_moveit_servo_realmove.launch.py robot_ip:=192.168.1.123 dof:=6 robot_type:=lite joystick_type:=3
-
Controlling with PC keyboard:
$ cd ~/dev_ws/ # For controlling simulated xArm: $ ros2 launch xarm_moveit_servo xarm_moveit_servo_fake.launch.py dof:=6 # Or controlling simulated Lite6: $ ros2 launch xarm_moveit_servo xarm_moveit_servo_fake.launch.py dof:=6 robot_type:=lite # For controlling real xArm: (use xArm 5 as example) $ ros2 launch xarm_moveit_servo xarm_moveit_servo_realmove.launch.py robot_ip:=192.168.1.123 dof:=5 # Or for controlling real Lite6: $ ros2 launch xarm_moveit_servo xarm_moveit_servo_realmove.launch.py robot_ip:=192.168.1.123 dof:=6 robot_type:=lite # Then in another terminal, run keyboad input node: $ ros2 run xarm_moveit_servo xarm_keyboard_input
Please note that Moveit Servo may consider the home position as singularity point, then try with joint motion first.
-
-
robot_ip, IP address of xArm, needed when controlling real hardware.
-
report_type, default: normal. Data report type, supported types are: normal/rich/dev, different types will report with different data contents and frequency.
-
dof, default: 7. Degree of freedom (DOF) of robot arm,no need to specify explicitly unless necessary. For dual arm launch files(with
dual_
prefix), DOF can be specified through:- dof_1
- dof_2
-
velocity_control, default: false. Whether to control with velocity interface. (Otherwise, use position interface)
-
add_gripper, default: false. Whether to include UFACTORY gripper in the model,it has higher priority than the argument
add_vacuum_gripper
. For dual arm launch files(withdual_
prefix), it can be specified through:- add_gripper_1
- add_gripper_2
-
add_vacuum_gripper, default: false. Whether to include UFACTRORY vacuum gripper in the model,
add_gripper
must be false in order to set vacuum gripper to be true. For dual arm launch files(withdual_
prefix), it can be specified through:- add_vacuum_gripper_1
- add_vacuum_gripper_2
-
add_other_geometry, default: false. Whether to add other geometric model as end-tool,
add_gripper
andadd_vacuum_gripper
has to be false in order to set it to be true.-
geometry_type, default: box, effective when
add_other_geometry=true
.
geometry type to be added as end-tool,valid types: box/cylinder/sphere/mesh. -
geometry_mass, unit: kg,default value: 0.1
model mass. -
geometry_height, unit: m,default value: 0.1
specifying geometry hight,effective when geometry_type=box/cylinder/sphere. -
geometry_radius, unit: m,default value: 0.1
specifying geometry radius, effective when geometry_type=cylinder/sphere. -
geometry_length, unit: m,default value: 0.1
specifying geometry length, effective when geometry_type=box. -
geometry_width, unit: m,default value: 0.1
specifying geometry width,effective when geometry_type=box. -
geometry_mesh_filename, filename of the specified mesh model,effective when geometry_type=mesh.
This file needs to be put inxarm_description/meshes/other/
folder. Such that full directory will not be needed in filename specification. -
geometry_mesh_origin_xyz, default: "0 0 0"
-
geometry_mesh_origin_rpy, default: "0 0 0"
transformation from end-flange coordinate frame to geometry model origin coordinate frame, effective whengeometry_type=mesh
. Example: geometry_mesh_origin_xyz:='"0.05 0.0 0.0"'. -
geometry_mesh_tcp_xyz, default: "0 0 0"
-
geometry_mesh_tcp_rpy, default: "0 0 0"
transformation from geometry model origin frame to geometry model tip ("Tool Center Point") frame, effective whengeometry_type=mesh
. Example: geometry_mesh_tcp_rpy:='"0.0 0.0 1.5708"'. -
Example of adding customized end tool (Cylinder):
$ ros2 launch xarm_gazebo xarm6_beside_table_gazebo.launch.py add_other_geometry:=true geometry_type:=cylinder geometry_height:=0.075 geometry_radius:=0.045
For dual arm launch files(with
dual_
prefix), here are the total arguments that can be configured:- add_other_geometry_1
- add_other_geometry_2
- geometry_type_1
- geometry_type_2
- geometry_mass_1
- geometry_mass_2
- geometry_height_1
- geometry_height_2
- geometry_radius_1,
- geometry_radius_2,
- geometry_length_1
- geometry_length_2
- geometry_width_1
- geometry_width_2
- geometry_mesh_filename_1
- geometry_mesh_filename_2
- geometry_mesh_origin_xyz_1
- geometry_mesh_origin_xyz_2
- geometry_mesh_origin_rpy_1
- geometry_mesh_origin_rpy_2
- geometry_mesh_tcp_xyz_1
- geometry_mesh_tcp_xyz_2
- geometry_mesh_tcp_rpy_1
- geometry_mesh_tcp_rpy_2
-