Skip to main content
All CollectionsxArm-Python/C++ SDK
Guide to use the interface 'set_servo_cartesian' and 'set_servo_anagle_j'
Guide to use the interface 'set_servo_cartesian' and 'set_servo_anagle_j'
W
Written by Wang Daniel
Updated over 3 years ago

1. set_servo_cartesian

The following is an example to explain the servo_cartesion motion.

from xarm.wrapper import XArmAPI

arm = XArmAPI('192.168.1.226')


arm.motion_enable(enable=True)

arm.set_mode(0)

arm.set_state(state=0)

arm.reset(wait=True)


arm.set_position(*[200, 0, 200, 180, 0, 0], wait=True)


arm.set_mode(1)

arm.set_state(0)

time.sleep(0.1)


while arm.connected and arm.state != 4:

for i in range(300):

x = 200 + i

mvpose = [x, 0, 200, 180, 0, 0]

ret = arm.set_servo_cartesian(mvpose, speed=100, mvacc=2000)

print('set_servo_cartesian, ret={}'.format(ret))

time.sleep(0.01)

for i in range(300):

x = 500 - i

mvpose = [x, 0, 200, 180, 0, 0]

ret = arm.set_servo_cartesian(mvpose, speed=100, mvacc=2000)

print('set_servo_cartesian, ret={}'.format(ret))

time.sleep(0.01)


arm.disconnect()

If you want to perform servo_ cartesian motion, please note the following:

1) Set the motion mode to servoj mode:

arm.set_mode (1)

0: Position control mode     1: Joint servo (servoj) mode

3: Joint teaching mode       4: Cartesian teaching mode (not available)

2) Method for controlling motion speed of the UFACTORY xArm 

●  In the case of a certain frequency, the motion speed of the UFACTORY xArm can be                      controlled by adjusting the step value of the UFACTORY xArm motion.

●  The relationship between the frequency of the UFACTORY xArm receiving commands, the step value of the UFACTORY xArm motion and the motion speed of the UFACTORY xArm is as follows:

* The frequency with which the control box accepts commands

It can be known from time.sleep (0.01) that the frequency at which the control box accepts commands: f (Hz) = 100Hz

* The step value of the xArm motion

Note: The step value should be no more than 10mm, and the motion will not be                       executed after it is exceeded.

* The speed of the UFACTORY xArm motion

In this example:

The frequency at which the control box accepts commands: f (Hz) = 100Hz

The step value of the UFACTORY xArm in the x, y, and z directions are 1, 0, 0.

Thus, the motion speed of the UFACTORY xArm:

Note:

●  In servoj mode, the maximum receiving frequency of the control box is 250Hz (the maximum receiving frequency of the version before 1.4.0 is 100Hz). If the frequency of sending commands exceeds 250Hz, the redundant commands will be lost. 

●  If you want to plan the trajectory by yourself, you can use this command to issue a   smoothed trajectory point with interpolation at a certain frequency (preferably              100Hz or 200 Hz), similar to the position servo control command. (Note: this step is      similar to the highest step response, for safety reasons, do not give a distant target      position at once.)

●  The frequency of sending commands is recommended to be controlled within the range of 30Hz-250Hz. If the frequency is lower than 30Hz, the motion of the UFACTORY xArm may be discontinuous.

2. set_servo_anagle_j

The following is an example to explain the servo_cartesion motion.

import os
import sys
import time

sys.path.append(os.path.join(os.path.dirname(__file__), '../../..'))

from xarm.wrapper import XArmAPI


arm = XArmAPI('192.168.1.226')
arm.motion_enable(enable=True)
arm.set_mode(0)
arm.set_state(state=0)

arm.reset(wait=True)

arm.set_mode(1)
arm.set_state(0)
time.sleep(0.1)

while arm.connected and arm.state != 4:
for i in range(100):
angles = [i, 0, 0, 0, 0, 0, 0]
ret = arm.set_servo_angle_j(angles)
print('set_servo_angle_j, ret={}'.format(ret))
time.sleep(0.01)
for i in range(100):
angles = [100-i, 0, 0, 0, 0, 0, 0]
ret = arm.set_servo_angle_j(angles)
print('set_servo_angle_j, ret={}'.format(ret))
time.sleep(0.01)

arm.disconnect()

If you want to perform servoj motion, please note the following:

1) Set the motion mode to servoj mode:

arm.set_mode (1)

0: Position control mode 1: Joint servo (servoj) mode

3: Joint teaching mode 4: Cartesian teaching mode (not available)

Note:

● Servoj motion: move to the given joint position with the fastest speed (180°/s) and acceleration (unit: degree/radian). This command has no buffer, only execute the latest received target point, and the user needs to enter the servoj mode to use.

● The xArm-Python-SDK interface function we provide also reserves the speed, acceleration, and time settings, but they will not work at present.

● In servoj mode, the maximum receiving frequency of the control box is 250Hz (the maximum receiving frequency of the version before 1.4.0 is 100Hz). If the frequency of sending commands exceeds 250Hz, the redundant commands will be lost.

● If you want to plan the trajectory by yourself, you can use this command to issue a smoothed trajectory point with interpolation at a certain frequency (preferably 100Hz or 200 Hz), similar to the position servo control command. (Note: this step is similar to the highest step response, for safety reasons, do not give a distant target position at once.)

Did this answer your question?