For simplified Chinese version: 简体中文版
This repository contains simulation models, and corresponding motion planning and controlling demos of the xArm series from UFACTORY. Developing environment: Ubuntu 20.04 + ROS Foxy.
- 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.
-
3.1 Install ROS Foxy
-
3.2 Install Moveit2
-
3.3 Install ros2_control, ros2_controllers
-
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 ros foxy environment settings first $ cd ~/dev_ws/src/ $ rosdep update $ rosdep install --from-paths . --ignore-src --rosdistro $ROS_DISTRO
-
# Remember to source ros foxy 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
. The defined service can only be activated at initialization if that service is configured totrue
.services: motion_enable: true set_mode: true set_state: true clean_conf: false ...
-
topics:
joint_states: is of type sensor_msgs::msg::JointState
xarm_states: is of type xarm_msgs::msg::RobotMsg
xarm_cgpio_states: is of type xarm_msgs::msg::CIOState
-
Launch and test
$ 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_xarm_states
-
-
This package defines the hardware interface for real xArm control under ros2.
$ cd ~/dev_ws/ # set 'add_gripper=true' to attach xArm gripper model $ ros2 launch xarm6_control_rviz_display.launch.py robot_ip:=192.168.1.117 [add_gripper:=true] # open up two rviz windows for two separated arms at the same time $ ros2 launch two_xarm6_control_rviz_display.launch.py robot1_ip:=192.168.1.117 robot2_ip:=192.168.1.203
-
This package provides abilities for controlling xArm (simulated or real arm) by moveit.
-
【simulated】Launch moveit, controlling xArm in rviz.
$ cd ~/dev_ws/ # set 'add_gripper=true' to attach xArm gripper model $ ros2 launch xarm_moveit_config xarm6_moveit_fake.launch.py [add_gripper:=true]
-
【real arm】Launch moveit, controlling xArm in rviz.
$ cd ~/dev_ws/ # 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]
-
【simulated x2】launch two moveit processes(including rviz),to control two xArms separately
$ cd ~/dev_ws/ # set 'add_gripper=true' to attach xArm gripper model $ ros2 launch xarm_moveit_config two_xarm6_moveit_fake.launch.py [add_gripper:=true]
-
【real arm x2】launch two moveit processes(including rviz),to control two xArms separately
$ cd ~/dev_ws/ # set 'add_gripper=true' to attach xArm gripper model $ ros2 launch xarm_moveit_config two_xarm6_moveit_realmove.launch.py robot1_ip:=192.168.1.117 robot2_ip:=192.168.1.203 [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. $ ros2 launch xarm_moveit_config dual_xarm6_moveit_fake.launch.py [add_gripper:=true]
-
【Dual real arm】Launch single moveit process, and controlling two xArms in one rviz.
$ cd ~/dev_ws/ # 'robot1_ip': IP address of left arm # 'robot2_ip': 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. $ ros2 launch xarm_moveit_config dual_xarm6_moveit_realmove.launch.py robot1_ip:=192.168.1.117 robot2_ip:=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】launch xarm_planner_node $ ros2 launch xarm_planner xarm6_planner_fake.launch.py [add_gripper:=true] # 【real arm】launch xarm_planner_node # $ ros2 launch xarm_planner xarm6_planner_realmove.launch.py robot_ip:=192.168.1.117 [add_gripper:=true] # run test program (control through API) $ ros2 launch xarm_planner test_xarm_planner_api_joint.launch.py dof:=6 $ ros2 launch xarm_planner test_xarm_planner_api_pose.launch.py dof:=6 # 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/ $ ros2 launch xarm_gazebo xarm6_beside_table_gazebo.launch.py
-
Simulation with moveit+gazebo (xArm controlled by moveit).
$ cd ~/dev_ws/ $ ros2 launch xarm_moveit_config xarm6_moveit_gazebo.launch.py
-
-
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
-