No version for distro humble. Known supported distros are highlighted in the buttons above.
No version for distro jazzy. Known supported distros are highlighted in the buttons above.
No version for distro rolling. Known supported distros are highlighted in the buttons above.

Package Summary

Tags No category tags.
Version 0.0.0
License BSD
Build type AMENT_CMAKE
Use RECOMMENDED

Repository Summary

Checkout URI https://github.com/xarm-developer/xarm_ros2.git
VCS Type git
VCS Version humble
Last Updated 2025-03-26
Dev Status UNMAINTAINED
CI status No Continuous Integration
Released UNRELEASED
Tags No category tags.
Contributing Help Wanted (0)
Good First Issues (0)
Pull Requests to Review (0)

Package Description

The xarm_api package

Additional Links

No additional links.

Maintainers

  • Vinman

Authors

No additional authors.

xarm_api/xarm_msgs:

  These two packages provide user with the ros2 service wrapper of the functions in Ufactory SDK. There are various types of motion command (service names) supported,please set correct robot mode first, refer to this documentation for the Mode/State definitions in our system.

  Attention: You need to enable the corresponding services in advance if they have not been activated by default in config/xarm_params.yaml. Or you can set the debug parameter as true to enable all services at once.

Robot Mode 0:

  • [set_servo_angle](#21-joint-space-motion):

    joint space point to point command, given target joint angles, max joint velocity and acceleration. Service definition: xarm_msgs/srv/MoveJoint. If specify wait=false and proper radius, motion can be continuous with next motion with Arc blending at the via points, and velocity is also continuous.

  • [set_position](#22-cartesian-space-motion-in-base-coordinate):

    straight-line motion to the specified Cartesian Tool Centre Point(TCP) target. Service definition: xarm_msgs/srv/MoveCartesian. If specify wait=false and proper radius, motion can be continuous with next motion with Arc blending at the via points, and velocity is also continuous. Relative (delta) motion can also be achieved by setting relative=true.

  • [set_tool_position](#23-cartesian-space-motion-in-tool-coordinate):

    straight-line motion, given target is expressed in TOOL coordinate system, can be considered as a relative motion.

  • [set_position_aa](#24-cartesian-space-motion-in-axis-angle-orientation):

    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:

  • [set_servo_cartesian/set_servo_cartesian_aa](#31-cartesian-space-servoing)/[set_servo_angle_j](#32-joint-space-servoing):

    streamed high-frequency [suggestion: 100 ~ 250Hz fixed] trajectory command execution in Cartesian space or joint space, this mode is especially useful for external trajectory planner which generates time parameterized servo command (e.g. Moveit+ros-controllers) or sensor guided motion. Special RISK ASSESMENT is required before using them and please note there is no further interpolation and speed control in this mode.

Robot Mode 4:

  • [vc_set_joint_velocity](#25-joint-velocity-control):

    Joint motion with specified velocity for each joint (unit: rad/s), with maximum joint acceleration configurable by set_joint_maxacc service.

Robot Mode 5:

  • [vc_set_cartesian_velocity](#26-cartesian-velocity-control):

    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_tcp_maxacc service.

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

  • [set_servo_angle](#21-joint-space-motion):

    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. wait parameter has to be false for successful transition.

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

  • [set_position/set_position_aa](#22-cartesian-space-motion-in-Base-coordinate):

    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. wait parameter has to be false for successful transition.

1. Starting xArm by ROS service:

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

$ ros2 launch xarm_api xarm7_driver.launch.py robot_ip:=192.168.1.127 report_type:=normal

The argument report_type is explained here.

  Then make sure all the servo motors are enabled:

$ ros2 service call /xarm/motion_enable xarm_msgs/srv/SetInt16ById "{id: 8, data: 1}"

  Before any motion commands, set proper robot mode(0: POSE, as example) and state(0: READY) in order:

$ ros2 service call /xarm/set_mode xarm_msgs/srv/SetInt16 "{data: 0}"
$ ros2 service call /xarm/set_state xarm_msgs/srv/SetInt16 "{data: 0}"

2. Joint or Cartesian space command example [use firmware planner]:

  This section will talk about general motion service interface, with firmware assisted planner for speed/acceleration control and smooth trajectory generation. Please note that all the angles for service command must use the unit of radian.

2.1 Joint space motion:

   To call joint space (7DOF) motion with max speed 0.35 rad/s and acceleration 10 rad/s^2:

$ ros2 service call /xarm/set_servo_angle xarm_msgs/srv/MoveJoint "{angles: [-0.28, 0, 0, 0, 0, 0, 0], speed: 0.35, acc: 10}"

Note: This command is valid for both Mode 0 and mode 6. The difference is: In mode 0 each received command will be queued and executed fully in order, whereas in mode 6(must specify wait as false), the newly received target will take effect immediately and all previous commands will be discarded.

  To go back to home (all joints at 0 rad) position with max speed 0.35 rad/s and acceleration 10 rad/s^2:

$ ros2 service call /xarm/move_gohome xarm_msgs/srv/MoveHome "{speed: 0.35, acc: 10}"

2.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:

$ ros2 service call /xarm/set_position xarm_msgs/srv/MoveCartesian "{pose: [300, 0, 250, 3.14, 0, 0], speed: 200, acc: 2000}"

Note: This command is valid for both Mode 0 and mode 7. The difference is: In mode 0 each received command will be queued and executed fully in order, whereas in mode 7(must specify wait as false), the newly received target will take effect immediately and all previous commands will be discarded.

2.3 Cartesian space motion in Tool coordinate:

  To execute Cartesian motion expressed in robot TOOL Coordinate, with max speed 50 mm/s and acceleration 1000 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:

$ ros2 service call /xarm/set_tool_position xarm_msgs/srv/MoveCartesian "{pose: [50, 100, 100, 0, 0, 0], speed: 50, acc: 1000}"

2.4 Cartesian space motion in Axis-angle orientation:

  Please pay attention to two special arguments: “is_tool_coord” is false for motion with respect to (w.r.t.) Arm base coordinate system, and true for motion w.r.t. Tool coordinate system. “relative” is false for absolute target position w.r.t. specified coordinate system, and true for relative target position.
  For example: to move 1.0 radian relatively around tool-frame Z-axis:

$ ros2 service call /xarm/set_position_aa xarm_msgs/srv/MoveCartesian "{pose: [0, 0, 0, 0, 0, 1.0], speed: 50, acc: 1000, is_tool_coord: true}"

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

$ ros2 service call /xarm/set_position_aa xarm_msgs/srv/MoveCartesian "{pose: [0, 122, 0, -0.5, 0, 0], speed: 100, acc: 1000, is_tool_coord: false, relative: true}"  

2.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 explanation. Please check the MoveVelocity.srv first to understand the meanings of parameters reqired. If more than one joint are to move, set is_sync to true for synchronized acceleration/deceleration for all joints in motion, and if is_sync is false, each joint will reach to its target velocity as fast as possible. is_tool_coord parameter is not used here. For example:

# NO Timed-out version (will not stop until all-zero velocity command received!):
$ ros2 service call /xarm/vc_set_joint_velocity xarm_msgs/srv/MoveVelocity "{speeds: [-0.1, 0, 0, 0, 0, 0, 0.2], is_sync: true}"
# With Timed-out version(controller firmware version >= 1.8.0): (if next velocity command not received within 0.2 seconds, xArm will stop)  
$ ros2 service call /xarm/vc_set_joint_velocity xarm_msgs/srv/MoveVelocity "{speeds: [-0.1, 0, 0, 0, 0, 0, 0.2], is_sync: true, duration: 0.2}"

will command the joints (for xArm7) 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):

$ ros2 service call /xarm/set_joint_maxacc xarm_msgs/srv/SetFloat32 "{data: 10.0}"  (maximum: 20.0 rad/s^2)

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 explanation. Please check the MoveVelocity.srv first to understand the meanings of parameters reqired. Set is_tool_coord to false for motion in world/base coordinate system and true for tool coordinate system. is_sync parameter is not used here. For example:

# NO Timed-out version (will not stop until all-zero velocity command received!):  
$ ros2 service call /xarm/vc_set_cartesian_velocity xarm_msgs/srv/MoveVelocity "{speeds: [30, 0, 0, 0, 0, 0.1], is_tool_coord: true}"  
# With Timed-out version(controller firmware version >= 1.8.0): (if next velocity command not received within 0.5 seconds, xArm will stop)  
$ ros2 service call /xarm/vc_set_cartesian_velocity xarm_msgs/srv/MoveVelocity "{speeds: [30, 0, 0, 0, 0, 0.1], is_tool_coord: true, duration: 0.5}"

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

$ ros2 service call /xarm/set_tcp_maxacc xarm_msgs/srv/SetFloat32 "{data: 2500}" (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!):
$ ros2 service call /xarm/vc_set_cartesian_velocity xarm_msgs/srv/MoveVelocity "{speeds: [0, 0, 0, 0.707, 0, 0], is_tool_coord: false}"
# With Timed-out version(controller firmware version >= 1.8.0): (if next velocity command not received within 0.2 seconds, xArm will stop)  
$ ros2 service call /xarm/vc_set_cartesian_velocity xarm_msgs/srv/MoveVelocity "{speeds: [0, 0, 0, 0.707, 0, 0], is_tool_coord: false, duration: 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.

2.7 Motion service Return:

  Please Note the above motion services will return immediately if wait parameter is set to false. If you wish to return until actual motion is finished, please set it to be true.
  Upon sending success, 0 will be returned. If any error occurs, other values will be returned.

3. Joint or Cartesian space servo command [quick step execution]:

  This section will talk about the servo (realtime, updated at high-frequency) command interface, only effective in Mode 1. Please note that all the angles for service command must use the unit of radian.

3.1 Cartesian space servoing:

PLEASE NOTE: If you are already using Moveit to control the real robot arm, move_servoj and move_servo_cart can not be used concurrently, since they use the same mode(1) to control and may interfere with each other!

Now with xArm controller Firmware Version >= 1.4.1, user can send streamed Cartesian poses to continuously control the xArm, through ros service, this is a wrap of the same xarm sdk(api) function. The actual speed depends on the sending frequency and step distance. Users are encouraged to send the path points in a fixed frequency(100Hz~250Hz) and step distance(MUST <10mm).

(1) To start, bring up the xarm server and in another terminal, do initial configurations, servo cartesian has to operate in Mode 1:

(2) Call the servo_cartesian service. Please note:
(1) the Cartesian pose representation is the same with xarm SDK here. which is [X(mm), Y(mm), Z(mm), Roll(rad), Pitch(rad), Yaw(rad)]
(2) the path must start from current tool center point(TCP) position and the command can not be too far away, or the execution will fail or act strange. PLEASE CHECK the correctness of command before sending it.
(3) For servo motion, the arguments mvvelo, mvacc, mvtime, and mvradii are not effective now, so just give them all 0.

Suppose current TCP position is at [206, 0, 121, 3.1416, 0, 0]

$ ros2 service call /xarm/set_servo_cartesian xarm_msgs/srv/MoveCartesian "{pose: [208, 0, 121, 3.1416, 0, 0]}"

Now please check the current TCP position, it will execute this target immediately if success. If you want continuous motion alone X axis, you can give the following pose like:

$ ros2 service call /xarm/set_servo_cartesian xarm_msgs/srv/MoveCartesian "{pose: [210, 0, 121, 3.1416, 0, 0]}"

And you can program this service calling procedure in a loop with proper intervals inbetween, the final execution will become smooth.

Notice: Servo_cartisian in TOOL coordinate: Please update the controller Firmware to version >= 1.5.0. If servo_cartesian in Tool Coordinate is needed, set “is_tool_coord” to be true, the resulted motion will base on current Tool coordinate. For example:

$ ros2 service call /xarm/set_servo_cartesian xarm_msgs/srv/MoveCartesian "{pose: [0, 0, 2, 0, 0, 0], is_tool_coord: true}"

This will make TCP to move 2 mm immediately along +Z Axis in TOOL Coordinate. You may also use xarm/set_servo_cartesian_aa service for axis-angle expression command.

3.2 Joint space servoing:

There is also a similar service called “/xarm/set_servo_angle_j”, you can use this service to control joint motion in the same mode (1) with Servo_Cartesian. It receives absolute joint positions as command. Before calling it, please check the current joint position in “/xarm/joint_states” topic, and increase the target joint position little by little just like calling /xarm/set_servo_cartesian.

For example, if /xarm/joint_state says current joint positions are: [0.25,-0.47,0.0,-0.28,0.0,0.76,0.24], you can call:

$ ros2 service call /xarm/set_servo_angle_j xarm_msgs/srv/MoveJoint "{angles: [0.25,-0.47,0.0,-0.28,0.0,0.76,0.25]}"

Which will move joint7 by 0.01 rad immediately. Keep calling it and increase the joint positions a small step each time, it will move smoothly. Be careful not to give a target too far away in one single update.

4. Tool I/O Operations:

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

4.1 To get current 2 DIGITAL input states:

$ ros2 service call /xarm/get_tgpio_digital xarm_msgs/srv/GetDigitalIO 

4.2 To get one of the ANALOG input value:

$ ros2 service call /xarm/get_tgpio_analog xarm_msgs/srv/GetAnalogIO "{ionum: 0}"  (io number, can only be 0 or 1)

4.3 To set one of the Digital output:

$ ros2 service call /xarm/set_tgpio_digital xarm_msgs/srv/SetDigitalIO "{ionum: 0, value: 1}"  (Setting output port 0 to be 1)

  You have to make sure the operation is successful by checking responding “ret” to be 0.

5. Controller I/O Operations:

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

5.1 To get all of the controller DIGITAL input state:

$ ros2 service call /xarm/get_cgpio_digital xarm_msgs/srv/GetDigitalIO  # (Notice: from 1st to 8th, for CO0~CO7; from 9th to 16th, for DI0~DI7[if any])

5.2 To set one of the controller DIGITAL output:

$ ros2 service call /xarm/set_cgpio_digital xarm_msgs/srv/SetDigitalIO "{ionum: 0, value: 1}" 

  Please note port number starts from 0, for example:

$ ros2 service call /xarm/set_cgpio_digital xarm_msgs/srv/SetDigitalIO "{ionum: 4, value: 1}"   #(Setting 5th [lable C04] output port to be 1)

5.3 To get one of the controller ANALOG input:

$ ros2 service call /xarm/get_cgpio_analog xarm_msgs/srv/GetAnalogIO "{ionum: <port_num>}"  # ionum: 0 or 1

5.4 To set one of the controller ANALOG output:

$ ros2 service call /xarm/set_cgpio_analog xarm_msgs/srv/SetAnalogIO  "{ionum: <port_num>, value: <target_value>}"

  For example:

$ ros2 service call /xarm/set_cgpio_analog xarm_msgs/srv/SetAnalogIO  "{ionum: 1, value: 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.

6. Getting status feedback:

  Having connected with a real xArm robot by running ‘xarm7_driver.launch.py’, user can subscribe to the topic “xarm/robot_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 “xarm/joint_states” topic, which is reporting in JointState.msg, however, currently only “position” field data is solidly 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

7. 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 (“err” field) in the message of topic “xarm/robot_states” .

$ ros2 topic echo /xarm/robot_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/clean_error” with empty argument.

$ ros2 service call /xarm/clean_error xarm_msgs/srv/Call

  After calling clean_error service, please check the err status again in ‘xarm/robot_states’, if it becomes 0, the clearing is successful. Otherwise, it means the error/exception is not properly solved. If using Moveit!, please set mode to 1 again manually, since controller error and state 4 will automatically switch mode back to 0. If clearing error is successful, remember to set robot state to 0 to make it ready to move again!

8. Gripper Control:

   If our Gripper (from UFACTORY) is attached to the tool end, the following services/actions can be called to operate or check the gripper. Please note we now have three types of grippers, judging from the service name: the ones with “bio_gripper” are for BIO parallel gripper, “lite_gripper” ones are for small gripper of lite 6, and the rest with just “gripper” are for xArm gripper. We will just use xArm gripper for instructions.

8.1 Gripper services:

(1) Upon powering up, first enable the griper and configure the grasp speed:

$ ros2 service call /xarm/set_gripper_enable xarm_msgs/srv/SetInt16 "{data: 1}"
$ ros2 service call /xarm/set_gripper_mode xarm_msgs/srv/SetInt16 "{data: 0}"
$ ros2 service call /xarm/set_gripper_speed xarm_msgs/srv/SetFloat32 "{data: 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:

$ ros2 service call /xarm/set_gripper_position xarm_msgs/srv/GripperMove "{pos: 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:

$ ros2 service call /xarm/get_gripper_position xarm_msgs/srv/GetFloat32
$ ros2 service call /xarm/get_gripper_err_code xarm_msgs/srv/GetInt16

   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.

8.2 Gripper action:

   The xArm gripper move action is xarm_gripper/gripper_action, which is of type control_msgs/action/GripperCommand. Attention: The goal position here should be the rotation angle of the virtual joint inside, which is from 0 rad (fully open) to 0.86 (fully closed). Not the pulse in afore-mentioned service call. Gripper action can be called by:

$ ros2 action send_goal /xarm_gripper/gripper_action control_msgs/action/GripperCommand "{command: {position: 0.5, max_effort: 0}}"

9. 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. Note the command service is applicable for both xArm and lite vacuum grippers.

  To turn on:

$ ros2 service call /xarm/set_vacuum_gripper xarm_msgs/srv/VacuumGripperCtrl "{'on': true}"

  To turn off:

$ ros2 service call /xarm/set_vacuum_gripper xarm_msgs/srv/VacuumGripperCtrl "{'on': false}"

  0 will be returned upon successful execution.

10. Tool Modbus communication:

If modbus communication with the tool device is needed, please first set the proper baud rate and timeout parameters through the relevant services:

$ ros2 service call /xarm/set_tgpio_modbus_baudrate xarm_msgs/srv/SetInt32 "{data: 115200}"
$ ros2 service call /xarm/set_tgpio_modbus_timeout xarm_msgs/srv/SetModbusTimeout "{timeout: 20}"  # unit: ms

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. 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 GetSetModbusData.srv for more parameter details):

$ ros2 service call /xarm/getset_tgpio_modbus_data xarm_msgs/srv/GetSetModbusData "{modbus_data: [0x01,0x06,0x00,0x0A,0x00,0x03]}"

please check the ret_data field for device response data.

11. “report_type” argument:

When launching real xArm ROS2 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/robot_states and xarm/joint_states will be published at 100Hz.
  • For users who want the controller gpio states being updated at xarm/xarm_cgpio_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/xarm_cgpio_states. F/T sensor topic => xarm/uf_ftsensor_ext_states and xarm/uf_ftsensor_raw_states.

CHANGELOG
No CHANGELOG found.

Wiki Tutorials

This package does not provide any links to tutorials in it's rosindex metadata. You can check on the ROS Wiki Tutorials page for the package.

Launch files

No launch files found

Messages

No message files found.

Services

No service files found

Plugins

No plugins found.

Recent questions tagged xarm_api at Robotics Stack Exchange

No version for distro noetic. Known supported distros are highlighted in the buttons above.
No version for distro ardent. Known supported distros are highlighted in the buttons above.
No version for distro bouncy. Known supported distros are highlighted in the buttons above.
No version for distro crystal. Known supported distros are highlighted in the buttons above.
No version for distro eloquent. Known supported distros are highlighted in the buttons above.
No version for distro dashing. Known supported distros are highlighted in the buttons above.
No version for distro galactic. Known supported distros are highlighted in the buttons above.
No version for distro foxy. Known supported distros are highlighted in the buttons above.
No version for distro iron. Known supported distros are highlighted in the buttons above.
No version for distro lunar. Known supported distros are highlighted in the buttons above.
No version for distro jade. Known supported distros are highlighted in the buttons above.
No version for distro indigo. Known supported distros are highlighted in the buttons above.
No version for distro hydro. Known supported distros are highlighted in the buttons above.

Package Summary

Tags No category tags.
Version 0.0.0
License BSD
Build type CATKIN
Use RECOMMENDED

Repository Summary

Checkout URI https://github.com/xArm-Developer/xarm_ros.git
VCS Type git
VCS Version master
Last Updated 2025-03-21
Dev Status DEVELOPED
CI status Continuous Integration
Released UNRELEASED
Tags No category tags.
Contributing Help Wanted (0)
Good First Issues (0)
Pull Requests to Review (0)

Package Description

The xarm_api package

Additional Links

No additional links.

Maintainers

  • Jason Peng

Authors

No additional authors.

xarm_api services description

Services

  The services of xarm_api is the interface encapsulation of C++ SDK, which may be a single interface call or multiple interface calls.   Note: The service path prefix (xarm/) used by rosservice is related to the startup parameters. The default xarm series is xarm/, and the Lite series is ufactory/. The following example uses xarm/, the actual use is modified according to the actual situation.

C++ SDK DOCS

  • Init

    • motion_ctrl
      • SDK API
        • motion_enable
      • rosservice
      # id: 1~7 means joint1~joint7, 8 means all joints
      # enable: 1 means enable, 0 means disable
      rosservice call /xarm/motion_ctrl ${enable} ${id}
      
  • set_mode
    • SDK API:
      • set_mode
    • rosservice:
      # mode: 
      #   0: position mode
      #   1: servo motion mode
      #   2: joint teaching mode
      #   4: joint velocity mode
      #   5: cartesian velocity mode
      #   6: joint online trajectory planning mode
      #   7: cartesian online trajectory planning mode
      rosservice call /xarm/set_mode ${mode}
      
  • set_state
    • SDK API:
      • set_state
    • rosservice:
      # state:
      #   0: motion state
      #   3: pause state
      #   4: stop state
      rosservice call /xarm/set_state ${state}
      
  • clear_err
    • SDK API:
      • (if gripper added) clean_gripper_error
      • clean_error
      • clean_warn
      • motion_enable
    • rosservice:
      rosservice call /xarm/clear_err
      
  • moveit_clear_err
    • SDK API:
      • (if gripper added) clean_gripper_error
      • clean_error
      • clean_warn
      • motion_enable
      • set_mode
      • set_state
    • rosservice:
      rosservice call /xarm/moveit_clear_err
      
  • Motion

    • go_home
      • SDK API:
        • move_gohome
      • rosservice:
      # mvvelo: speed (rad/s)
      # mvacc: acceleration (rad/s^2)
      rosservice call /xarm/go_home [] ${mvvelo} ${mvacc} 0 0
      
  • move_joint
    • SDK API:
      • set_servo_angle
    • rosservice:
      # angles: [joint1-rad, ..., joint${dof}-rad]
      # mvvelo: speed (rad/s)
      # mvacc: acceleration (rad/s^2)
      rosservice call /xarm/move_joint ${angles} ${mvvelo} ${mvacc} 0 0
      
  • move_jointb
    • SDK API:
      • set_servo_angle
    • rosservice:
      # angles: [joint1-rad, ..., joint${dof}-rad]
      # mvvelo: speed (rad/s)
      # mvacc: acceleration (rad/s^2)
      # radius: the blending radius between 2 straight path trajectories, 0 for no blend.
      rosservice call /xarm/move_jointb ${angles} ${mvvelo} ${mvacc} 0 ${radius}
      
  • move_line
    • SDK API:
      • set_position
    • rosservice:
      # pose: [x(mm), y(mm), z(mm), roll(rad), pitch(rad), yaw(rad)]
      # mvvelo: speed (mm/s)
      # mvacc: acceleration (mm/s^2)
      rosservice call /xarm/move_line ${pose} ${mvvelo} ${mvacc} 0 0
      
  • move_lineb
    • SDK API:
      • set_position
    • rosservice:
      # pose: [x(mm), y(mm), z(mm), roll(rad), pitch(rad), yaw(rad)]
      # mvvelo: speed (mm/s)
      # mvacc: acceleration (mm/s^2)
      # radius: the blending radius between 2 straight path trajectories, 0 for no blend.
      rosservice call /xarm/move_lineb ${pose} ${mvvelo} ${mvacc} 0 ${radius}
      
  • move_line_tool
    • SDK API:
      • set_tool_position
    • rosservice:
      # pose: [x(mm), y(mm), z(mm), roll(rad), pitch(rad), yaw(rad)]
      # mvvelo: speed (mm/s)
      # mvacc: acceleration (mm/s^2)
      rosservice call /xarm/move_line_tool ${pose} ${mvvelo} ${mvacc} 0 0
      
  • move_servoj
    • SDK API:
      • set_servo_angle_j
    • rosservice:
      # angles: [joint1-rad, ..., joint${dof}-rad]
      # mvvelo: speed (rad/s)
      # mvacc: acceleration (rad/s^2)
      rosservice call /xarm/move_servoj ${angles} ${mvvelo} ${mvacc} 0 0
      
  • move_servo_cart
    • SDK API:
      • set_servo_cartesian
    • rosservice:
      # pose: [x(mm), y(mm), z(mm), roll(rad), pitch(rad), yaw(rad)]
      # mvvelo: speed (mm/s)
      # mvacc: acceleration (mm/s^2)
      # coord: motion coordinate system indicator, base (0) or tool(1) coordinate
      rosservice call /xarm/move_servo_cart ${pose} ${mvvelo} ${mvacc} ${coord} 0
      
  • move_line_aa
    • SDK API:
      • set_position_aa
    • rosservice:
      # pose: [x(mm), y(mm), z(mm), roll(rad), pitch(rad), yaw(rad)]
      # mvvelo: speed (mm/s)
      # mvacc: acceleration (mm/s^2)
      # coord: motion coordinate system indicator, base (0) or tool(1) coordinate
      # relative: indicator of given target is relative (1) or not (0, absolute)
      rosservice call /xarm/move_line_aa ${pose} ${mvvelo} ${mvacc} 0 ${coord} ${relative}
      
  • move_servo_cart_aa
    • SDK API:
      • set_servo_cartesian_aa
    • rosservice:
      # pose: [x(mm), y(mm), z(mm), roll(rad), pitch(rad), yaw(rad)]
      # mvvelo: speed (mm/s)
      # mvacc: acceleration (mm/s^2)
      # coord: motion coordinate system indicator, base (0) or tool(1) coordinate
      # relative: indicator of given target is relative (1) or not (0, absolute)
      rosservice call /xarm/move_servo_cart_aa ${pose} ${mvvelo} ${mvacc} 0 ${coord} ${relative}
      
  • velo_move_joint
    • SDK API:
      • vc_set_joint_velocity
    • rosservice:
      # velocities: [joint1-velo(rad/s), ..., joint${dof}-velo(rad/s)]
      # jnt_sync: whether all joints accelerate and decelerate synchronously, 1 for yes, 0 for no
      rosservice call /xarm/velo_move_joint ${velocities} ${jnt_sync} 0
      
  • velo_move_line
    • SDK API:
      • vc_set_cartesian_velocity
    • rosservice:
      # velocities: [velo-x(mm/s), velo-y(mm/s), velo-z(mm/s), velo-roll(rad/s), velo-pitch(rad/s), velo-yaw(rad/s)]
      # coord: whether motion is in tool coordinate(1) or not(0)
      rosservice call /xarm/velo_move_joint ${velocities} 0 ${coord}
      
  • velo_move_joint_timed
    • SDK API:
      • vc_set_joint_velocity
    • rosservice:
      # velocities: [joint1-velo(rad/s), ..., joint${dof}-velo(rad/s)]
      # is_sync: whether all joints accelerate and decelerate synchronously, 1 for yes, 0 for no
      # duration: the maximum duration of the speed, over this time will automatically set the speed to 0
      rosservice call /xarm/velo_move_joint_timed ${velocities} ${is_sync} 0 ${duration}
      
  • velo_move_line_timed
    • SDK API:
      • vc_set_cartesian_velocity
    • rosservice:
      # velocities: [velo-x(mm/s), velo-y(mm/s), velo-z(mm/s), velo-roll(rad/s), velo-pitch(rad/s), velo-yaw(rad/s)]
      # is_tool_coord: whether motion is in tool coordinate(1) or not(0)
      # duration: the maximum duration of the speed, over this time will automatically set the speed to 0
      rosservice call /xarm/velo_move_line_timed ${velocities} 0 ${is_tool_coord} {duration}
      
  • Tool GPIO (ionum from 1 to 2)

    • set_digital_out
      • SDK API:
        • set_tgpio_digital
      • rosservice:
      # io_num: io num, 1: DO0, 2: DO1
      # value: 0/1
      rosservice call /xarm/set_digital_out ${io_num} ${value}
      
  • get_digital_in
    • SDK API:
      • get_tgpio_digital
    • rosservice:
      rosservice call /xarm/get_digital_in
      
  • get_analog_in
    • SDK API:
      • get_tgpio_analog
    • rosservice:
      # io_num: io num, 1: AI0, 2: AI1
      rosservice call /xarm/get_analog_in ${io_num}
      
  • Controller GPIO (ionum from 1 to 16)

    • set_controller_dout
      • SDK API:
        • set_cgpio_digital
      • rosservice:
      # io_num: io num, 1 ~ 16, (1: CO0, 9: DO0)
      # value: 0/1
      rosservice call /xarm/set_controller_dout ${io_num} ${value}
      
  • get_controller_din
    • SDK API:
      • get_cgpio_digital
    • rosservice:
      # io_num: io num, 1 ~ 16, (1: CI0, 9: DI0)
      rosservice call /xarm/get_controller_din ${io_num}
      
  • set_controller_aout
    • SDK API:
      • set_cgpio_analog
    • rosservice:
      # io_num: io num, 1: AO0, 2: AO1
      # value: value
      rosservice call /xarm/set_controller_aout ${io_num} ${value}
      
  • get_controller_ain
    • SDK API:
      • get_cgpio_analog
    • rosservice:
      # io_num: io num, 1: AI0, 2: AI1
      rosservice call /xarm/get_controller_ain ${io_num}
      
  • XArm Gripper

    • gripper_config
      • SDK API:
        • set_gripper_mode
        • set_gripper_enable
        • set_gripper_speed
      • rosservice:
      # velocity: pulse velocity, 1 ~ 5000
      rosservice call /xarm/gripper_config ${velocity}
      
  • gripper_move
    • SDK API:
      • set_gripper_position
    • rosservice:
      # pos: pulse pos, -100 ~ 850
      rosservice call /xarm/gripper_move ${pos}
      
  • gripper_state
    • SDK API:
      • get_gripper_err_code
      • get_gripper_position
    • rosservice:
      rosservice call /xarm/gripper_state 
      
  • XArm Vacuum Gripper

    • vacuum_gripper_set
      • SDK API:
        • set_vacuum_gripper
      • rosservice:
      # on: 1: open, 0: close
      rosservice call /xarm/vacuum_gripper_set ${on}
      
  • Lite Gripper

    • open_lite6_gripper
      • SDK API:
        • open_lite6_gripper
      • rosservice:
      rosservice call /xarm/open_lite6_gripper
      
  • close_lite6_gripper
    • SDK API:
      • close_lite6_gripper
    • rosservice:
      rosservice call /xarm/close_lite6_gripper
      
  • stop_lite6_gripper
    • SDK API:
      • stop_lite6_gripper
    • rosservice:
      rosservice call /xarm/stop_lite6_gripper
      
  • Force torque Sensor

    • ft_sensor_enable
      • SDK API:
        • ft_sensor_enable
      • rosservice:
      # enable: 1: enable, 0: disable
      rosservice call /xarm/ft_sensor_enable ${enable}
      
  • ft_sensor_app_set
    • SDK API:
      • ft_sensor_app_set
    • rosservice:
      # app_code
      #   0: non-force mode
      #   1: impendance control
      #   2: force control
      rosservice call /xarm/ft_sensor_app_set ${app_code}
      
  • ft_sensor_set_zero
    • SDK API:
      • ft_sensor_set_zero
    • rosservice:
      rosservice call /xarm/ft_sensor_set_zero
      
  • ft_sensor_cali_load
    • SDK API:
      • ft_sensor_cali_load
      • save_conf
    • rosservice:
      # data: iden load result
      # association_setting_tcp_load: association setting tcp load or not
      rosservice call /xarm/ft_sensor_cali_load ${data} ${association_setting_tcp_load}
      
  • ft_sensor_iden_load
    • SDK API:
      • ft_sensor_iden_load
    • rosservice:
      rosservice call /xarm/ft_sensor_iden_load
      
  • get_ft_sensor_error
    • SDK API:
      • get_ft_sensor_error
    • rosservice:
      rosservice call /xarm/get_ft_sensor_error
      
  • Tool Modbus

    • config_tool_modbus
      • SDK API:
        • set_state
        • set_tgpio_modbus_baudrate
        • set_tgpio_modbus_timeout
      • rosservice:
      # baudrate: baudrate
      # timeout_ms: timeout(ms)
      rosservice call /xarm/config_tool_modbus ${baudrate} ${timeout_ms}
      
  • set_tool_modbus
    • SDK API:
      • getset_tgpio_modbus_data
    • rosservice:
      # send_data: modbus data
      # respond_len: the length of the response modbus data
      rosservice call /xarm/getset_tgpio_modbus_data ${send_data} ${respond_len}
      
  • get_tgpio_modbus_baudrate
    • SDK API:
      • get_tgpio_modbus_baudrate
    • rosservice:
      rosservice call /xarm/get_tgpio_modbus_baudrate
      
  • set_tgpio_modbus_timeout
    • SDK API:
      • set_tgpio_modbus_timeout
    • rosservice:
      # timeout_ms: timeout(ms)
      # is_transparent_transmission: is transparent transmission or not
      rosservice call /xarm/set_tgpio_modbus_timeout ${timeout_ms} ${is_transparent_transmission}
      
  • getset_tgpio_modbus_data
    • SDK API:
      • getset_tgpio_modbus_data
    • rosservice:
      # send_data: modbus data
      # respond_len: the length of the response modbus data
      # host_id: host id, 9: END RS485, 10: Controller RS485
      # is_transparent_transmission: is transparent transmission or not
      # use_503_port: whether to use port 503 for communication
      rosservice call /xarm/getset_tgpio_modbus_data ${send_data} ${respond_len} ${host_id} ${is_transparent_transmission} ${use_503_port}
      
  • Get

    • get_servo_angle
      • SDK API:
        • get_servo_angle
      • rosservice:
      rosservice call /xarm/get_servo_angle
      
  • get_position_rpy
    • SDK API:
      • get_position
    • rosservice:
      rosservice call /xarm/get_position_rpy
      
  • get_position_axis_angle
    • SDK API:
      • get_position_aa
    • rosservice:
      rosservice call /xarm/get_position_axis_angle
      
  • Set

    • set_tcp_offset
      • SDK API:
        • set_tcp_offset
        • save_conf
      • rosservice
      # x/y/z: mm
      # roll/pitch/yaw: rad
      rosservice call /xarm/set_tcp_offset ${x} ${y} ${z} ${roll} ${pitch} ${yaw}
      
  • set_load
    • SDK API:
      • set_tcp_load
      • save_conf
    • rosservice
      # mass: kg
      # xc: x center of mass (mm)
      # yc: y center of mass (mm)
      # zc: z center of mass (mm)
      rosservice call /xarm/set_load ${mass} ${xc} ${yc} ${zc}
      
  • set_max_acc_joint
    • SDK API:
      • set_joint_maxacc
    • rosservice
      # maxacc: joint max acc, rad/s^2, 0 ~ 20
      rosservice call /xarm/set_max_acc_joint ${maxacc}
      
  • set_max_acc_line
    • SDK API:
      • set_tcp_maxacc
    • rosservice
      # maxacc: tcp max acc, mm/s^2, 0 ~ 50000
      rosservice call /xarm/set_max_acc_line ${maxacc}
      
  • set_collision_rebound
    • SDK API:
      • set_collision_rebound
    • rosservice
      # on: 1: on, 0: off
      rosservice call /xarm/set_collision_rebound ${on}
      
  • set_collision_sensitivity
    • SDK API:
      • set_collision_sensitivity
    • rosservice
      # sens: collision sensitivity, 0 ~ 5
      rosservice call /xarm/set_collision_sensitivity ${sens}
      
  • set_teach_sensitivity
    • SDK API:
      • set_teach_sensitivity
    • rosservice
      # sens: teach sensitivity, 1 ~ 5
      rosservice call /xarm/set_teach_sensitivity ${sens}
      
  • set_world_offset
    • SDK API:
      • set_world_offset
      • save_conf
    • rosservice
      # x/y/z: mm
      # roll/pitch/yaw: rad
      rosservice call /xarm/set_world_offset ${x} ${y} ${z} ${roll} ${pitch} ${yaw}
      
  • set_fence_mode
    • SDK API:
      • set_fence_mode
    • rosservice
      # on: 1: on, 0: off
      rosservice call /xarm/set_fence_mode ${on}
      
  • set_reduced_mode
    • SDK API:
      • set_reduced_mode
    • rosservice
      # on: 1: on, 0: off
      rosservice call /xarm/set_reduced_mode ${on}
      
  • set_tcp_jerk
    • SDK API:
      • set_tcp_jerk
    • rosservice
      # jerk: tcp max acc, mm/s^3
      rosservice call /xarm/set_tcp_jerk ${jerk}
      
  • set_joint_jerk
    • SDK API:
      • set_joint_jerk
    • rosservice
      # jerk: joint jerk, rad/s^3
      rosservice call /xarm/set_joint_jerk ${jerk}
      
  • Trajectory

    • set_recording
      • SDK API:
        • start_record_trajectory or stop_record_trajectory
      • rosservice
      # on: 1: start, 0: stop
      rosservice call /xarm/set_recording ${on}
      
  • save_traj
    • SDK API:
      • save_record_trajectory
    • rosservice
      # filename: the trajectory filename to save
      # timeout: save timeout (second)
      rosservice call /xarm/save_traj ${filename} ${timeout}
      
  • play_traj
    • SDK API:
      • playback_trajectory
    • rosservice
      # filename: the trajectory filename to playback
      # times: repeat times
      # speed_factor: speed factor, 1/2/4
      rosservice call /xarm/play_traj ${filename} ${times} ${speed_factor}
      
CHANGELOG
No CHANGELOG found.

Wiki Tutorials

This package does not provide any links to tutorials in it's rosindex metadata. You can check on the ROS Wiki Tutorials page for the package.

Launch files

No launch files found

Messages

No message files found.

Services

No service files found

Plugins

No plugins found.

Recent questions tagged xarm_api at Robotics Stack Exchange

No version for distro melodic. Known supported distros are highlighted in the buttons above.