10. Robotic Arm Motion Mode and State
The controller provides 7 motion mode and 6 state, corresponding to python SDK set_mode, set_state.
10.1 Robotic Arm Mode
Mode 0: Position Control Mode
The control box enters this mode by default after startup.
Joint Motion
To achieve the point-to-point motion of joint space (unit: degree/radian), the speed between each command is discontinuous.
Python Example: set_servo_angle
Linear Motion
To achieve linear motion between Cartesian coordinates (unit: mm), the speed between each instruction is discontinuous.
Python Example: set_position, set_position_aa
Arc Linear Motion:
To achieve linear motion between Cartesian coordinates (unit: mm), inserting an arc between two straight lines for a smooth transition, and the speed between each command is continuous.
Python Example: move_arc_lines
Circular Motion:
Circular motion calculates the trajectory of the spatial circle according to the three-point coordinates, the three-point coordinates are starting point, parameter 1 and parameter 2.
Python Example: move_circle
Mode 1: Servo(ServoJ) Mode
Servo Joint 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. In servoj mode, the maximum receiving frequency of the control box is 250 Hz (the maximum receiving frequency of the version before 1.4.0 is 100 Hz). If the frequency of sending commands exceeds 250Hz, the redundant commands will be lost. The xArm-Python-SDK interface function we provide also reserves the speed, acceleration and time settings, but they will not work at present. The suggested way of use: If you want to plan your track, you can use this command to issue a smoothed track point with interpolation at a certain frequency (preferably 100Hz or 200 Hz), similar to the position servo control command. (Note: this execution is similar to the step response, for safety considerations, do not give a distant target position at once). Using this mode requires detailed position planning for each axis and motion estimation of the robotic arm, which is difficult to develop.
Python Example: set_servo_angle_j
Servo Cartesian Motion Move to the given cartesian position with the fastest speed (1 m/s) and acceleration (unit: mm). This command has no buffer, only execute the latest received target point, and the user needs to enter the servoj mode to use. In servoj mode, the maximum receiving frequency of the control box is 250 Hz (the maximum receiving frequency of the version before 1.4.0 is 100 Hz). If the frequency of sending commands exceeds 250 Hz, the redundant commands will be lost. The xArm-Python-SDK interface function we provide also reserves the speed, acceleration and time settings, but they will not work at present.
The suggested way of use: If you want to plan your track, you can use this command to issue a smoothed track point with interpolation at a certain frequency (preferably 100 Hz or 200 Hz), similar to the position servo control command. (Note: this execution is similar to the step response, for safety considerations, do not give a distant target position at once). It is recommended that the frequency of user issuing commands be controlled within the range of 30 Hz-250 Hz. If the frequency is lower than 30 Hz, the motion of the robotic arm may be discontinuous. Using this mode requires planning the fine position of each axis and predicting the motion behavior of the robotic arm, which is difficult to develop.
Python Example: servo_cartesian, servo_cartesian_aa
Mode 2: Manual Mode
In this mode, the robotic arm will enter the zero gravity mode, and the user can freely drag the links of the robotic arm to complete the teaching function. If the drag teaching is completed, switch back to mode 0.
Note for safe use: Before turning on the joint teaching mode, be sure to confirm that the installation direction of the robotic arm and the TCP load are set correctly, otherwise the arm may not be able to remain stationary due to inaccurate gravity compensation.
Python Example:
arm.set_mode(2)
arm.set_state(0)
Mode 4: Joint Velocity Control Mode
Joint motion with specified velocity for each joint (unit: rad/s).
Python Example: vc_set_joint_velocity
Mode 5: Cartesian Velocity Mode
Linear motion of TCP with specified velocity in mm/s (position) and rad/s (orientation in axis-angular_velocity).
Python Example: vc_set_cartesian_velocity
Mode 6: Joint online planning Mode
Command sent by set_servo_angle(). In this mode, every time a motion command is received, the current motion command will be interrupted, and then the motion command will be planned and executed from the current position, and the latter motion command can be interrupted Ongoing movement.
Python Example: set_servo_angle
Mode 7: Cartesian online planning Mode
Command sent by set_position() or set_position_aa(). In this mode, every time a motion command is received, the current motion command will be interrupted, and then the motion command will be planned and executed from the current position, and the latter motion command can be interrupted Ongoing movement.
Note: When using Cartesian online planning mode, the is_tool_coord
in set_position_aa()
must be False, that is, Cartesian online planning mode can only use the base coordinate system as the reference coordinate system, not the tool coordinate system for relative motion.
Python Example: set_position
10.2 Robotic Arm State
State 0
Set: configure the robot the be STANDBY state in corresponding mode, and clear the error code as well. Note: after this setting, the feedback state will switch to 2(REDDY) automatically.
State 1
Feedback. The robot is in motion.
State 2
Feedback. The robot is ready to receive and execute commands.
State 3
Set and Feedback.
- set: set the robot to a PAUSED state when executing motion commands, the motion can be resumed by setting state 0.
- feedback: the robot is in PAUSE state.
State 4
Set and Feedback.
- set: set the robot to STOP state, it will terminate any execution immediately and will not receive or execute any new command until the state is set back to STANDBY.
- feedback: the robot is in STOP state, can't receive and execute any command, and will automatically switch to this state when any error occurs.
State 5
Feedback. MODE_CHANGED state, will automatically switch to this state if some critical configurations (mode, payload, TCP offset, collision sensitivity, etc) have been changed, and cannot receive and execute any command until set state 0.
State 6
Set and Feedback. Perform a decelerated stop immediately.