Git Product home page Git Product logo

xarm_ros's Introduction

For simplified Chinese version: 简体中文版
For UFACTORY Lite 6/850 users, make sure you have followed the instructions before chapter 4.7 on this page, then switch to ReadMe for Lite6/UF850.
For kinetic users, please use the kinetic branch.

Important Notice:

  Topic "xarm_cgpio_states" has been renamed to "controller_gpio_states".

  After using xArm C++ SDK as sub-module, the use of /xarm/set_tool_modbus service has been modified, compared with old version, the redundant '0x09' byte in response data has been removed
  Due to robot communication data format change, early users (xArm shipped before June 2019) are encouraged to upgrade their controller firmware immediately to drive the robot normally in future updates as well as to use newly developed functions. Please contact our staff to get instructions of the upgrade process. The old version robot driver can still be available in 'legacy' branch, however, it will not be updated any more.

  You MUST follow chapter 3 to install additional packages needed before any usage of xarm_ros packages. Otherwise, unexpected errors may occur.

  If developing with Moveit, it is highly recommended to use DIRECT network cable connection between controller box and your PC, and no intermediate switches or routers, or the communication latency may have a bad impact on trajectory execution.

   When updating this package, please remember to check the submodule update as well!

Contents:

1. 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/18.04/20.04 + ROS Kinetic/Melodic/Noetic.
Instructions below is based on xArm7, other model user can replace 'xarm7' with 'xarm6' or 'xarm5' where applicable.

2. 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.
  • Add vacuum gripper model and xArm-with-vacuum-gripper Moveit development packages (under /examples dir).
  • Thanks to Microsoft IoT, xarm_ros can now be compiled and run on Windows platform.
  • Add velocity control mode for joint and Cartesian space. (xArm controller firmware version >= 1.6.8 required)
  • Add support for custom tool model for Moveit
  • Add timed-out version of velocity control mode, for better safety consideration. (xArm controller firmware version >= 1.8.0 required)
  • Add xArm Vision and RealSense D435i related demo. Migrate previous "xarm_device" into xarm_vision/camera_demo.
  • xarm_controler (xarm_hw) no longer uses the SDK through service and topic, but directly calls the SDK interface.
  • Add text interpretation for Controller Error code, returned from "get_err" service.
  • Support UFACTORY Lite 6 model.
  • [Beta] Added two more torque-related topics (temporarily do not support third-party torque sensors): /xarm/uf_ftsensor_raw_states (raw data) and /xarm/uf_ftsensor_ext_states (filtered and compensated data)
  • (2022-09-07) Add service(set_tgpio_modbus_timeout/getset_tgpio_modbus_data), choose whether to transparently transmit Modbus data according to different parameters
  • (2022-09-07) Update submodule xarm-sdk to version 1.11.0
  • (2022-11-16) Add torque related services: /xarm/ft_sensor_enable, /xarm/ft_sensor_app_set, /xarm/ft_sensor_set_zero, /xarm/ft_sensor_cali_load, /xarm/get_ft_sensor_error
  • (2023-02-10) Added xarm_moveit_servo to support xbox controller/SpaceMouse/keyboard control
  • (2022-02-18) Automatically saving in service(/xarm/ft_sensor_cali_load) and add torque related service(/xarm/ft_sensor_iden_load)
  • (2023-02-27) Added service to control Lite6 Gripper(/ufactory/open_lite6_gripper, /ufactory/close_lite6_gripper, /ufactory/stop_lite6_gripper)(Note: Once stop, close will be invalid, you must open first to enable control)
  • (2023-03-29) Added the launch parameter model1300 (default is false), and replaced the model of the end of the xarm robot arm with the 1300 series
  • (2023-04-20) Update the URDF file, adapt to ROS1 and ROS2, and load the inertia parameters of the link from the configuration file according to the SN
  • (2023-04-20) Added launch parameter add_realsense_d435i (default is false), supports loading Realsense D435i model
  • (2023-04-20) Added the launch parameter add_d435i_links (default is false), which supports adding the link relationship between D435i cameras when loading the RealSense D435i model. It is only useful when add_realsense_d435i is true
  • (2023-04-20) Added the launch parameter robot_sn, supports loading the inertia parameters of the corresponding joint link, and automatically overrides the model1300 parameters
  • (2023-04-20) Added launch parameters attach_to/attach_xyz/attach_rpy to support attaching the robot arm model to other models
  • (2023-04-21) Added services usage documentation in xarm_api
  • (2023-06-07) Added support for UFACTORY850 robotic arm
  • (2023-06-07) Added uf_robot_moveit_config, support xArm/Lite6/UFACTORY850 series of robotic arm controls with moveit, which may replace these packages in the future. See instructions for uf_robot_moveit_config
    • xarm5_moveit_config
    • xarm5_gripper_moveit_config
    • xarm5_vacuum_moveit_config
    • xarm6_moveit_config
    • xarm6_gripper_moveit_config
    • xarm6_vacuum_moveit_config
    • xarm7_moveit_config
    • xarm7_gripper_moveit_config
    • xarm7_vacuum_moveit_config
    • lite6_moveit_config
  • (2023-10-12) Added the generation and use of joint kinematics parameter files (only supports uf_robot_moveit_config, see the description of the general parameter kinematics_suffix in uf_robot_moveit_config)

3. Preparations before using this package

3.1 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/

3.2 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/

3.3 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.

3.4 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.

12/22/2020: Refer to issue #53, Please Note this plugin has recently been deprecated, if you plan to use new version, please change "libroboticsgroup_gazebo_mimic_joint_plugin.so" to "libroboticsgroup_upatras_gazebo_mimic_joint_plugin.so" in files xarm_ros/xarm_gripper/urdf/xarm_gripper.gazebo.xacro and xarm_ros/xarm_description/urdf/gripper/xarm_gripper.gazebo.xacro.

4. Getting started with 'xarm_ros'

4.1 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.

4.2 Obtain the package

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

4.2.1 update the package

$ cd ~/catkin_ws/src/xarm_ros
$ git pull
$ git submodule sync
$ git submodule update --init --remote

4.3 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 change 'kinetic' to the ROS distribution you use.

4.4 Build the code

$ cd ~/catkin_ws
$ catkin_make

4.5 Source the setup script

$ echo "source ~/catkin_ws/devel/setup.bash" >> ~/.bashrc

Skip above operation if you already have that inside your ~/.bashrc. Then do:

$ source ~/.bashrc

4.6 First try out in RViz:

$ roslaunch xarm_description xarm7_rviz_display.launch

4.7 Run the demo in Gazebo simulator

$ roslaunch xarm_gazebo xarm7_beside_table.launch [run_demo:=true] [add_gripper:=true] [add_vacuum_gripper:=true] 

  Add the "run_demo" option if you wish to see a pre-programed loop motion in action. The command trajectory is written in xarm_controller\src\sample_motion.cpp. And the trajectory in this demo is controlled by pure position interface.
  Add the "add_gripper" option if you want to see the xArm Gripper attached at the tool end.
  Add the "add_vacuum_gripper" option if you want to see the xArm Vacuum Gripper attached at the tool end. Please note ONLY ONE end effector can be attached.

5. Package description & Usage Guidance

5.1 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.

5.2 xarm_gazebo

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

5.3 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)

5.4 xarm_bringup

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

5.5 xarm7_moveit_config

Please note: xarm_moveit_config related packages will limit all joints within [-pi, pi], it seems that moveit tend to generate plans involving greater joint motions if not limited within this range. This limit can be canceled by setting "limited:=false" in ...moveit_config/launch/planning_context.launch.

For any model which needs kinematic calibration correction added to the URDF, please check uf_robot_moveit_config, this is a unified moveit_config package for all our models and supports new features.

  This package is 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:

  1. 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
  1. 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.

  1. If xArm vacuum gripper needs to be attached, just replace "gripper" with "vacuum_gripper" in above gripper example.

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> [velocity_control:=false] [report_type:=normal]

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!

velocity_control is optional, if set to true, velocity controller and velocity interface will be used rather than position control. report_type is also optional, refer here.

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.

To run Moveit! motion planner to control the real xArm with xArm Vacuum Gripper attached:

First make sure the xArm and the controller box are powered on, then execute:

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

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

5.5.1 Add custom tool model for Moveit

  This part may require ROS Melodic or later versions to function well
  For xarm5_moveit_config/xarm6_moveit_config/xarm7_moveit_config, customized tool models maybe added to the tool flange through quick-configuration parameters listed below,thus to enable Tool offset and 3D collision checking during Moveit motion planning. (Notice:configuration through '/xarm/set_tcp_offset' service will not be effective in Moveit planning!)

Examples:

# attaching box model:
$ roslaunch xarm7_moveit_config demo.launch add_other_geometry:=true geometry_type:=box

# attaching cylinder model:
$ roslaunch xarm7_moveit_config demo.launch add_other_geometry:=true geometry_type:=cylinder

# attaching sphere model:
$ roslaunch xarm7_moveit_config demo.launch add_other_geometry:=true geometry_type:=sphere

# attaching customized mesh model:(Here take xarm vacuum_gripper as an example,if the mesh model could be placed in: 'xarm_description/meshes/other'directory,'geometry_mesh_filename' argument can be simplified to be just the filename)
$ roslaunch xarm7_moveit_config demo.launch add_other_geometry:=true geometry_type:=mesh geometry_mesh_filename:=package://xarm_description/meshes/vacuum_gripper/xarm/visual/vacuum_gripper.stl geometry_mesh_tcp_xyz:='"0 0 0.126"'

Argument explanations:

  • add_other_geometry: default to be false,indicating whether to add other geometry model to the tool.
  • geometry_type: geometry shapes to be added,as one of 'box/cylinder/sphere/mesh', there are different parameters required for different types.
  • geometry_height: height of geometry shape,unit: meter,default value: 0.1,effective for geometry_type: box/cylinder/sphere.
  • geometry_radius: radius of geometry shape,unit: meter,default value: 0.1,effective for geometry_type: cylinder/sphere.
  • geometry_length: length of geometry shape,unit: meter,default value: 0.1,effective for geometry_type: box.
  • geometry_width: width of geometry shape,unit: meter,default value: 0.1,effective for geometry_type: box.
  • geometry_mesh_filename: geometry shape,effective for geometry_type: mesh.
  • geometry_mesh_origin_xyz: position offset from mesh base coordinate to xarm tool-flange coordinate, default: "0 0 0",effective for geometry_type: mesh.
  • geometry_mesh_origin_rpy: orientation offset from mesh base coordinate to xarm tool-flange coordinate, default: "0 0 0",effective for geometry_type: mesh.
  • geometry_mesh_tcp_xyz: the positional TCP offset with respect to xarm tool-flange coordinate, default: "0 0 0",effective for geometry_type: mesh.
  • geometry_mesh_tcp_rpy: the orientational TCP offset with respect to xarm tool-flange coordinate, default: "0 0 0",effective for geometry_type: mesh.

5.6 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> add_(vacuum_)gripper:=<true|false>

Argument 'robot_dof' specifies the number of joints of your xArm (default is 7). Now xarm_planner supports model with gripper or vacuum_gripper attached. Please specify "add_gripper" or "add_vacuum_gripper" argument if needed.

5.7 xarm_api/xarm_msgs:

  These two packages provide user with the ros service wrapper of the functions in xArm SDK. There are 12 types of motion command (service names) supported,please set correct robot mode first, refer to mode change section:

Robot Mode 0:

  • 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: straight-line motion, and blending continuously with next motion. Normally works in the form of a list of known via points followed by target Cartesian point. Each motion segment is straight-line with Arc blending at the via points, to make velocity continuous. Corresponding function in SDK is "set_position()"[wait=false and blending radius specified]. Please refer to move_test.cpp and blended_motion_test.py for example code, /xarm/wait_for_finish parameter has to be false for successful blending calculation.

  • move_jointb: joint space point to point motion, and blending continuously with next motion. It can be used together with "move_lineb" for joint-linear blending motions, as long as the via points are known, and blending radius is properly specified, velocity will be continuous during the execution. Corresponding function in SDK is "set_servo_angle()"[wait=false and blending radius specified]. Please refer to blended_motion_test.py for example code. /xarm/wait_for_finish parameter has to be false for successful blending calculation.

  • 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_line_aa: straight-line motion, with orientation expressed in Axis-angle rather than roll-pitch-yaw angles. Please refer to xArm user manual for detailed explanation of axis-angle before using this command.

Robot Mode 1:

  • 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. Special RISK ASSESMENT is required before using them. Please read the guidance carefully at examples chapter 2-3.

Robot Mode 4:

Robot Mode 5:

  • velo_move_line/velo_move_line_timed: Linear motion of TCP with specified velocity in mm/s (position) and rad/s (orientation in axis-angular_velocity), with maximum linear acceleration configurable by set_max_acc_line service.

Robot Mode 6: (Firmware >= v1.10.0)

  • move_joint: Online joint space replanning to the new joint angles, with new max joint velocity and acceleration. Joint velocities and accelerations are continuous during transition, however the velocity profiles may not be synchronous and the final reached positions may have small errors. This function is mainly for dynamic response without self trajectory planning requirement like servo joint commands. /xarm/wait_for_finish parameter has to be false for successful transition. Corresponding function in SDK is "set_servo_angle(wait=false)" under mode 6. Instructions

Robot Mode 7: (Firmware >= v1.11.0)

  • move_line: Online Cartesian space replanning to the new target coordinate, with new max linear velocity and acceleration. Velocities and accelerations are continuous during transition, This function is mainly for dynamic response without self trajectory planning requirement like servo cartesian commands. /xarm/wait_for_finish parameter has to be false for successful transition. Corresponding function in SDK is "set_position(wait=false)" under mode 7. Instructions

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 report_type:=normal

The argument report_type is explained here.

  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
4. Cartesian space motion in Axis-angle orientation:

  Corresponding service for Axis-angle motion is MoveAxisAngle.srv. Please pay attention to the last two arguments: "coord" is 0 for motion with respect to (w.r.t.) Arm base coordinate system, and 1 for motion w.r.t. Tool coordinate system. "relative" is 0 for absolute target position w.r.t. specified coordinate system, and 1 for relative target position.
  For example: to move 1.0 radian relatively around tool-frame Z-axis:

$ rosservice call /xarm/move_line_aa "pose: [0, 0, 0, 0, 0, 1.0]
mvvelo: 30.0
mvacc: 100.0
mvtime: 0.0
coord: 1
relative: 1" 
ret: 0
message: "move_line_aa, ret = 0"

Or

$ rosservice call /xarm/move_line_aa [0,0,0,0,0,1.0] 30.0 100.0 0.0 1 1

  "mvtime" is not meaningful in this command, just set it to 0. Another example: in base-frame, to move 122mm relatively along Y-axis, and rotate around X-axis for -0.5 radians:

$ rosservice call /xarm/move_line_aa [0,122,0,-0.5,0,0] 30.0 100.0 0.0 0 1  
5. Joint velocity control:

  (xArm controller firmware version >= 1.6.8 required) If controlling joint velocity is desired, first switch to Mode 4 as descriped in mode change section. Please check the MoveVelo.srv first to understand the meanings of parameters reqired. If more than one joint are to move, set jnt_sync to 1 for synchronized acceleration/deceleration for all joints in motion, and if jnt_sync is 0, each joint will reach to its target velocity as fast as possible. coord parameter is not used here, just set it to 0. For example:

# NO Timed-out version (will not stop until all-zero velocity command received!):
$ rosservice call /xarm/velo_move_joint [0.1,-0.1,0,0,0,-0.3] 1 0
# With Timed-out version(controller firmware version >= 1.8.0): (if next velocity command not received within 0.2 seconds, xArm will stop)  
$ rosservice call /xarm/velo_move_joint_timed [0.1,-0.1,0,0,0,-0.3] 1 0 0.2

will command the joints (for xArm6) to move in specified angular velocities (in rad/s) and they will reach to target velocities synchronously. The maximum joint acceleration can also be configured by (unit: rad/s^2):

$ rosservice call /xarm/set_max_acc_joint 10.0  (maximum: 20.0 rad/s^2)
6. Cartesian velocity control:

  (xArm controller firmware version >= 1.6.8 required) If controlling linar velocity of TCP towards certain direction is desired, first switch to Mode 5 as descriped in mode change section. Please check the MoveVelo.srv first to understand the meanings of parameters reqired. Set coord to 0 for motion in world/base coordinate system and 1 for tool coordinate system. jnt_sync parameter is not used here, just set it to 0. For example:

# NO Timed-out version (will not stop until all-zero velocity command received!):  
$ rosservice call /xarm/velo_move_line [30,0,0,0,0,0] 0 1  
# With Timed-out version(controller firmware version >= 1.8.0): (if next velocity command not received within 0.2 seconds, xArm will stop)  
$ rosservice call /xarm/velo_move_line_timed [30,0,0,0,0,0] 0 1 0.2

will command xArm TCP move along X-axis of TOOL coordinate system with speed of 30 mm/s. The maximum linear acceleration can also be configured by (unit: mm/s^2):

$ rosservice call /xarm/set_max_acc_line 5000.0  (maximum: 50000 mm/s^2)

For angular motion in orientation, please note the velocity is specified as axis-angular_velocity elements. That is, [the unit rotation axis vector] multiplied by [rotation velocity value(scalar)]. For example,

# NO Timed-out version (will not stop until all-zero velocity command received!):
$ rosservice call /xarm/velo_move_line [0,0,0,0.707,0,0] 0 0
# With Timed-out version(controller firmware version >= 1.8.0): (if next velocity command not received within 0.2 seconds, xArm will stop)  
$ rosservice call /xarm/velo_move_line_timed [0,0,0,0.707,0,0] 0 0 0.2

This will command TCP to rotate along X-axis in BASE coordinates at about 45 degrees/sec. The maximum acceleration for orientation change is fixed.

Please Note: For no Timed-out version services: velocity motion can be stopped by either giving all 0 velocity command, or setting state to 4(STOP) and 0(READY) later for next motion. However, timed-out versions are more recommended for use, since it can be safe if network comminication or user program fails, controller firmware needs to be updated to v1.8.0 or later.

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.

Controller I/O Operations:

  We provide 8/16 digital input and 8/16 digital output ports at controller box for general usage.

1. To get one of the controller DIGITAL input state:
$ rosservice call /xarm/get_controller_din io_num (Notice: from 1 to 8, for CI0~CI7; from 9 to 16, for DI0~DI7[if any])  
2. To set one of the controller DIGITAL output:
$ rosservice call /xarm/set_controller_dout io_num (Notice: from 1 to 8, for CO0~CO7; from 9 to 16, for DI0~DI7[if any]) logic (0 or 1) 

  For example:

$ rosservice call /xarm/set_controller_dout 5 1  (Setting output 5 [lable C04] to be 1)
3. To get one of the controller ANALOG input:
$ rosservice call /xarm/get_controller_ain port_num  (Notice: from 1 to 2, for AI0~AI1)
4. To set one of the controller ANALOG output:
$ rosservice call /xarm/set_controller_aout port_num (Notice: from 1 to 2, for AO0~AO1) analog_value

  For example:

$ rosservice call /xarm/set_controller_aout 2 3.3  (Setting port AO1 to be 3.3)

  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, and "effort" feedback are current-based estimated values, not from direct torque sensor, so they are just for reference.   In consideration of performance, default update rate of above two topics are set at 5Hz. The report content and frequency have other options, refer to report_type argument

Setting Tool Center Point Offset(only effective for xarm_api ROS service control):

  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 default tool frame (Frame B), which is located at flange center, with roll, pitch, yaw rotations of (PI, 0, 0) from base frame (Frame A).
xArmFrames
  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). Note this offset might be overwritten by xArm Stdudio if it is not consistent with the default value set in studio! It is recommended to do the same TCP default offset configuration in xArm studio if you want to use it alongside with ros service control.

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 

Vacuum Gripper Control:

   If Vacuum Gripper (from UFACTORY) is attached to the tool end, the following service can be called to operate the vacuum gripper.

  To turn on:

$ rosservice call /xarm/vacuum_gripper_set 1

  To turn off:

$ rosservice call /xarm/vacuum_gripper_set 0

  0 will be returned upon successful execution.

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] 6

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 (without CRC bytes). For example, with some testing device the above instruction would reply:

ret: 0
respond_data: [1, 6, 0, 10, 0, 3]

and actual feedback data frame is: [0x01, 0x06, 0x00, 0x0A, 0x00, 0x03], with the length of 6 bytes.

"report_type" argument:

When launching real xArm ROS applications, the argument "report_type" can be specified. It decides the state feedback rate and content. Refer to the developer manual at chapter 2.1.6 Automatic Reporting Format for the report contents of the three available report type (normal/rich/dev), default type using is "normal".

  • For users who demand high-frequency feedback, report_type:=dev can be specified, then the topics /xarm/xarm_states and /xarm/joint_states will be published at 100Hz.
  • For users who want the gpio states being updated at /xarm/controller_gpio_states topic, please use report_type:=rich, since this reports the fullest information from the controller. As can be seen in developer manual.
  • The report rate of the three types:
type port No. Frequency GPIO topic F/T sensor topic
normal 30001 5Hz Not Available Not Available
rich 30002 5Hz Available Available
dev 30003 100Hz Not Available Available

Note: GPIO topic => xarm/controller_gpio_states. F/T sensor topic => xarm/uf_ftsensor_ext_states and xarm/uf_ftsensor_raw_states.

5.8 xarm_moveit_servo:

  This package serves as a demo for jogging xArm with devices such as joystick.

  • 5.8.1 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.
    # For controlling real xArm: (use xArm 6 as example)
    $ roslaunch xarm_moveit_servo xarm_moveit_servo_realmove.launch robot_ip:=192.168.1.206 dof:=6 joystick_type:=1
    # XBOX Wired -> joystick_type=1
    # XBOX Wireless -> joystick_type=2
    
    # Or controlling real Lite6
    $ roslaunch xarm_moveit_servo xarm_moveit_servo_realmove.launch robot_ip:=192.168.1.52 dof:=6 joystick_type:=1 robot_type:=lite
  • 5.8.2 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
    # For controlling real xArm: (use xArm 6 as example)
    $ roslaunch xarm_moveit_servo xarm_moveit_servo_realmove.launch robot_ip:=192.168.1.206 dof:=6 joystick_type:=3
    
    # Or controlling real Lite6
    $ roslaunch xarm_moveit_servo xarm_moveit_servo_realmove.launch robot_ip:=192.168.1.52 dof:=6 joystick_type:=3 robot_type:=lite
  • 5.8.3 Controlling with PC keyboard

    # For controlling real xArm: (use xArm 6 as example)
    $ roslaunch xarm_moveit_servo xarm_moveit_servo_realmove.launch robot_ip:=192.168.1.206 dof:=6 joystick_type:=99
    
    # Or controlling real Lite6
    $ roslaunch xarm_moveit_servo xarm_moveit_servo_realmove.launch robot_ip:=192.168.1.52 dof:=6 joystick_type:=99 robot_type:=lite

6. 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.

6.1 Mode Explanation

   Mode 0 : xArm controller (Position) mode.
   Mode 1 : External trajectory planner (position) mode.
   Mode 2 : Free-Drive (zero gravity) mode.
   Mode 3 : Reserved.
   Mode 4 : Joint velocity control mode.
   Mode 5 : Cartesian velocity control mode.
   Mode 6 : Joint space online planning mode. (Firmware >= v1.10.0)
   Mode 7 : Cartesian space online planning mode. (Firmware >= v1.11.0)

  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. Mode 4 is to control arm velocity in joint space. Mode 5 is to control arm (linear) velocity in Cartesian space. Mode 6 and 7 are for dynamic realtime response to newly generated joint or Cartesian target respectively, with automatic speed-continuous trajectoty re-planning.

6.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

7. xArm Vision

For simple demonstrations of vision application development with xArm, including hand-eye calibration and object detection and grasping. Examples are based on Intel RealSense D435i depth camera.

7.1 Installation of dependent packages:

First enter the workspace source directory:

$ cd ~/catkin_ws/src/

7.1.1 Install RealSense developer library and ROS package:

Please refer to the installation steps at official webpage.

7.1.2 Install 'aruco_ros', for hand-eye calibration:

Refer to official Github:

$ git clone -b kinetic-devel https://github.com/pal-robotics/aruco_ros.git

7.1.3 Install 'easy_handeye', for hand-eye calibration:

Refer to official Github:

$ git clone https://github.com/IFL-CAMP/easy_handeye

7.1.4 Install 'find_object_2d', for object detection:

Refer to official Github:

$ sudo apt-get install ros-kinetic-find-object-2d

7.1.5 Install other dependencies:

$ cd ~/catkin_ws

Then follow chapter 4.3.

7.1.6 Build the whole workspace:

$ catkin_make

7.2 Hand-eye Calibration Demo:

If attaching RealSense D435i camera at tool end of xArm, with mechanical adapters, making a "eye-on-hand"(or eye-in-hand) configuration,the following launch file can be used and modified for hand-eye calibration: (make sure the camera communication is functional and robot is properly switched on)

$ roslaunch d435i_xarm_setup d435i_xarm_auto_calib.launch robot_dof:=your_xArm_DOF robot_ip:=your_xArm_IP

Note: for xArm/UF850 produced after August 2023, kinematic calibration can be added to the URDF model, you can specify kinematics_suffix parameter for better accuracy, refer here for details.

The aruco Marker used inside can be downloaded here, please remember the marker ID and marker size and modify them in the launch file accordingly. Refer to officialor other usage instructions online and finish the calibration with the GUI.

If calculation result is confirmed and saved,it will appear by default under ~/.ros/easy_handeye directory and can be used for transferring object coordinates to base frame. If the camera_stand provided by UFACTORY is used for fixing camera, a sample calibration result is stored at xarm_vision/d435i_xarm_setup/config/xarm_realsense_handeyecalibration_eye_on_hand_sample_result.yaml for this case.

7.2.1 Hand-eye Calibration Demo for UFACTORY Lite6:

Please first read through the above instruction for xarm series, and use the files listed here for Lite6 calibration.

Sample calibration launch:

$ roslaunch d435i_xarm_setup d435i_lite6_auto_calib.launch robot_ip:=your_xArm_IP

Sample Calibration result file: lite6_realsense_handeyecalibration_eye_on_hand_sample_result.yaml

Sample calibration result TF publication: publish_handeye_tf_lite6.launch

7.2.2 Precautions for Hand-eye Calibration:

Since the position and orientation of the robot arm generated by easy_handeye by default does not change much, the final calibration result may not be too accurate or stable. In the actual calibration process, we do not need to use the position generated by easy_handeye. We can specify the startup parameter freehand_robot_movement:=true in the above command to start, and control the robotic arm to different positions through the xarm studio control interface or enable drag teaching. Then collect data through "Take Sample" of the activated hand-eye calibration window. After collecting about 17 data, calculate it through "Compute". It is recommended to rotate the rpy as much as possible to ensure that the calibration plate is within the field of view for the position of the robotic arm during each acquisition.

  • The angle between the rotation axes of the two movements should be as large as possible
  • The rotation angle corresponding to the rotation matrix of each movement should be as large as possible
  • The distance from the camera center to the calibration plate should be as small as possible
  • The distance moved by the end of the robot arm in each movement should be as small as possible

7.3 Vision Guided Grasping Demo:

find_object_2d is used for this demo for simple object detection and grasping. Hardware used in this part: RealSense D435i depth camera, UFACTORY camera stand and the xArm Gripper.

1.Use moveit to drive xArm's motion,recommended for singularity and collision free execution, but will require a reliable network connection.

$ roslaunch d435i_xarm_setup d435i_findobj2d_xarm_moveit_planner.launch robot_dof:=your_xArm_DOF robot_ip:=your_xArm_IP

If target object can be properly detected, to run the Grasping node:

$ rosrun d435i_xarm_setup findobj2d_grasp_moveit

Please note it will use previously mentioned sample handeye calibration result, you can change it at publish_handeye_tf.launch. For node program source code, refer to: d435i_xarm_setup/src/findobj_grasp_moveit_planner.cpp.

2.Alternatively, to drive xArm motion with ros service provided by 'xarm_api', in this way, real-time performance of network will not be required so strict as moveit way, but execution may fail in the middle if singularity or self-collision is about to occur.

$ roslaunch d435i_xarm_setup d435i_findobj2d_xarm_api.launch robot_dof:=your_xArm_DOF robot_ip:=your_xArm_IP

If target object can be properly detected, to run the Grasping node:

$ roslaunch d435i_xarm_setup grasp_node_xarm_api.launch

Please note it will use previously mentioned sample handeye calibration result, you can change it at publish_handeye_tf.launch. For node program source code, refer to: d435i_xarm_setup/src/findobj_grasp_xarm_api.cpp.

Please read and comprehend the source code and make necessary modifications before real application test, necessary modifications include preparation pose, grasping orientation, grasping depth, motion speed and so on. The identification target name in the code is "object_1", which corresponds to 1.png in /objects directory, users can add their own target in "find_object_2d" GUI, then modify the source_frame inside the code, for costomized application.

Tips: make sure the background is clean and the color is distinguished from the object, detection success rate can be higher if the target object has rich texture (features).

7.4 Adding RealSense D435i model to simulated xArm:

For installation with camera stand provided by UFACTORY, the cam model can be attached by following modifications (use xarm7 as example):

 $ roslaunch xarm7_moveit_config demo.launch add_realsense_d435i:=true

7.5 Color Cube Grasping Demo

7.5.1 Download 'gazebo_grasp_plugin' for successful grasp simulation (ROS Melodic and later)

 # enter source directory of ROS workspace:
 $ cd ~/catkin_ws/src/
 # Download through git (mind to checkout the proper branch):
 $ git clone https://github.com/JenniferBuehler/gazebo-pkgs.git
 $ git clone https://github.com/JenniferBuehler/general-message-pkgs.git
 # Compile:
 $ cd ..
 $ catkin_make

7.5.2 Gazebo grasping simulation (ROS Melodic and later)

 # Initialize gazebo scene and move_group:
 $ roslaunch xarm_gazebo xarm_camera_scene.launch robot_dof:=6

 # In another terminal, run the color recognition and grasping script:
 $ rosrun xarm_gazebo color_recognition.py

7.5.3 Real xArm and Intel realsense_d435i hardware

 # launch move_group:
 $ roslaunch camera_demo xarm_move_group.launch robot_ip:=192.168.1.15 robot_dof:=6 add_realsense_d435i:=true

 # In another terminal, run the color recognition and grasping script (use with interaction prompt):
 $ rosrun camera_demo color_recognition.py

8. 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.

xarm_ros's People

Contributors

bryanstuurman avatar chengkun avatar dependabot[bot] avatar eruvae avatar haotiangu avatar jimy92 avatar jkaniuka avatar kruusamae avatar ldemk avatar lilustga avatar penglongxiang avatar rvalner avatar vimior avatar wanglong06 avatar xqms avatar

Stargazers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar

Watchers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar

xarm_ros's Issues

Cannot control via MoveIt!

Thanks for developing the packages!

In the current master branch at 055b1ba, real robots cannot be controlled through MoveIt (execution fails).

The command I launched MoveIt is

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

as described in https://github.com/xArm-Developer/xarm_ros#to-run-moveit-motion-planner-to-control-the-real-xarm-with-xarm-gripper-attached.

And the error occurs as below,

[ INFO] [1606814705.233160442]: ABORTED: Solution found but controller failed during execution
[ INFO] [1606814806.654758866]: Planning request received for MoveGroup action. Forwarding to planning pipeline.
[ INFO] [1606814806.656490789]: Planner configuration 'xarm7[RRTConnect]' will use planner 'geometric::RRTConnect'. Additional configuration parameters will be set when the planner is constructed.
[ INFO] [1606814806.658114161]: xarm7[RRTConnect]: Starting planning with 1 states already in datastructure
[ INFO] [1606814806.658432332]: xarm7[RRTConnect]: Starting planning with 1 states already in datastructure
[ INFO] [1606814806.658749222]: xarm7[RRTConnect]: Starting planning with 1 states already in datastructure
[ INFO] [1606814806.659127183]: xarm7[RRTConnect]: Starting planning with 1 states already in datastructure
[ INFO] [1606814806.674514077]: xarm7[RRTConnect]: Created 4 states (2 start + 2 goal)
[ INFO] [1606814806.674824208]: xarm7[RRTConnect]: Created 4 states (2 start + 2 goal)
[ INFO] [1606814806.675870649]: xarm7[RRTConnect]: Created 5 states (2 start + 3 goal)
[ INFO] [1606814806.676187360]: xarm7[RRTConnect]: Created 5 states (2 start + 3 goal)
[ INFO] [1606814806.676898691]: ParallelPlan::solve(): Solution found by one or more threads in 0.019365 seconds
[ INFO] [1606814806.678005553]: xarm7[RRTConnect]: Starting planning with 1 states already in datastructure
[ INFO] [1606814806.678423674]: xarm7[RRTConnect]: Starting planning with 1 states already in datastructure
[ INFO] [1606814806.678815814]: xarm7[RRTConnect]: Starting planning with 1 states already in datastructure
[ INFO] [1606814806.679104555]: xarm7[RRTConnect]: Starting planning with 1 states already in datastructure
[ INFO] [1606814806.684202083]: xarm7[RRTConnect]: Created 4 states (2 start + 2 goal)
[ INFO] [1606814806.684395253]: xarm7[RRTConnect]: Created 5 states (2 start + 3 goal)
[ INFO] [1606814806.685232214]: xarm7[RRTConnect]: Created 5 states (2 start + 3 goal)
[ INFO] [1606814806.685583275]: xarm7[RRTConnect]: Created 5 states (2 start + 3 goal)
[ INFO] [1606814806.686071616]: ParallelPlan::solve(): Solution found by one or more threads in 0.008401 seconds
[ INFO] [1606814806.687052387]: xarm7[RRTConnect]: Starting planning with 1 states already in datastructure
[ INFO] [1606814806.687277807]: xarm7[RRTConnect]: Starting planning with 1 states already in datastructure
[ INFO] [1606814806.693070867]: xarm7[RRTConnect]: Created 4 states (2 start + 2 goal)
[ INFO] [1606814806.693313877]: xarm7[RRTConnect]: Created 4 states (2 start + 2 goal)
[ INFO] [1606814806.694019768]: ParallelPlan::solve(): Solution found by one or more threads in 0.007306 seconds
[ INFO] [1606814806.712420117]: SimpleSetup: Path simplification took 0.018009 seconds and changed from 3 to 2 states
[ INFO] [1606814807.706837994]: Execution request received
[ INFO] [1606814807.707018114]: Returned 0 controllers in list
[ERROR] [1606814807.707113044]: Unable to identify any set of controllers that can actuate the specified joints: [ joint1 joint2 joint3 joint4 joint5 joint6 joint7 ]
[ERROR] [1606814807.707210575]: Known controllers and their joints:

However, I confirmed this command works in 472f475, by checking out to the commit.

I doubt some changes to moveit control have been added between these commits, but I cannot find them.
Do you have any idea on the solution or reasons?

Thanks again for the active development!

Bug in ROS xarm_driver_node at shutdown

Hi,

When running roslaunch xarm_bringup xarm6_server.launch robot_ip:=<robot_ip> on the latest code, everything starts up and runs fine. However, when Ctrl-Cing the launch (which is only running the xarm_driver_node), I get the following error message - something to do with throwing an instance of 'std::system_error'. I think it's related to threading, but not sure how.

image

xarm_api bug

The ROS Service for getting the current error message should return a boolean, but it does not. This results in a compilation time warning in ROS Noetic on Ubuntu 20.04. See the function at

bool XARMDriver::GetErrCB(xarm_msgs::GetErr::Request & req, xarm_msgs::GetErr::Response & res)

Calling the set_tcp_offset ROS service

For whatever reason, after calling this service, the robot's state (as shown in the xarm_states topic) changes to '5'. The error code is 0, but if I ever call this service, I have to reset the state to 0 to work with the robot. From the RobotMsg message description, it doesn't even show '5' as an option (only 1 - 4). What does this mean, and why does it happen?

Error: material 'Black' is not unique

i work only with xarm7 but, by looking at the xacro files, i expect the behavior to be the same for all xarms. everything works just fine when you work with only one robot. but if you create a system with multiple robots (e.g., a xacro file that includes two xarm7s on a tabletop) and start parsing the xacro, there will be an error along the lines, "material 'Black' is not unique."
this happens because materials Black, Red, White, and Silver are defined (without prefix) in xarm7.urdf.xacro. easiest fix to the issue would be to add ${prefix} to wherever materials are defined and used, i.e., in files xarm7.urdf.xacro, xarm6.urdf.xacro, and xarm5.urdf.xacro.
however, i am not sure if this is the most intelligent way to fix the issue. any feedback from the maintainers would be much appreciated!

xarm_driver node crashing

Hello, I would like to report a strange behavior while using xarm7. This happens quite often for me.

xarm model: xarm7 with DC PSU
ROS version: melodic
using with moveit: yes
host computer: Jetson Xavier AGX

behavior:

  1. xarm_driver crashes while executing motion with moveit, sometimes with sudden abrupt movements.

  2. sometimes error happens even while stationary, like right after starting the node. Also if I leave ROS running and come back after lunch break, it would have crashed similarly. However robot never crashes or moves abruptly while using xArm studio.

Please see the following ROS log errors:

  1. while executing moveit trajectory, sudden abrupt movements occur and these errors are printed in rosconsole:
Error: real_data.flush_data failed, ret = -2
Error: real_data.flush_data failed, ret = -2
Error: real_data.flush_data failed, ret = -2
[ WARN] [1611033990.500463346]: joint 3 abnormal command! previous: -0.801784, this: -1.337893

[ WARN] [1611033990.501630547]: joint 4 abnormal command! previous: 0.463958, this: 0.393108

[ WARN] [1611033990.502213124]: joint 5 abnormal command! previous: 0.670980, this: 1.119614

[ WARN] [1611033990.503170286]: joint 6 abnormal command! previous: 1.059416, this: 0.517504

[ WARN] [1611033990.506442686]: joint 7 abnormal command! previous: -1.413036, this: -2.357749

SocketPort::recv_proc exit, 11
[ERROR] [1611033994.255229374]: Failed to call service move_servoj
[ERROR] [1611033994.255556321]: Failed to call service move_servoj
[ERROR] [1611033994.266150062]: Failed to call service move_servoj
[ERROR] [1611033994.275791115]: Failed to call service move_servoj
[xarm/xarm_driver-2] process has died [pid 19393, exit code -11, cmd /home/bgoat/catkin_ws/devel/lib/xarm_api/xarm_driver_node __name:=xarm_driver __log:=/mnt/1005750b-a346-4aa9-af8a-a586d9ec3c3e/.ros/log/b6316258-5a16-11eb-9225-48b02d2b82fa/xarm-xarm_driver-2.log].
log file: /mnt/1005750b-a346-4aa9-af8a-a586d9ec3c3e/.ros/log/b6316258-5a16-11eb-9225-48b02d2b82fa/xarm-xarm_driver-2*.log
[ERROR] [1611033994.285811458]: Failed to call service move_servoj
[ERROR] [1611033994.296369429]: Failed to call service move_servoj
[ERROR] [1611033994.305735174]: Failed to call service move_servoj
[ERROR] [1611033994.315706662]: Failed to call service move_servoj
  1. same behavior as above but node does not exit, instead prints error: socket_send_data endlessly.
[ERROR] [1612074783.132805788]: 
Invalid Trajectory: start point deviates from current robot state more than 0.01
joint 'joint1': expected: -3.1056, current: -1.39891
[ INFO] [1612074783.133137961]: Execution completed: ABORTED
SocketPort::recv_proc exit, 12
Error: real_data.flush_data failed, ret = -2
[ WARN] [1612074783.972975479]: joint 1 abnormal command! previous: -1.736944, this: -1.791387

[ WARN] [1612074783.973332710]: joint 2 abnormal command! previous: -0.780556, this: -0.927827

[ WARN] [1612074783.973896477]: joint 3 abnormal command! previous: 0.648341, this: 0.735660

[ WARN] [1612074783.974116902]: joint 4 abnormal command! previous: 0.317356, this: 0.515447

[ WARN] [1612074783.974246635]: joint 5 abnormal command! previous: 1.585996, this: 1.660190

[ WARN] [1612074783.974344143]: joint 6 abnormal command! previous: 0.623723, this: 0.940028

[ WARN] [1612074783.974489973]: joint 7 abnormal command! previous: -0.068890, this: -0.274293

[net work] error: socket_send_data
[net work] error: socket_send_data
[net work] error: socket_send_data
[net work] error: socket_send_data
[net work] error: socket_send_data
[net work] error: socket_send_data
[net work] error: socket_send_data
[net work] error: socket_send_data
[net work] error: socket_send_data
[net work] error: socket_send_data
[net work] error: socket_send_data
[net work] error: socket_send_data
  1. the following error is printed right after nodes are started and I am unable to move the robot.
[ INFO] [1612074897.322016087]: MoveGroup context using planning plugin ompl_interface/OMPLPlanner
[ INFO] [1612074897.322227072]: MoveGroup context initialization complete

You can start planning now!

[ INFO] [1612074897.886367954]: Recovery behavior will clear layer 'obstacles'
[ INFO] [1612074897.907037753]: Recovery behavior will clear layer 'obstacles'
[INFO] [1612074898.013211]: Started controllers: xarm7_traj_controller
[ INFO] [1612074898.049392203]: odom received!
Error: real_data.flush_data failed, ret = -2
Error: real_data.flush_data failed, ret = -2
sizeof_data = 69
Error: real_data.flush_data failed, ret = -1
[ WARN] [1612074904.602190357]: Could not grab single echo scan.
[ WARN] [1612074904.728127084]: Hardware Notification:RT IC2 Config error,1.61207e+12,Error,Hardware Error
[ERROR] [1612074904.729105268]: Performing Hardware Reset.
sizeof_data = 69
Error: real_data.flush_data failed, ret = -1
[ WARN] [1612074915.162202866]: Could not grab single echo scan.
Error: real_data.flush_data failed, ret = -2
sizeof_data = 69
Error: real_data.flush_data failed, ret = -1
[ WARN] [1612074925.982250721]: Could not grab single echo scan.
Error: real_data.flush_data failed, ret = -2
Error: real_data.flush_data failed, ret = -2
Error: real_data.flush_data failed, ret = -2

I will do my best to provide more information if needed. Thanks,

xArm API to control simulation

While we wait for my xArm to ship, I'd like to start prototyping the code to control it.

Can we use the xarm_ros and xArm-Python-SDK together to achieve it ? So we can write code with SDK functions, and observe motion in Gazebo.

Compiling error from the source code.

Hello.

I followed the x-arm 'read. me' file and installed all required dependencies.
But when I compiled the workspace, two errors show up and the compile was failed.
The error message is shown below, Would you please help me to check it? and how to solve this issue?
My ROS version is "ROS 16.04 kInetic", Thanks!!!!

[ 91%] Built target test_tool_modbus [ 91%] Built target sample_motion In file included from /usr/include/eigen3/Eigen/Core:297:0, from /usr/include/eigen3/Eigen/Geometry:11, from /opt/ros/kinetic/include/moveit/robot_model/joint_model.h:47, from /opt/ros/kinetic/include/moveit/robot_model/joint_model_group.h:41, from /opt/ros/kinetic/include/moveit/robot_model/robot_model.h:47, from /opt/ros/kinetic/include/moveit/robot_state/robot_state.h:41, from /opt/ros/kinetic/include/moveit/move_group_interface/move_group_interface.h:43, from /home/anson/xarm_github/src/xarm_ros/xarm_planner/src/xarm_gripper_planner.cpp:7: /usr/include/eigen3/Eigen/src/Geometry/Transform.h: In instantiation of ‘Eigen::Transform<Scalar, Dim, Mode, _Options>::Transform(const Eigen::Transform<_Scalar, Dim, OtherMode, OtherOptions>&) [with int OtherMode = 2; int OtherOptions = 0; _Scalar = double; int _Dim = 3; int _Mode = 1; int _Options = 0]’: /opt/ros/kinetic/include/moveit_visual_tools/moveit_visual_tools.h:227:45: required from here /usr/include/eigen3/Eigen/src/Core/util/StaticAssert.h:32:40: error: static assertion failed: YOU_PERFORMED_AN_INVALID_TRANSFORMATION_CONVERSION #define EIGEN_STATIC_ASSERT(X,MSG) static_assert(X,#MSG); ^ /usr/include/eigen3/Eigen/src/Geometry/Transform.h:330:5: note: in expansion of macro ‘EIGEN_STATIC_ASSERT’ EIGEN_STATIC_ASSERT(EIGEN_IMPLIES(OtherMode==int(Affine)||OtherMode==int(AffineCompact), Mode!=int(Isometry)), ^ In file included from /usr/include/eigen3/Eigen/Core:297:0, from /usr/include/eigen3/Eigen/Geometry:11, from /opt/ros/kinetic/include/moveit/robot_model/joint_model.h:47, from /opt/ros/kinetic/include/moveit/robot_model/joint_model_group.h:41, from /opt/ros/kinetic/include/moveit/robot_model/robot_model.h:47, from /opt/ros/kinetic/include/moveit/robot_state/robot_state.h:41, from /opt/ros/kinetic/include/moveit/move_group_interface/move_group_interface.h:43, from /home/anson/xarm_github/src/xarm_ros/xarm_planner/src/xarm_simple_planner.cpp:7: /usr/include/eigen3/Eigen/src/Geometry/Transform.h: In instantiation of ‘Eigen::Transform<Scalar, Dim, Mode, _Options>::Transform(const Eigen::Transform<_Scalar, Dim, OtherMode, OtherOptions>&) [with int OtherMode = 2; int OtherOptions = 0; _Scalar = double; int _Dim = 3; int _Mode = 1; int _Options = 0]’: /opt/ros/kinetic/include/moveit_visual_tools/moveit_visual_tools.h:227:45: required from here /usr/include/eigen3/Eigen/src/Core/util/StaticAssert.h:32:40: error: static assertion failed: YOU_PERFORMED_AN_INVALID_TRANSFORMATION_CONVERSION #define EIGEN_STATIC_ASSERT(X,MSG) static_assert(X,#MSG); ^ /usr/include/eigen3/Eigen/src/Geometry/Transform.h:330:5: note: in expansion of macro ‘EIGEN_STATIC_ASSERT’ EIGEN_STATIC_ASSERT(EIGEN_IMPLIES(OtherMode==int(Affine)||OtherMode==int(AffineCompact), Mode!=int(Isometry)), ^ [ 91%] Linking CXX executable /home/anson/xarm_github/devel/lib/xarm_api/xarm_driver_node [ 91%] Built target xarm_driver_node xarm_ros/xarm_planner/CMakeFiles/xarm_gripper_planner.dir/build.make:62: recipe for target 'xarm_ros/xarm_planner/CMakeFiles/xarm_gripper_planner.dir/src/xarm_gripper_planner.cpp.o' failed make[2]: *** [xarm_ros/xarm_planner/CMakeFiles/xarm_gripper_planner.dir/src/xarm_gripper_planner.cpp.o] Error 1 CMakeFiles/Makefile2:5552: recipe for target 'xarm_ros/xarm_planner/CMakeFiles/xarm_gripper_planner.dir/all' failed make[1]: *** [xarm_ros/xarm_planner/CMakeFiles/xarm_gripper_planner.dir/all] Error 2 make[1]: *** 正在等待未完成的任务.... xarm_ros/xarm_planner/CMakeFiles/xarm_simple_planner.dir/build.make:62: recipe for target 'xarm_ros/xarm_planner/CMakeFiles/xarm_simple_planner.dir/src/xarm_simple_planner.cpp.o' failed make[2]: *** [xarm_ros/xarm_planner/CMakeFiles/xarm_simple_planner.dir/src/xarm_simple_planner.cpp.o] Error 1 CMakeFiles/Makefile2:6097: recipe for target 'xarm_ros/xarm_planner/CMakeFiles/xarm_simple_planner.dir/all' failed make[1]: *** [xarm_ros/xarm_planner/CMakeFiles/xarm_simple_planner.dir/all] Error 2

xArm for ROS2

Dear xArm developers,

thanks for your awesome product, it is a great solution for needs of our team.
Could you tell, is the current xarm_ros package compatible with ROS2? If no, do you plan transferring your progress to ROS2?

Thanks in advance!

Rviz doesn't show the planned trajectory (trace)

Hello,

Recently, I learned the package of MoveIt! and try to use X-arm to do some simulations.
I met with a problem: RVIZ doesn't show the planned trajectory.

The code in the "xarm_simple_planner.CPP" in the x-arm planner_package, the "rviz_visul_tool" is already being used to show the information and the planned trajectory in Rviz. (Shown below)

image
image

And I also added the "Marker Array" tool in Rviz and subscribe to the right topic, the information is shown correctly:
image

But when I executed the "pose planning code", the robot trajectory was now shown in Rviz as the code...
rosservice call xarm_pose_plan 'target: [[0.28, 0.2, 0.2], [1.0, 0.0, 0.0, 0.0]]'
image

Could you please tell me how to let the rviz show the trajectory of the robot as in the picture below?
image

**I followed the detailed tutorial of the official moveit webpage and tried many ways to solve this problem, including modifying the rviz environment, robot model in Moveit_setup_assistant,and modifying the code...But still can not solve this problem.

Or is there any other way to show the trajectory like the picture above?
Many thanks for your help!!**

http://docs.ros.org/en/kinetic/api/moveit_tutorials/html/doc/move_group_interface/move_group_interface_tutorial.html

unnormalized quaternions

When roslaunch xarm*_moveit_config demo.launch, there are warning about unnormalized quaternions in that last link, which cause rviz to crash during development. How to fix this?

[ WARN] [1586333539.548156725]: Interactive marker 'EE:goal_link6' contains unnormalized quaternions. This warning will only be output once but may be true for others; enable DEBUG messages for ros.rviz.quaternions to see more details.

Questions on dual arm control

Hi,

I have a few questions on dual arm control.

  1. I would like to ask if it is possible to control dual arms in mode 0 through rosservice commands? Or is the dual arm control only possible in mode 1 using moveit?

  2. Is it possible to let the dual arm work and switch to different modes seperately from each other? For example, having the left arm working in mode 2, while the right arm is working in mode 1.

Thanks.

How to use move_servoj

Thank you for providing a wonderful robot arm.
This is a question when using with ROS.
Service message move_servoj has the same message type as move_joint.
move_joint is called as follows:
rosservice call / xarm / move_joint [0,0, -0.5,0,0,0,0] 0.35 7 0 0
Can move_servoj be called in the same way?
rosservice call / xarm / move_servoj [0,0, -0.5,0,0,0,0] 0.35 7 0 0
What does max speed 0.35 and acceleration 7 mean in that case?

Also, when teaching, is it OK to specify set_mode to 2 and then use the one that recorded the message / xarm / xarm_states?
If so, please let me know if there is a teaching sample for ROS.

xarm_gripper build problem

Hello
The package xarm_gripper fails when catkin build. I fixed the error. How can I commit it here and create pull request?

xarm last updates and how-to at the end of May 2020

  1. gripper in gazebo.
    I launch
    roslaunch xarm_gazebo xarm6_beside_table.launch add_gripper:=true
    and
    roslaunch xarm6_gripper_moveit_config xarm6_gripper_moveit_gazebo.launch
    and then in rviz when I choose planning group to xarm_gripper and click on Plan&Execute random valid goal I see error: Unable to identify any set of controllers that can actuate the specified joints: [ drive_joint ]
[ INFO] [1590564017.938652113, 33.026000000]: Planning request received for MoveGroup action. Forwarding to planning pipeline.
[ INFO] [1590564017.939214614, 33.027000000]: Planner configuration 'xarm_gripper' will use planner 'geometric::RRTConnect'. Additional configuration parameters will be set when the planner is constructed.
[ INFO] [1590564017.939659265, 33.027000000]: RRTConnect: Starting planning with 1 states already in datastructure
[ INFO] [1590564017.939719885, 33.027000000]: RRTConnect: Starting planning with 1 states already in datastructure
[ INFO] [1590564017.939799389, 33.027000000]: RRTConnect: Starting planning with 1 states already in datastructure
[ INFO] [1590564017.939940968, 33.027000000]: RRTConnect: Starting planning with 1 states already in datastructure
[ INFO] [1590564017.953521355, 33.041000000]: RRTConnect: Created 7 states (2 start + 5 goal)
[ INFO] [1590564017.953644197, 33.041000000]: RRTConnect: Created 7 states (2 start + 5 goal)
[ INFO] [1590564017.955738016, 33.041000000]: RRTConnect: Created 7 states (2 start + 5 goal)
[ INFO] [1590564017.955850722, 33.041000000]: RRTConnect: Created 8 states (2 start + 6 goal)
[ INFO] [1590564017.956544702, 33.041000000]: ParallelPlan::solve(): Solution found by one or more threads in 0.017047 seconds
[ INFO] [1590564017.956943353, 33.045000000]: RRTConnect: Starting planning with 1 states already in datastructure
[ INFO] [1590564017.957010164, 33.045000000]: RRTConnect: Starting planning with 1 states already in datastructure
[ INFO] [1590564017.958066013, 33.045000000]: RRTConnect: Starting planning with 1 states already in datastructure
[ INFO] [1590564017.958191260, 33.046000000]: RRTConnect: Starting planning with 1 states already in datastructure
[ INFO] [1590564017.960608571, 33.048000000]: RRTConnect: Created 7 states (2 start + 5 goal)
[ INFO] [1590564017.961609250, 33.049000000]: RRTConnect: Created 7 states (2 start + 5 goal)
[ INFO] [1590564017.962110127, 33.050000000]: RRTConnect: Created 7 states (2 start + 5 goal)
[ INFO] [1590564017.964275938, 33.052000000]: RRTConnect: Created 8 states (2 start + 6 goal)
[ INFO] [1590564017.965227264, 33.053000000]: ParallelPlan::solve(): Solution found by one or more threads in 0.008469 seconds
[ INFO] [1590564017.965442032, 33.053000000]: RRTConnect: Starting planning with 1 states already in datastructure
[ INFO] [1590564017.965487039, 33.053000000]: RRTConnect: Starting planning with 1 states already in datastructure
[ INFO] [1590564017.968904286, 33.057000000]: RRTConnect: Created 7 states (2 start + 5 goal)
[ INFO] [1590564017.968997145, 33.057000000]: RRTConnect: Created 7 states (2 start + 5 goal)
[ INFO] [1590564017.970238554, 33.057000000]: ParallelPlan::solve(): Solution found by one or more threads in 0.004848 seconds
[ INFO] [1590564018.000741571, 33.085000000]: SimpleSetup: Path simplification took 0.030395 seconds and changed from 6 to 2 states
[ INFO] [1590564026.934026733, 41.966000000]: Execution request received
[ INFO] [1590564026.934113786, 41.966000000]: Returned 1 controllers in list
[ERROR] [1590564026.934164558, 41.966000000]: Unable to identify any set of controllers that can actuate the specified joints: [ drive_joint ]
[ERROR] [1590564026.934221128, 41.966000000]: Known controllers and their joints:
controller '' controls joints:
  joint1
  joint2
  joint3
  joint4
  joint5
  joint6

[ INFO] [1590564026.943665812, 41.975000000]: ABORTED: Solution found but controller failed during execution

what does this error mean? Is gripper manipulation available in gazebo?

  1. gripper teleoperation. How can I do gripper teleoperation in gazebo?
    I tried to launch
    roslaunch xarm_gripper gazebo.launch and
    roslaunch xarm_gripper gripper_rviz_display.launch
    but it didnt work.

  2. gripper and xarm7. is gripper supported with xarm7?

  3. xarm and camera in simulation.
    How can I attach camera to gripper in gazebo simulation? Is there any launch file provided or I can do it manually?

Controller handle arm_controller reports status PREEMPTED

Hello,

I'm working with arm and time to time I receive next messages, when arm is moving. After that I need to restart node

[ INFO] [1598371134.336988967]: SimpleSetup: Path simplification took 0.007873 seconds and changed rom 4 to 2 states
[ INFO] [1598371135.875451622]: Execution request received
[ WARN] [1598371140.829753677]: Controller handle arm_controller reports status PREEMPTED
[ INFO] [1598371140.829787962]: Completed trajectory execution with status PREEMPTED ...  
[ INFO] [1598371140.829833516]: Execution completed: PREEMPTED  

What this issue means and how it could be resolved?

Commands executed to start moveit:

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

Info about the system:
Laptop:
Ubuntu 16.04
ROS Kinetic
Control box:
Firmware: 1.5.2
Xarm studio: 1.5.2

manual control using ps4 joystick

Hello,

I'm trying to make a node to control xarm7 using ps4 joystick without moveit.
Currently xarm7 has only position mode, not velocity mode. Am I right?
So it is hard to implement joystick manual control.

Is there a way to implement joystick manual control ?

catkin build fails

i am working on ROS Kinetic. even though catkin_make has no problems compiling xarm_ros, it is highly recommended to make it work with catkin build as well (https://catkin-tools.readthedocs.io/en/latest/migration.html)

currently. when i run caktin build, i get the following error:

CMake Warning at /opt/ros/kinetic/share/catkin/cmake/catkinConfig.cmake:76 (find_package):
Could not find a package configuration file provided by "xarm_api" with any
of the following names:

xarm_apiConfig.cmake
xarm_api-config.cmake

Add the installation prefix of "xarm_api" to CMAKE_PREFIX_PATH or set
"xarm_api_DIR" to a directory containing one of the above files. If
"xarm_api" provides a separate development package or SDK, be sure it has
been installed.
Call Stack (most recent call first):
CMakeLists.txt:10 (find_package)

move_servo_cart enhancement

Is it possible in a new update to have this ROS service return the joint commands that it's actually sending to the robot? It would make it easier to keep track in my own node of where each joint is supposed to be (which can't be reliably done at the moment).

Position feedback rate

Hi there,

is there some way to increase the frequency of the position feedback? We are using the xArm6 in a low-latency application. While we can provide commands with 100 Hz, the position feedback is only 5 Hz. It would be great if this could be improved :)

Accessing IOState

Is there a method to access IOState while using the ROS API? Doing research I found the following code commented out in xarm_driver_node.cpp:

// publish io state: This line may interfere with servoj execution
// xarm_driver.pub_io_state();

What specifically we are trying to do is to detect BOTH that the stop button is pressed or released. Currently we can detect if the stop button is pressed via the /xarm/xarm_states topic and checking if robot_msg.state == 4 but we cannot determine if the button is physically in the "up" or "ready" position.

One idea was to assign the "Emergency Stop" function to a digital pin and monitor the digital pin, but in ROS there seems to be no way to do this without getting and publishing the IOState message.

We also tried to do this by using the C++ SDK get_cgpio_state in a ROS node but that seems to cause issues with the ROS driver.

XArm questions on Gazebo

Ubuntu16.04
ROS kinetic

For the time being, I would like to run an XArm simulation with Gazebo and check the operation of the program I created.
Start Gazebo with the following command.
roslaunch xarm_gazebo xarm6_beside_table.launch add_gripper: = true
At that time, there are two questions.
1)
It seems that the gripper is not displayed properly. What is the cause?
2)
Which service should I use when trying to run XArm on Gazebo?
Which service will you use to set arm goals and speeds?
The list of current services is as follows.
$ rosservice list
/ gazebo / apply_body_wrench
/ gazebo / apply_joint_effort
/ gazebo / clear_body_wrenches
/ gazebo / clear_joint_forces
/ gazebo / delete_light
/ gazebo / delete_model
/ gazebo / get_joint_properties
/ gazebo / get_light_properties
/ gazebo / get_link_properties
/ gazebo / get_link_state
/ gazebo / get_loggers
/ gazebo / get_model_properties
/ gazebo / get_model_state
/ gazebo / get_physics_properties
/ gazebo / get_world_properties
/ gazebo / pause_physics
/ gazebo / reset_simulation
/ gazebo / reset_world
/ gazebo / set_joint_properties
/ gazebo / set_light_properties
/ gazebo / set_link_properties
/ gazebo / set_link_state
/ gazebo / set_logger_level
/ gazebo / set_model_configuration
/ gazebo / set_model_state
/ gazebo / set_parameters
/ gazebo / set_physics_properties
/ gazebo / spawn_sdf_model
/ gazebo / spawn_urdf_model
/ gazebo / unpause_physics
/ gazebo_gui / get_loggers
/ gazebo_gui / set_logger_level
/ gazebo_gui / set_parameters
/ robot_state_publisher / get_loggers
/ robot_state_publisher / set_logger_level
/ rosout / get_loggers
/ rosout / set_logger_level
/ xarm / controller_manager / list_controller_types
/ xarm / controller_manager / list_controllers
/ xarm / controller_manager / load_controller
/ xarm / controller_manager / reload_controller_libraries
/ xarm / controller_manager / switch_controller
/ xarm / controller_manager / unload_controller
/ xarm / xarm6_traj_controller / query_state

that's all, thank you very much.

Gripper control through MoveIT with real xarm7 not working

Hello,
I've faced with a problem when trying to control real Xarm7 gripper through MoveIT.
First of all, a real gripper position is not visualized with rviz, second - commands from moveit are not executed on real hand: planning is successful, but the execution fails with:

[ERROR] [1597913128.002681382]: Unable to identify any set of controllers that can actuate the specified joints: [ drive_joint ]
[ERROR] [1597913128.002724845]: Known controllers and their joints:
controller 'arm_controller' controls joints:
  joint1
  joint2
  joint3
  joint4
  joint5
  joint6
  joint7

Commands executed to start moveit:

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

Info about the system:
Laptop:
Ubuntu 16.04
ROS Kinetic
Control box:
Firmware: 1.5.2
Xarm studio: 1.5.2

Access Control box Analog Pins?

Hi is it possible to access the analog pins of the control box using this library or the only way is using the python SDK?

Thank you,

Ivan

/usr/bin/ld: cannot find -lxarm_ros_client

ROS: Melodic
Ubuntu 18.04
Gazebo: 9

Errors << xarm_controller:make /home/ubuntu/workspace/catkin-ws/logs/xarm_controller/build.make.001.log
/usr/bin/ld: cannot find -lxarm_ros_client
collect2: error: ld returned 1 exit status
make[2]: *** [/home/ubuntu/workspace/catkin-ws/devel/.private/xarm_controller/lib/xarm_controller/xarm_traj_controller] Error 1
make[1]: *** [CMakeFiles/xarm_traj_controller.dir/all] Error 2
make: *** [all] Error 2
cd /home/ubuntu/workspace/catkin-ws/build/xarm_controller; catkin build --get-env xarm_controller | catkin env -si /usr/bin/make --jobserver-fds=6,7 -j; cd -

Safety Tips

Hi,

I was just wondering what would happen if you called one of the ROS services (move_line, move_joint, mve_servo_cart, or move_servoj) to move the robot with either an invalid joint goal (one or more of the desired joint positions are above or below the URDF limits), or an invalid pose goal (either due to joint limits being violated or because the goal is physically impossible). I don't want to try this out on the physical robot in case I break it, so I'm asking it here. Does the internal robot controller take this into account no matter if you are in Mode 0 or Mode 1, or is this something the user must check before commanding the goals?

Thanks

Driver sends robot commands when controllers fail to load (!)

When starting up the robot driver before the robot_description parameter is set, it reports an error and outputs that no controllers were started up, but then sends zero-position commands to all joints! This is dangerous behavior.

You can reproduce the behavior by starting this launch file on a fresh roscore (you may also need a real robot). Commenting out the line that uploads robot_description causes the bug to occur.

<?xml version="1.0"?>
<launch>
  <arg name="robot_ip" default="192.168.1.214"/>

  <!-- If this line is removed, the driver sends joint commands upon startup -->
  <param name="robot_description" command="xacro --inorder  '$(find xarm_description)/urdf/xarm6_robot.urdf.xacro' limited:=true"/>

  <remap from="/xarm/joint_states" to="/joint_states"/>
  <include file="$(find xarm_bringup)/launch/xarm6_server.launch">
    <arg name="robot_ip" value="$(arg robot_ip)" />
    <arg name="use_moveit" value="true" />
    <arg name="ns" value="xarm" />
  </include>
  
  <rosparam file="$(find xarm_controller)/config/xarm6_traj_controller.yaml" command="load"/>
  <node
    name="traj_controller_spawner"
    pkg="controller_manager"
    type="spawner"
    respawn="false"
    output="screen"
    ns="xarm"
    args="xarm6_traj_controller"/>
</launch>

Here is the terminal output when no robot_description is found:

process[xarm/traj_controller_spawner-1]: started with pid [59136]
process[xarm/xarm_driver-2]: started with pid [59137]
process[xarm/xarm_traj_controller-3]: started with pid [59138]
[ INFO] [1614739172.494982512]: start xarm driver
Tcp Report Norm connection successful
Tcp Control connection successful
[INFO] [1614739172.724230]: Controller Spawner: Waiting for service controller_manager/load_controller
[ INFO] [1614739174.742081852]: motion enable, ret = 0

[ INFO] [1614739174.756223941]: servo mode, ret = 0

[ INFO] [1614739174.772531233]: start, ret = 0

[INFO] [1614739174.832211]: Controller Spawner: Waiting for service controller_manager/switch_controller
[INFO] [1614739174.834114]: Controller Spawner: Waiting for service controller_manager/unload_controller
[INFO] [1614739174.835735]: Loading controller: xarm6_traj_controller
[ERROR] [1614739174.841896763]: Could not find parameter robot_description on parameter server
[ERROR] [1614739174.841966595]: Failed to parse URDF contained in 'robot_description' parameter
[ERROR] [1614739174.841986839]: Failed to initialize the controller
[ERROR] [1614739174.842015245]: Initializing controller 'xarm6_traj_controller' failed
[ERROR] [1614739175.843300]: Failed to load xarm6_traj_controller
[INFO] [1614739175.844406]: Controller Spawner: Loaded controllers: 
[INFO] [1614739176.794854]: Started controllers: 

When robot_description is available, the driver starts up healthy and sends no joint commands:

process[xarm/xarm_driver-1]: started with pid [60294]
process[xarm/xarm_traj_controller-2]: started with pid [60295]
[ INFO] [1614740763.971844821]: start xarm driver
process[xarm/traj_controller_spawner-3]: started with pid [60300]
Tcp Report Norm connection successful
Tcp Control connection successful
[INFO] [1614740764.220008]: Controller Spawner: Waiting for service controller_manager/load_controller
[ INFO] [1614740766.219007836]: motion enable, ret = 0

[ INFO] [1614740766.233351613]: servo mode, ret = 0

[ INFO] [1614740766.249698320]: start, ret = 0

[INFO] [1614740766.327826]: Controller Spawner: Waiting for service controller_manager/switch_controller
[INFO] [1614740766.329563]: Controller Spawner: Waiting for service controller_manager/unload_controller
[INFO] [1614740766.331418]: Loading controller: xarm6_traj_controller
[INFO] [1614740766.350450]: Controller Spawner: Loaded controllers: xarm6_traj_controller
[INFO] [1614740768.270390]: Started controllers: xarm6_traj_controller

Mimic Joint Plugin Update

Hi,

I noticed that the mimic joint plugin used in this repo has actually been deprecated by the maintainer a few days ago. It is now located at https://github.com/roboticsgroup/roboticsgroup_upatras_gazebo_plugins. The plugin's name has also changed to include 'upatras' in the filename. Not sure what the difference between the versions are, but I did see that the plugin is now available as a debian package from apt (the previous version wasn't).

That said, the ros-kinetic-roboticsgroup-upatras-gazebo-plugins debian package has dependencies on gazebo7, so you will still have to build the new plugin from source on ROS Kinetic to make it work with Gazebo 9. I've already tried this and confirmed that it works.

Pick and Place with Xarm5

Hi there dev team.
im using xarm5 with ros_melodic
can i earn some example code or package of pick and place?

compile errors building xarm_ros

Hi Amy,

Another technical question ....

In attempting to start up Gazebo as per the ReadMe.md file, I have problems
with step 4.3.

4.3 Build the code

$ cd ~/catkin_ws
$ catkin_make

ROS runs OK, Gazebo starts up fine. But running the make
generates the following errors. Any ideas?

Thanks!

Andre

============ ERRORS ===========================

test@ubuntu:~/catkin_ws$ catkin_make
In file included from /home/test/catkin_ws/src/ros_control/combined_robot_hw/include/combined_robot_hw/combined_robot_hw.h:37:0,
from /home/test/catkin_ws/src/ros_control/combined_robot_hw/src/combined_robot_hw.cpp:29:
/home/test/catkin_ws/src/ros_control/hardware_interface/include/hardware_interface/robot_hw.h:168:14: error: ‘shared_ptr’ in namespace ‘std’ does not name a template type
typedef std::shared_ptr RobotHWSharedPtr;
^
In file included from /home/test/catkin_ws/src/ros_control/combined_robot_hw/src/combined_robot_hw.cpp:29:0:
/home/test/catkin_ws/src/ros_control/combined_robot_hw/include/combined_robot_hw/combined_robot_hw.h:107:15: error: ‘RobotHWSharedPtr’ is not a member of ‘hardware_interface’
std::vector<hardware_interface::RobotHWSharedPtr> robot_hw_list_;
^
/home/test/catkin_ws/src/ros_control/combined_robot_hw/include/combined_robot_hw/combined_robot_hw.h:107:15: error: ‘RobotHWSharedPtr’ is not a member of ‘hardware_interface’
/home/test/catkin_ws/src/ros_control/combined_robot_hw/include/combined_robot_hw/combined_robot_hw.h:107:51: error: template argument 1 is invalid
std::vector<hardware_interface::RobotHWSharedPtr> robot_hw_list_;
^
/home/test/catkin_ws/src/ros_control/combined_robot_hw/include/combined_robot_hw/combined_robot_hw.h:107:51: error: template argument 2 is invalid
/home/test/catkin_ws/src/ros_control/combined_robot_hw/include/combined_robot_hw/combined_robot_hw.h:116:49: error: ‘hardware_interface::RobotHWSharedPtr’ has not been declared
hardware_interface::RobotHWSharedPtr robot_hw);
^
/home/test/catkin_ws/src/ros_control/combined_robot_hw/src/combined_robot_hw.cpp: In member function ‘virtual bool combined_robot_hw::CombinedRobotHW::prepareSwitch(const std::__cxx11::list<hardware_interface::ControllerInfo>&, const std::cxx11::list<hardware_interface::ControllerInfo>&)’:
/home/test/catkin_ws/src/ros_control/combined_robot_hw/src/combined_robot_hw.cpp:65:17: error: ‘RobotHWSharedPtr’ is not a member of ‘hardware_interface’
std::vector<hardware_interface::RobotHWSharedPtr>::iterator robot_hw;
^
/home/test/catkin_ws/src/ros_control/combined_robot_hw/src/combined_robot_hw.cpp:65:17: error: ‘RobotHWSharedPtr’ is not a member of ‘hardware_interface’
/home/test/catkin_ws/src/ros_control/combined_robot_hw/src/combined_robot_hw.cpp:65:53: error: template argument 1 is invalid
std::vector<hardware_interface::RobotHWSharedPtr>::iterator robot_hw;
^
/home/test/catkin_ws/src/ros_control/combined_robot_hw/src/combined_robot_hw.cpp:65:53: error: template argument 2 is invalid
/home/test/catkin_ws/src/ros_control/combined_robot_hw/src/combined_robot_hw.cpp:65:65: error: expected initializer before ‘robot_hw’
std::vector<hardware_interface::RobotHWSharedPtr>::iterator robot_hw;
^
/home/test/catkin_ws/src/ros_control/combined_robot_hw/src/combined_robot_hw.cpp:66:10: error: ‘robot_hw’ was not declared in this scope
for (robot_hw = robot_hw_list
.begin(); robot_hw != robot_hw_list
.end(); +

Xarm7: Joint 6 Issue

Hello,
During usage of Xarm7 I am constantly heading with the following error:
image
This error comes up during usage of MoveIT, when controlling hand via Xarm Studio (web interface) and even when using joint teach mode. What makes hand usage almost impossible

How do I read the Current of the xarm gripper motor?

Hi,

Are there any rostopics or rosserives that publishes the Current of the gripper motor?
/xarm/gripper_state only returns the position feedback of the gripper, I would like to know how to get the current feedback of the gripper.

Thanks

Bug When Switching Modes using ROS Service

There is no issue when switching from Mode 0 to Mode 1 or from Mode 0 to Mode 2 or from either of those modes to Mode 0.

However, when switching from Mode 1 to Mode 2 or from Mode 2 to Mode 1, the Mode automatically goes back to Mode 0.

I noticed this issue only occurs if the state in the xarm_states topic is set to '2'. But, if the state in the xarm_states topic is set to '5', then there is no issue.

To clarify...
In the image below, the robot is in Mode 2 and has a state of 2.
image

Then I type rosservice call /xarm/set_mode "data: 1" in a terminal. The result is 'ret: 0' and the message is 'message: "servo mode, ret = 0".

However, the robot in actuality goes to Mode 0 as shown in the topic below...
image

Now - if the the robot is in Mode 2 and has a state of 5.
image

Then I type the rosservice call above to change to mode 1, it works correctly.
image

Why is this happening?

mounting setting

Hi,
I want to use wall mounting.
How can I send it using the node?
Thanks

How to control the motor

I want to use my own controller to directly control the motor
Can you provide 485 communication protocol
thanks

TCP Offset & MoveIt

When setting the TCP offset via /xarm/set_tcp_offset MoveIt does not appear to recognize this when planning. Is this by design?

Sudden jump when switching to mode 1.

Hi,

When I try to switch from mode 0 to mode 1 or from mode 2 to mode 1 to control the robot with moveit, the robot performs a very jerky jump at the moment of the switch.

The jump only occurs when I attempt to switch to mode 1. There are no problems when switching from mode 1 to mode 0 or mode 1 to mode 2.

Are there any ways to solve this problem?

Many thanks

Unable to identify any set of controllers that can actuate the specified joints: [ joint1 joint2 joint3 joint4 joint5 joint6 joint7 ]

Hello!
when I spawn xarm7 in gazebo:
roslaunch xarm_gazebo xarm7_beside_table.launch
I see errors:

[ERROR] [1590488171.835015000, 0.394000000]: No p gain specified for pid.  Namespace: /xarm/gazebo_ros_control/pid_gains/joint1
[ERROR] [1590488171.836314999, 0.394000000]: No p gain specified for pid.  Namespace: /xarm/gazebo_ros_control/pid_gains/joint2
[ERROR] [1590488171.837444478, 0.394000000]: No p gain specified for pid.  Namespace: /xarm/gazebo_ros_control/pid_gains/joint3
[ERROR] [1590488171.838585170, 0.394000000]: No p gain specified for pid.  Namespace: /xarm/gazebo_ros_control/pid_gains/joint4
[ERROR] [1590488171.839765461, 0.394000000]: No p gain specified for pid.  Namespace: /xarm/gazebo_ros_control/pid_gains/joint5
[ERROR] [1590488171.840988391, 0.394000000]: No p gain specified for pid.  Namespace: /xarm/gazebo_ros_control/pid_gains/joint6
[ERROR] [1590488171.841756028, 0.394000000]: No p gain specified for pid.  Namespace: /xarm/gazebo_ros_control/pid_gains/joint7

and then when I launch:
roslaunch xarm7_moveit_config xarm7_moveit_gazebo.launch
Plan works well but when I click on Execute in rviz I see errors:

[ERROR] [1590489570.573187541, 280.419000000]: Unable to identify any set of controllers that can actuate the specified joints: [ joint1 joint2 joint3 joint4 joint5 joint6 joint7 ]
[ERROR] [1590489570.573237097, 280.419000000]: Known controllers and their joints:

I tried to set pid values in ~/catkin_ws/src/xarm_ros/xarm7_moveit_config/config/xarm7_params.yaml. Errors No p gain specified for pid disappeared, but model in gazebo starts falling down and then teleports into the floor under and behind the table. Plan stops working.

how can I solve this problem to execute plan in rviz? which pid values should I set?

xArm7 gripper

Currently I am working with the xArm7 robot and I'm trying to control the gripper through moveit/Rviz but I can not manage to load the gripper controller. I can plan and execute a new pose for the manipulator but not for the gripper.

Following the xarm6_gripper_moveit_config package, the controllers.yaml and ros_controllers.yaml files just contain definition for the links 1 to 6, but there is no control for the drive_joint. It is just defined on the hardware_interface.

my control.yaml looks like:


controller_list:
#  - name: xarm7_controller
  - name: ""
    action_ns: follow_joint_trajectory
    default: True
    type: FollowJointTrajectory
    joints:
      - joint1
      - joint2
      - joint3
      - joint4
      - joint5
      - joint6
      - joint7
  - name: end_effector_controller
    action_ns: follow_joint_trajectory
    default: True
    type: FollowJointTrajectory
    joints:
      drive_joint

[ INFO] [1571396632.556916925]: Returned 1 controllers in list

Can it be related to the fact that the - name: "" in the yaml file must be empty?, because if I put any value the robot it can not find any controller.

To sum up, how can I move the gripper using moveit! and Rviz and get it connected to the real robot?

Recommend Projects

  • React photo React

    A declarative, efficient, and flexible JavaScript library for building user interfaces.

  • Vue.js photo Vue.js

    🖖 Vue.js is a progressive, incrementally-adoptable JavaScript framework for building UI on the web.

  • Typescript photo Typescript

    TypeScript is a superset of JavaScript that compiles to clean JavaScript output.

  • TensorFlow photo TensorFlow

    An Open Source Machine Learning Framework for Everyone

  • Django photo Django

    The Web framework for perfectionists with deadlines.

  • D3 photo D3

    Bring data to life with SVG, Canvas and HTML. 📊📈🎉

Recommend Topics

  • javascript

    JavaScript (JS) is a lightweight interpreted programming language with first-class functions.

  • web

    Some thing interesting about web. New door for the world.

  • server

    A server is a program made to process requests and deliver data to clients.

  • Machine learning

    Machine learning is a way of modeling and interpreting data that allows a piece of software to respond intelligently.

  • Game

    Some thing interesting about game, make everyone happy.

Recommend Org

  • Facebook photo Facebook

    We are working to build community through open source technology. NB: members must have two-factor auth.

  • Microsoft photo Microsoft

    Open source projects and samples from Microsoft.

  • Google photo Google

    Google ❤️ Open Source for everyone.

  • D3 photo D3

    Data-Driven Documents codes.