Pro 450 Python Socket API
[toc]
Preparing for Use
Before using the Python API, please ensure that the following hardware and environment are complete:
Hardware
- MyCobot Pro 450 robot arm
- Network cable (for connecting the robot arm to the computer)
- Power adapter
- Emergency stop switch (for safe operation)
Software and Environment
- Python 3.6 or later installed
- The
pymycobot
library installed (using thepip install pymycobot
terminal command) - Ensure that the MyCobot Pro 450 is properly powered on and in standby mode.
- Note: The Pro 450 server automatically starts upon powering on; no manual operation is required.
Network Configuration
- MyCobot Pro 450 default IP address:
192.168.0.232
- Default port number:
4500
- Note: PC The local network card IP address must be set to the same network segment as the robot (e.g., 192.168.0.xxx, where xxx is a number between 2 and 254 and must not conflict with the robot).
Example:
- Robot IP: 192.168.0.232
- PC IP: 192.168.0.100
- Subnet mask: 255.255.255.0
Verification: After completing the network configuration, execute the following command on the PC terminal. If data packets are successfully returned, the network connection is normal:
ping 192.168.0.232
- MyCobot Pro 450 default IP address:
API usage instructions
API (Application Programming Interface), also known as Application Programming Interface functions, are predefined functions. When using the following function interfaces, please import our API library at the beginning by entering the following code, otherwise it will not run successfully:
Note: Before use, please make sure that the MyCobot Pro 450 server is turned on and the PC and the robot are in the same network segment.
# Example
from pymycobot import Pro450Client
# The default IP address is "192.168.0.232" and the default port number is 4500
mc = Pro450Client('192.168.0.232', 4500)
if mc.is_power_on() !=1:
mc.power_on()
print(mc.get_angles())
1. System Status
get_system_version()
- function: get system version
- Return value: system version
get_modified_version()
- function: Read the revision number, for internal use only
- Return value: Correction version number
get_robot_type()
function: Detection robot model
Return value: Definition Rule: Actual machine model. For example, the MyCobot Pro 450 model is 4503
get_atom_version()
- function: Get the end version number
- Return value: End parameters(
float
)
get_tool_modify_version()
- function: Read end correction version number
- Return value: end correction version
2. Overall Status
power_on()
- Function: Starts the robot (power on)
- Return value:
1
- Power on successfully.2
- Power on failed0
- Power not on
power_off()
Function: Shuts down the robot (power off)
Return value:
1
- Command received successfully.
is_power_on()
Function: Checks whether the robot is powered on
Return value:
1
: Power on successfully0
: Power not on2
: Power on failed
is_init_calibration()
function: Check if the robot is initialized for calibration
Return value:
bool
: True if the robot is initialized for calibration, False otherwise
get_fresh_mode()
function: Query sports mode
Return value:
0
: Interpolation mode1
: Refresh mode
set_fresh_mode()
function: Set command refresh mode
Parameters:
1
: Always execute the latest command first.0
: Execute instructions sequentially in the form of a queue.
get_debug_state()
Function: Get the current robot's debug logging mode.
Return value:
int
: Current debug logging state.0
: No debug logs1
: General debug log only (_debug.log)2
: Motion-related log only (_move.log)3
: General and motion-related logs (_debug.log + _move.log)4
: Motor read/control frequency log only (_clock_rate_debug.log)5
: General and motor frequency logs (_debug.log + _clock_rate_debug.log)6
: Motion and motor frequency logs (_move.log + _clock_rate_debug.log)7
: All logs
set_debug_state(log_state)
Function: Set the debug logging mode for the current robot.
Parameters:
log_state
:int
, debug log state (0 to 7)0
: Do not log any debug logs1
: General debug log only (_debug.log)2
: Motion-related log only (_move.log)3
: General and motion-related logs (_debug.log + _move.log)4
: Motor read/control frequency log only (_clock_rate_debug.log)5
: General and motor frequency logs (_debug.log + _clock_rate_debug.log)6
: Motion and motor frequency logs (_move.log + _clock_rate_debug.log)7
: Log all logs
Return value:
int
- 1 - Success
- 0 - Failure
- 1 - Error
set_communication_mode(communication_mode, protocol_mode=None)
Function: Sets the current robot communication mode.
Parameters:
communication_mode
:int
- 0 - Socket communication mode
- 1 - 485 communication mode
protocol_mode
:int
, protocol mode, optional, default: None0
: Custom protocol1
: Modbus protocol
- Return value:
int
- 1 - Success
- 0 - Failure
- 1 - Error
get_communication_mode()
Function: Gets the current robot communication mode.
Return value:
communication_mode
:int
- 0 - Socket communication mode
- 1 - 485 communication mode
protocol_mode
:int
0
: Custom protocol1
: Modbus protocol
3.Robot abnormal control
get_robot_status()
- function: Upper computer error security status
- Return value: 0 - Normal. other - Robot triggered collision detection
servo_restore(joint_id)
- function:Clear joint abnormalities
- Parameters:
joint_id
: int. joint id 1 - 6, 254-All joints restored.
get_comm_error_counts(joint_id)
- function:Read the number of communication exceptions
- Parameters:
joint_id
: int. joint id 1 - 6
get_error_information()
- Function: Read robot error information
- Return value:
int
0
: No error information1-6
: The corresponding joint exceeds the limit position.32-36
: Coordinate motion error.32
: No coordinate solution. Please check if the arm span is near the limit.33
: No adjacent solution for linear motion.34
: Velocity fusion error.35
: No adjacent solution for null space motion.36
: No solution for singular position. Please use joint control to leave the singular point.
clear_error_information()
- Function: Clear robot error information
over_limit_return_zero()
- Function: Return to zero for a joint exceeding the limit
get_motors_run_err()
- Function: Read motor error information during robot motion
- Return value:
list
, a list of 6, all zeros, indicating normal operation
4.MDI Mode and Operation
set_control_mode(mode)
- Function: Set the robot motion mode
- Parameter:
mode
:int
, 0 to 1, default 00
: Position mode1
: Torque mode
get_control_mode()
- Function: Get the robot motion mode
- Return value:
0
: Position mode1
: Torque mode
get_angles()
- function: get the degree of all joints
- Return value:
list
a float list of all degree
get_angle()
- function: Get single joint angle
- Parameters:
joint_id
(int): 1 ~ 6 - Return value:
float
, single joint angle
send_angle(id, degree, speed)
- function: send one degree of joint to robot arm
Parameters:
id
: Joint id(genre.Angle
), range int 1-6degree
: degree value(float
) | Joint Id | range | | ---- | ---- | | 1 | -165 ~ 165 | | 2 | -120 ~ 120 | | 3 | -158 ~ 158 | | 4 | -165 ~ 165 | | 5 | -165 ~ 165 | | 6 | -175 ~ 175 |speed
:the speed and range of the robotic arm's movement 1~100
send_angles(angles, speed)
- function: Send all angles to all joints of the robotic arm
- Parameters:
angles
: a list of degree value(List[float]
), length 6speed
: (int
) 1 ~ 100
get_coords()
- function: Obtain robot arm coordinates from a base based coordinate system
- Return value: a float list of coord:[x, y, z, rx, ry, rz]
send_coord(id, coord, speed)
- function: send one coord to robot arm
- Parameters:
id
:send one coord to robot arm, 1-6 corresponds to [x, y, z, rx, ry, rz]coord
: coord value(float
) | Coord Id | range | | ---- | ---- | | x | -466 ~ 466 | | y | -466 ~ 466 | | z | -230 ~ 614 | | rx | -180 ~ 180 | | ry | -180 ~ 180 | | rz | -180 ~ 180 |speed
: (int
) 1-100
send_coords(coords, speed, mode)
- function:: Send overall coordinates and posture to move the head of the robotic arm from its original point to your specified point
- Parameters:
- coords: : a list of coords value
[x,y,z,rx,ry,rz]
,length6 - speed
(int)
: 1 ~ 100
- coords: : a list of coords value
pause(deceleration=0)
- Function: Controls the core and stops all motion commands.
- Parameters:
deceleration
: Whether to decelerate and stop. The default value is 0. 1 indicates a deceleration.
- Return Value:
1
- stopped0
- not stopped-1
- error
is_paused()
- Function: Checks whether the program has paused a motion command.
- Return Value:
1
- paused0
- not paused-1
- error
resume()
- Function: Resume robot motion and complete the previous command.
stop(deceleration=0)
- Function: Stops robot motion.
- Parameters:
deceleration
: Whether to decelerate and stop. Defaults to 0. 1 indicates a slow stop.
- Return Value:
1
- Stopped0
- Not stopped-1
- Error
is_in_position(data, flag)
- function : judge whether in the position.
- Parameters:
data
: Provide a set of data that can be angles or coordinate values. If the input angle length range is 7, and if the input coordinate value length range is 6flag
: data type (value range 0 or 1)0
: angle1
: coord
- Return value:
1
- true0
- false-1
- error
is_moving()
- function: judge whether the robot is moving
- Return value:
1
moving0
not moving-1
error
5. JOG Mode and Operation
jog_angle(joint_id, direction, speed)
- function: jog control angle
- Parameters:
joint_id
: Represents the joints of the robotic arm, represented by joint IDs ranging from 1 to 6direction(int)
: To control the direction of movement of the robotic arm, input0
as negative value movement and input1
as positive value movementspeed
: 1 ~ 100
jog_coord(coord_id, direction, speed)
- function: jog control coord.
- Parameters:
coord_id
: (int
) Coordinate range of the robotic arm: 1~6direction
:(int
) To control the direction of machine arm movement,0
- negative value movement,1
- positive value movementspeed
: 1 ~ 100
jog_increment_angle(joint_id, increment, speed)
- function: Single joint angle increment control
- Parameters:
joint_id
: 1-6increment
: Incremental movement based on the current position anglespeed
: 1 ~ 100
jog_increment_coord(coord_id, increment, speed)
- function: Single joint angle increment control
- Parameters:
joint_id
: axis id 1 - 6.increment
: Incremental movement based on the current position coordspeed
: 1 ~ 100
6. Speed/Acceleration Parameters
get_max_speed(mode)
- Function: Get the maximum speed
- Parameters:
mode
:int
0
: Angular speed1
: Coordinate speed
- Return value: Angular speed range: 1-150°/s, coordinate speed range: 1-200mm/s
set_max_speed(mode, max_speed)
- Function: Set the maximum speed
- Parameters:
mode
:int
0
: Angular speed1
: Coordinate speed
max_speed
: Angular speed range: 1-150°/s, coordinate speed range: 1-200mm/s
get_max_acc(mode)
- Function: Get the maximum acceleration
- Parameters:
mode
:int
0
: Angular acceleration1
: Coordinate acceleration
- Return value: Angular acceleration range 1 to 150°/s, coordinate acceleration range 1 to 400 mm/s
set_max_acc(mode, max_acc)
- Function: Set maximum motion acceleration
- Parameters:
mode
:int
0
: Angular acceleration1
: Coordinate accelerationmax_acc
: Angular acceleration range 1 to 150°/s, coordinate acceleration range 1 to 400 mm/s
7. Joint software limit operation
get_joint_min_angle(joint_id)
- function: Read the minimum joint angle
- Parameters:
joint_id
: Enter joint ID (range 1-6)
- Return value:
float
Angle value
get_joint_max_angle(joint_id)
- function: Read the maximum joint angle
- Parameters:
joint_id
: Enter joint ID (range 1-6)
- Return value:
float
Angle value
set_joint_min_angle(id, angle)
- function: Set minimum joint angle limit
- Parameters:
id
: Enter joint ID (range 1-6)angle
: Refer to the limit information of the corresponding joint in the send_angle() interface, which must not be less than the minimum value
set_joint_max_angle(id, angle)
- function: Set minimum joint angle limit
- Parameters:
id
: Enter joint ID (range 1-6)angle
: Refer to the limit information of the corresponding joint in the send_angle() interface, which must not be greater than the maximum value
8. Joint motor auxiliary control
get_servo_encoders()
- function:Read the full joint encoder value
- Return value: A list of length 6
set_servo_calibration(servo_id)
- function: The current position of the calibration joint actuator is the angle zero point
- Parameters:
servo_id
: 1 - 6
set_break(joint_id, value)
- function: Set break point
- Parameters:
joint_id
: int. joint id 1 - 6value
: int. 0 - disable, 1 - enable
- Return value: 0 : faile; 1 : success
set_motor_enabled(joint_id, state
- function: Set the robot torque state.(Release joint interface)
- Parameters:
joint_id
: int. joint id 1 - 6, 254-all jointsstate
: int. 0 - disable, 1 - enable
9. Drag Teach
drag_teach_save()
- Function: Start recording and dragging the teach point.
- Note: For optimal motion performance, the recording time should not exceed 90 seconds.
drag_teach_execute()
- Function: Start dragging the teach point. Execute only once.
drag_teach_clean()
- Function: Clear the sampling point.
10. Dynamics
get_collision_mode()
- Function: Query the collision detection mode
- Return value:
0
: Off1
: On
set_collision_mode(mode)
- Function: Set the joint collision threshold
- Parameter:
int
mode
:0
: Off1
: On
get_collision_threshold()
- Function: Get the joint collision threshold
- Return value: A list of all joint collision thresholds
set_torque_comp(joint_id, comp_value=100)
- Function: Set the torque compensation coefficient
- Parameter:
joint_id
int
: Joint ID, range 1 to 6comp_value
: Compensation value, range 0-250, default 100. Smaller values result in more difficult joint dragging.
get_torque_comp()
- Function: Get torque compensation coefficients
- Return value: A list of torque compensation coefficients for all joints
fourier_trajectories(trajectory)
- Function: Execute dynamic identification trajectory
- Parameter:
trajectory
:int
, range 0-1
parameter_identify()
- Function: Kinetic parameter identification
11. Circular Motion
write_move_c(transpoint, endpoint, speed)
- Function: Circular arc motion (specify transit points)
- Parameter:
transpoint(list)
: Arc transit pointsendpoint(list)
: Arc endpointspeed(int)
: 1 to 100
12. Run auxiliary information
get_zero_pos()
- function: Read the zero encoder value
- Return value:
list
The value of the zero encoder for seven joints
get_servo_speeds()
- function:Get the movement speed of all joints
- Return value: unit step/s
get_servo_currents()
- function:Get the movement current of all joints
- Return value: 0 ~ 5000 mA
get_servo_status()
- function:Get the movement status of all joints
- Return value: a value of 0 means no error
13. Robotic arm end IO control
set_digital_output(pin_no, pin_signal)
- Function: Set terminal IO status
- Parameters
pin_no
(int): Pin number, range 1 to 2pin_signal
(int): 0 / 1, 0 - low level, 1 - high level
- Return Value:
1
: Completed
get_digital_input(pin_no)
- Function: Get terminal IO status
- Parameters:
pin_no
(int), range 1 to 2 - Return Value:
int
0 / 1, 0 - low level, 1 - high level
14. End Light Panel Function
set_color(r, g, b)
Function: Set the color of the end light of the robot arm
Parameter:
r (int)
: 0 to 255g (int)
: 0 to 255b (int)
: 0 to 255
15. Bottom IO control
set_base_io_output(pin_no, pin_signal)
- function:Set Base IO Output
- Parameters:
pin_no
(int
) Pin port number, range 1 ~ 12pin_signal
(int
): 0 - low. 1 - high
get_base_io_output(pin_no)
- function: Read base IO input
- Parameters:
pin_no
(int
) pin number, range 1 ~ 12
- Return value: 0 - low. 1 - high
set_base_external_config(communicate_mode, baud_rate, timeout)
- Function: Set the bottom external device configuration
- Parameter:
communicate_mode
(int
) Range: 1 to 21
: 4852
: can
baud_rate
(int
): Baud ratetimeout
: Timeout
get_base_external_config()
- Function: Read the bottom external device configuration
- Return value:
list
returns a list: [communication mode, baud rate, timeout]
base_external_can_control(can_id, can_data)
- Function: Controls CAN devices on the bottom
- Parameters:
can_id
(int
) Range: 1 to 4can_data
(list
) List contents are in hexadecimal format, with a maximum length of 64 characters.
base_external_485_control(data)
- Function: Controls 485 devices on the bottom
- Parameters:
data
(list
) List contents are in hexadecimal format, with a maximum length of 64 characters.
16. Set up 485 communication at the end of the robotic arm
tool_serial_read_data(data_len)
- function: Read fixed length data. Before reading, read the buffer length first. After reading, the data will be cleared
- Parameters: data_len (int): The number of bytes to be read, range 1 ~ 45
- Return value: 0 : not set 1 : Setup completed
tool_serial_write_data(command)
- function: End 485 sends data, Data length range is 1 ~ 45 bytes
- Parameters:
command
(list
): Data instructions in modbus format
- Return value: Modbus data list
set_over_time(timeout=1000)
- function: Set the timeout (unit: ms), default is 1000ms (1 second)
- Parameters: timeout (int): Timeout period, in ms, range 0~65535
flash_tool_firmware(main_version, modified_version=0)
- Function: Flash the terminal firmware
- Parameters:
main_version (str)
: Major and minor version numbers, e.g.1.1
modified_version (int)
: Modified version number, range 0 to 255, default is 0
17. Tool Coordinate System Operations
set_tool_reference(coords)
- Function: Set the tool coordinate system
Parameters:
coords
: (list
) [x, y, z, rx, ry, rz].| Coord Id | range | | ---- | ---- | | x | -1000 ~ 1000 | | y | -1000 ~ 1000 | | z | -1000 ~ 1000 | | rx | -180 ~ 180 | | ry | -180 ~ 180 | | rz | -180 ~ 180 |
get_tool_reference(coords)
- Function: Get the tool coordinate system
- Return value: (
list
) [x, y, z, rx, ry, rz]
set_world_reference(coords)
- Function: Set the world coordinate system
Parameters:
coords
: (list
) [x, y, z, rx, ry, rz].| Coord Id | range | | ---- | ---- | | x | -1000 ~ 1000 | | y | -1000 ~ 1000 | | z | -1000 ~ 1000 | | rx | -180 ~ 180 | | ry | -180 ~ 180 | | rz | -180 ~ 180 |
get_world_reference()
- Function: Get the world coordinate system.
- Return value:
list
[x, y, z, rx, ry, rz].
set_reference_frame(rftype)
- Function: Set the base coordinate system
- Parameters:
rftype
: 0 - Base coordinates (default), 1 - World coordinates.
get_reference_frame()
- Function: Get the base coordinate system
- Return value: (list`) [x, y, z, rx, ry, rz].
set_movement_type(move_type)
- Function: Set the movement type
- Parameters:
move_type
: 1 - moveL, 0 - moveJ.
get_movement_type()
- Function: Get the movement type
- Return value:
1
- moveL0
- moveJ
set_end_type(end)
- Function: Set the end coordinate system
- Parameters:
end (int)
:0
- Flange (default),1
- Tool
get_end_type()
- Function: Get the end coordinate system
- Return value:
0
- Flange (default)1
- Tool
18. Algorithm Parameters
get_vr_mode()
- Function: Get the VR mode
- Return value:
0
: Off1
: On
set_vr_mode(move)
- Function: Set the VR mode
- Parameters:
move
: 1 - On, 0 - Off.
get_model_direction()
- Function: Get the joint model direction
- Return value: Model direction of joints 1-6
1
- Same direction as the motor0
- Opposite direction from the motor
set_model_direction(joint_id, direction)
- Function: Set the joint model direction
- Parameters:
joint_id (int)
: 1 to 6direction (int)
:1
- Same direction as the motor.0
- Opposite direction from the motor
get_filter_len(rank)
- Function: Get filter parameters
- Parameters:
rank
:int
1
: Drag teach sampling filter2
: Drag teach execution filter3
: Joint velocity fusion filter4
: Coordinate velocity fusion filter5
: Drag teach sampling period
- Return value:
int
1 to 100
set_filter_len(rank, value)
- Function: Set filter parameters
- Parameters:
rank (int)
: 1 to 5value (int)
: 1 to 100
get_fusion_parameters(rank_mode)
- Function: Get velocity fusion planning parameters
- Parameters:
rank_mode
: 1 to 41
: Fusion joint velocity2
: Fusion joint acceleration3
: Fusion coordinate velocity4
: Fusion coordinate acceleration
- Return value:
(int)
: 0 to 1000
set_fusion_parameters(rank_mode, value)
- Function: Set velocity fusion planning parameters
- Parameters:
rank_mode (int)
: 1 to 4value (int)
: 0 to 1000
19. Kinematics Algorithm Interface
solve_inv_kinematics(target_coords, current_angles)
- Function: Convert coordinates to angles.
- Parameters
target_coords
:list
A list of floating-point values for all coordinates.current_angles
:list
A list of floating-point values for all angles, indicating the current angles of the robot arm.
- Return Value:
list
A list of floating-point values for all angles.
20. Pro force-controlled gripper
get_pro_gripper_firmware_version( gripper_id=14)
- Function: Read the major and minor versions of the Pro Force Control Gripper firmware.
Parameter:
gripper_id
(int
): Gripper ID, default is 14, value range is 1 to 254.
Return value: (
float
) Version number, x.x
get_pro_gripper_firmware_modified_version(gripper_id=14)
- Function: Read the modified version of the Pro Force Control Gripper firmware.
Parameter:
gripper_id
(int
): Gripper ID, default is 14, value range is 1 to 254.
Return value: (int) Correction version number
set_pro_gripper_id(target_id, gripper_id=14)
- Function: Set the force-controlled gripper ID.
- Parameter:
target_id
(int): Range: 1 to 254.gripper_id
(int): Gripper ID, default: 14, range: 1 to 254.
- Return value:
- 0 - Failure
- 1 - Success
get_pro_gripper_id(gripper_id=14)
- Function: Read the force-controlled gripper ID.
- Parameter:
gripper_id
(int): Gripper ID, default: 14, range: 1 to 254.
- Return value:
int
Range: 1 to 254.
set_pro_gripper_angle(gripper_angle,gripper_id=14)
- Function: Set the force-controlled gripper angle.
- Parameter:
gripper_angle
(int
): Gripper angle, value range 0 ~ 100.gripper_id
(int
) Gripper ID, default 14, value range 1 ~ 254.
- Return value:
- 0 - Failed
- 1 - Success
get_pro_gripper_angle(gripper_id=14)
- Function: Read the angle of the force-controlled gripper.
- Parameter:
gripper_id
(int
): Gripper ID, default 14, value range 1 ~ 254.
- Return value:
int
0 ~ 100
set_pro_gripper_open(gripper_id=14)
- Function: Open the force-controlled gripper.
- Parameter:
gripper_id
(int
): Gripper ID, default 14, value range 1 ~ 254.
- Return value:
- 0 - Failed
- 1 - Success
set_pro_gripper_close(gripper_id=14)
- Function: Close the force-controlled gripper.
- Parameter:
gripper_id
(int
): Gripper ID, default 14, value range 1 ~ 254.
- Return value:
- 0 - Failed
- 1 - Success
set_pro_gripper_calibration(gripper_id=14)
- Function: Set the zero position of the force-controlled gripper. (The zero position needs to be set first when using it for the first time)
- Parameter:
gripper_id
(int
): Gripper ID, default 14, value range 1 ~ 254.
- Return value:
- 0 - Failed
- 1 - Success
get_pro_gripper_status(gripper_id=14)
- Function: Read the gripping status of the force-controlled gripper.
- Parameter:
gripper_id
(int
): Gripper ID, default 14, value range 1 ~ 254.
- Return value:
0
- Moving.1
- Stopped moving, no object was detected.2
- Stopped moving, object was detected.3
- After the object was detected, it fell.
set_pro_gripper_enabled(state, gripper_id=14)
- Function: Sets the force-controlled gripper enable state.
- Parameter:
state
(bool
): 0 or 1, 0 - disable, 1 - enablegripper_id
(int
): Gripper ID, default 14, range 1 to 254.
- Return Value:
- 0 - Failure
- 1 - Success
set_pro_gripper_torque(torque_value,gripper_id=14)
- Function: Set the torque of the force-controlled gripper.
- Parameter:
torque_value
(int
): Torque value, value range 0 ~ 100.gripper_id
(int
): Gripper ID, default 14, value range 1 ~ 254.
- Return value:
- 0 - Failed
- 1 - Success
get_pro_gripper_torque(gripper_id=14)
- Function: Read the torque of the force-controlled gripper.
- Parameter:
gripper_id
(int
): Gripper ID, default 14, value range 1 ~ 254.
- Return value: (
int
) 0 ~ 100
set_pro_gripper_speed(speed,gripper_id=14)
- Function: Set the force-controlled gripper speed.
- Parameter:
speed
(int): Gripper movement speed, value range 1 ~ 100.gripper_id
(int
) Gripper ID, default 14, value range 1 ~ 254.
- Return value:
- 0 - Failed
- 1 - Success
get_pro_gripper_speed(speed,gripper_id=14)
- Function: Read the speed of the force-controlled gripper.
- Parameter:
gripper_id
(int
): Gripper ID, default 14, value range 1 ~ 254.
- Return value: Gripper default movement speed, range 1 ~ 100.
set_pro_gripper_abs_angle(gripper_angle,gripper_id=14)
- Function: Set the absolute angle of the force-controlled gripper.
- Parameter:
gripper_angle
(int
): Gripper angle, value range 0 ~ 100.gripper_id
(int
) Gripper ID, default 14, value range 1 ~ 254.
- Return value:
- 0 - Failed
- 1 - Success
set_pro_gripper_io_open_angle(gripper_angle, gripper_id=14)
- Function: Sets the force-controlled gripper I/O opening angle.
- Parameter:
gripper_angle
(int
): Gripper angle, value range 0 to 100.gripper_id
(int
): Gripper ID, default 14, value range 1 to 254.
- Return Value:
- 0 - Failure
- 1 - Success
get_pro_gripper_io_open_angle(gripper_id=14)
- Function: Reads the force-controlled gripper I/O opening angle.
- Parameter:
gripper_id
(int
): Gripper ID, default 14, value range 1 to 254.
- Return value:
int
0 to 100
set_pro_gripper_io_close_angle(gripper_angle, gripper_id=14)
- Function: Sets the force-controlled gripper IO closing angle.
- Parameter:
gripper_angle
(int
): Gripper angle, value range 0 to 100.gripper_id
(int
): Gripper ID, default 14, value range 1 to 254.
- Return value:
- 0 - Failure
- 1 - Success
get_pro_gripper_io_close_angle(gripper_id=14)
- Function: Read the force-controlled gripper IO closing angle.
- Parameter:
gripper_id
(int
): Gripper ID, default 14, value range 1 to 254.
- Return value:
int
0 to 100
set_pro_gripper_mini_pressure(pressure_value, gripper_id=14)
- Function: Set the minimum actuation force of the force-controlled gripper
- Parameter:
pressure_value
(int
): Actuation force value, range 0 to 254.gripper_id
(int
): Gripper ID, default 14, range 1 to 254.
- Return value:
- 0 - Failure
- 1 - Success
get_pro_gripper_mini_pressure(gripper_id=14)
- Function: Read the minimum actuation force of the force-controlled gripper
- Parameter:
gripper_id
(int
): Gripper ID, default 14, range 1 to 254.
- Return value: (
int
) Starting force value, range 0 to 254.
set_pro_gripper_protection_current(current_value, gripper_id=14)
- Function: Set the gripping current of the force-controlled gripper
- Parameter:
current_value
(int
): Gripping current value, range 100 to 300.gripper_id
(int
) Gripper ID, default 14, range 1 to 254.
- Return value:
- 0 - Failure
- 1 - Success
get_pro_gripper_protection_current(gripper_id=14)
- Function: Read the gripping current of the force-controlled gripper
- Parameter:
gripper_id
(int
) Gripper ID, default 14, range 1 to 254.
- Return value: (
int
) Clamping current value, range 100 ~ 300.