Closed wcdoug closed 1 year ago
I figured this out. By switching from arm.set_position to arm.set_servo_cartesian - it is completely smooth now.
What wasn't working (jerky): arm.set_position(*[int(set_robot_x), set_robot_y, set_robot_z, 180, 0.0, rect_angle], speed=robot_speed, mvacc=robot_acceleration, radius=10.0, wait=False)
What is working (no jerk): arm.set_servo_cartesian(mvpose, speed=robot_speed, mvacc=2000)
Hi @wcdoug, We noticed you are using joystick to jog xArm in Cartesian space dynamically, right? In this case, I believe the better option is to use Cartesian Velocity control (In Mode 5) or Online Trajectory Planing (in Mode 7).
(1) set_position()
in default mode 0 is not meant for dynamic control, it will queue up all the received targets and execute sequentially. It is more suitable for fixed trajectory and repetitive tasks.
(2) set_servo_cartesian()
in mode 1 is indeed for dynamic control, but requires the trajectory command to be updated in a high frequency, like directly sending servo commands within milliseconds. It was targeted for high frequency control or execute 3rd party generated trajectory (like ROS Moveit). As you may noticed, the speed/acceleration arguments are not effective since it is immediate (jump) execution and no additional planning introduced.
(3) Please refer to the Mode 5 Cartesian Velocity control API (doc is similar with its previous function for joint space) and its example code. We recommend to enable and use the duration
argument as a timeout for auto-stop, in case the network communication is bad or lost.
(4) Alternatively, you may try the set_position()
command in Mode 7, which will respond to the latest target immediately with automated planning with respect to specified speed and acceleration. It does not require high frequency control but updating the command at any time. Please refer to the example code here.
Thanks, I'll check it out.
On Mon, May 22, 2023 at 7:58 PM penglongxiang @.***> wrote:
Hi @wcdoug https://github.com/wcdoug, We noticed you are using joystick to jog xArm in Cartesian space dynamically, right? In this case, I believe the better option is to use Cartesian Velocity control (In Mode 5) or Online Trajectory Planing (in Mode 7).
(1) set_position() in default mode 0 is not meant for dynamic control, it will queue up all the received targets and execute sequentially. It is more suitable for fixed trajectory and repetitive tasks. (2) set_servo_cartesian() in mode 1 is indeed for dynamic control, but requires the trajectory command to be updated in a high frequency, like directly sending servo commands within milliseconds. It was targeted for high frequency control or execute 3rd party generated trajectory (like ROS Moveit). As you may noticed, the speed/acceleration arguments are not effective since it is immediate (jump) execution and no additional planning introduced. (3) Please refer to the Mode 5 Cartesian Velocity control API https://github.com/xArm-Developer/xArm-Python-SDK/blob/0fd107977ee9e66b6841ea9108583398a01f227b/xarm/wrapper/xarm_api.py#L2961 (doc is similar with its previous function for joint space) and its example code https://github.com/xArm-Developer/xArm-Python-SDK/blob/master/example/wrapper/common/1009-cartesian_velocity_control.py. We recommend to enable and use the duration argument as a timeout for auto-stop, in case the network communication is bad or lost. (4) Alternatively, you may try the set_position() command in Mode 7, which will respond to the latest target immediately with automated planning with respect to specified speed and acceleration. It does not require high frequency control but updating the command at any time. Please refer to the example code https://github.com/xArm-Developer/xArm-Python-SDK/blob/master/example/wrapper/common/1010-cartesian_online_trajectory_planning.py here.
— Reply to this email directly, view it on GitHub https://github.com/xArm-Developer/xArm-Python-SDK/issues/77#issuecomment-1558429454, or unsubscribe https://github.com/notifications/unsubscribe-auth/APXG4TK3SXEPMMEWDPB6TI3XHQRUPANCNFSM6AAAAAAYH6IH2A . You are receiving this because you were mentioned.Message ID: @.***>
Thanks! That worked great.
The challenge I now have is resetting the robot when it has a collision. I've tried all the clear and clean warnings, set state, set motion, etc...and some times it works...but many times I have to go back into the software to reset and then go back to program again to control from robot. Any suggestions?
Note...I am doing tons of work to try to prevent collisions (defining mins, max, and polygons where the robot shouldn't go...
On Tue, May 23, 2023 at 2:24 PM Douglas Lieberman @.***> wrote:
Thanks, I'll check it out.
On Mon, May 22, 2023 at 7:58 PM penglongxiang @.***> wrote:
Hi @wcdoug https://github.com/wcdoug, We noticed you are using joystick to jog xArm in Cartesian space dynamically, right? In this case, I believe the better option is to use Cartesian Velocity control (In Mode 5) or Online Trajectory Planing (in Mode 7).
(1) set_position() in default mode 0 is not meant for dynamic control, it will queue up all the received targets and execute sequentially. It is more suitable for fixed trajectory and repetitive tasks. (2) set_servo_cartesian() in mode 1 is indeed for dynamic control, but requires the trajectory command to be updated in a high frequency, like directly sending servo commands within milliseconds. It was targeted for high frequency control or execute 3rd party generated trajectory (like ROS Moveit). As you may noticed, the speed/acceleration arguments are not effective since it is immediate (jump) execution and no additional planning introduced. (3) Please refer to the Mode 5 Cartesian Velocity control API https://github.com/xArm-Developer/xArm-Python-SDK/blob/0fd107977ee9e66b6841ea9108583398a01f227b/xarm/wrapper/xarm_api.py#L2961 (doc is similar with its previous function for joint space) and its example code https://github.com/xArm-Developer/xArm-Python-SDK/blob/master/example/wrapper/common/1009-cartesian_velocity_control.py. We recommend to enable and use the duration argument as a timeout for auto-stop, in case the network communication is bad or lost. (4) Alternatively, you may try the set_position() command in Mode 7, which will respond to the latest target immediately with automated planning with respect to specified speed and acceleration. It does not require high frequency control but updating the command at any time. Please refer to the example code https://github.com/xArm-Developer/xArm-Python-SDK/blob/master/example/wrapper/common/1010-cartesian_online_trajectory_planning.py here.
— Reply to this email directly, view it on GitHub https://github.com/xArm-Developer/xArm-Python-SDK/issues/77#issuecomment-1558429454, or unsubscribe https://github.com/notifications/unsubscribe-auth/APXG4TK3SXEPMMEWDPB6TI3XHQRUPANCNFSM6AAAAAAYH6IH2A . You are receiving this because you were mentioned.Message ID: @.***>
Hi @wcdoug, please check the readme chapter 6.2 to properly recover from collision or other errors. The proper order should be calling clear_err
, then set_mode
and set_state (0)
in the exact order.
We will be releasing a new version of firmware (should be v2.2.0) in the near future, and collision detection logic has been optimized, hopefully reducing the chance of false collision report.
I have been struggling for a few days on this. Tried lots of combinations of speed, acceleration, timeouts between sending commands to robot (from 0 to 25 to 800 ms), setting continuous on...can't seem to eliminate significant "jerk" in the movement
Has anyone successfully found a combination of settings that allows simple control of the xArm 5 with joysticks (using pything sdk?)