API Reference
RobotiqGripper
- class RobotiqGripper(com_port='auto', device_id=9, connection_type='RTU', tcp_host='127.0.0.1', tcp_port=54321, debug=False, **kwargs)[source]
Bases:
objectClass use to control Robotiq grippers (2F85, 2F140 or hande).
This class provides methods to initialize, open, close, and monitor the gripper.
Physical connection
The physical connection with the gripper can done in 2 ways: - Connected to the PC via the USB/RS485 adapter. - Connected to the UR robot: In this case the UR RS485 URCAP needs to be installed on the robot controller.
Modbus RTU/TCP communication
Modbus RTU function code supported by robotiq gripper
Description
Modbus function code
Read registers
4
Write registers
16
Master read & write multiple registers
23
For more information for gripper communication please check gripper manual on Robotiq website. https://robotiq.com/support/2f-85-2f-140
Note
This class cannot be use to control epick, 3F or powerpick.
- __init__(com_port='auto', device_id=9, connection_type='RTU', tcp_host='127.0.0.1', tcp_port=54321, debug=False, **kwargs)[source]
Create a RobotiqGripper object which can be use to control Robotiq grippers using modbus RTU protocol USB/RS485 connection.
- Parameters:
com_port (str) – COM port to which the gripper is connected. If “auto” (or equal to the constant AUTO_DETECTION), the library will try to find the COM port to which the gripper is connected. On Windows, COM ports are named COM1, COM2, etc. On Linux, COM ports are named /dev/ttyUSB0, /dev/ttyUSB1, etc. Default is AUTO_DETECTION.
device_id (int) – Address of the gripper (integer) usually 9.
gripper_type (str) – Type of the gripper. Currently only “2F” is supported. Default is “2F”.
connection_type (str) – Type of connection to the gripper. “RTU” (or equal to the constant GRIPPER_MODE_RTU) for direct Modbus RTU connection (e.g. via USB/RS485 adapter). “RTU_VIA_TCP” (or equal to the constant GRIPPER_MODE_RTU_VIA_TCP) for Modbus RTU connection via TCP (e.g. when using the UR RS485 URCAP). Default is “RTU”.
tcp_host (str) – Host IP address for TCP connection. Default is “127.0.0.1”
tcp_port (int) – Port number for TCP connection. Default is 54321.
debug (bool) – If True, enable debug logging for Modbus communication. Default is False.
Examples
Gripper connected at PC USB port:
>>> import pyrobotiqgripper as rq >>> gripper = rq.RobotiqGripper(connection_type=rq.GRIPPER_MODE_RTU) >>> gripper.connect() >>> gripper.activate() >>> gripper.start() >>> gripper.open() >>> gripper.close() >>> gripper.move(100) #Move at position 100 in bit >>> print(gripper.position()) #Print gripper position in bit >>> gripper.calibrate_mm(closemm=0,openmm=85) #Calibrate the gripper with 0mm when closed and 85mm when open >>> gripper.move_mm(50) #Move at position 50mm >>> gripper.printStatus() #Print gripper status information in the python terminal >>> print(gripper.positionmm()) #Print gripper position in mm
Gripper connected to UR robot via RS495 URCAP (RTU over TCP):
>>> import pyrobotiqgripper as rq >>> gripper = rq.RobotiqGripper(connection_type=rq.GRIPPER_MODE_RTU_VIA_TCP,tcp_host="192.168.1.100") >>> gripper.connect() >>> gripper.activate() >>> gripper.start() >>> gripper.open()
- Parameters:
com_port (str)
device_id (int)
connection_type (str)
tcp_host (str)
tcp_port (int)
debug (bool)
Setup
- RobotiqGripper.connect()[source]
Connect to the gripper. If the connection is already established, do nothing.
- RobotiqGripper.disconnect()[source]
Disconnect from the gripper. If the connection is already closed, do nothing.
- RobotiqGripper.reset()[source]
Reset the gripper (clear previous activation and calibration if any)
- RobotiqGripper.activate(reset=True, start=True, refreshStatus=True)[source]
Activate the gripper if it is not already active.
- Parameters:
reset (bool) – Whether to reset the gripper before activation.
start (bool) – Whether to start the gripper motion immediately after activation (gGTO set to 1).
refreshStatus (bool) – Whether to refresh the gripper status before the activation process. The status information is used to determine if the gripper is already activated. Setting this parameter to False can make the activation faster if you are sure the gripper status is up to date.
Warning
When you execute this function, the gripper will fully open and close. During this operation, the gripper must be able to move freely. Do not place any object inside the gripper.
- RobotiqGripper.start(refreshStatus=True)[source]
Start the gripper motion.
The GTO bit is set to 1. The gripper will move to the position command if it is not already there.
- Parameters:
refreshStatus (bool) – Whether to refresh the gripper status before the start process. The status information is used to determine if the gripper is already started. Setting this parameter to False can make the start process faster if you are sure the gripper status is up to date.
- RobotiqGripper.stop()[source]
Gripper stop moving. GTO bit is set to 0 but the position command is not changed. The gripper will stop at its current position and hold it.
- RobotiqGripper.calibrate_bit(openbit=None, closebit=None)[source]
Calibrate the maximum and minimum position bit values of the gripper.
This function sets the reference positions for the gripper in bits. If no parameters are provided, the gripper will perform a full open followed by a full close to measure the maximum and minimum positions.
- Parameters:
openbit (int, optional) – Position value in bits when the gripper is open.
closebit (int, optional) – Position value in bits when the gripper is closed.
Warning
If no parameters are provided, the gripper will make a full open followed by a full close to measure the maximum and minimum positions in bits. Ensure the gripper can move freely during this operation.
- RobotiqGripper.calibrate_speed(minSpeedClosingTime=None, maxSpeedClosingTime=None)[source]
Calibrate gripper speed to estimate gripper position over time.
If no parameters are provided, the gripper will perform a full-speed closing and a slow-speed closing to evaluate its motion. Bit calibration will also be performed.
- Parameters:
minSpeedClosingTime (float, optional) – Time in seconds for the gripper to move from fully open to fully closed at minimum speed.
maxSpeedClosingTime (float, optional) – Time in seconds for the gripper to move from fully open to fully closed at maximum speed.
Warning
If no parameters are provided, the gripper will perform a full-speed closing and a slow-speed closing to evaluate its motion. Ensure the gripper can move freely during this operation.
- RobotiqGripper.calibrate_mm(closemm, openmm)[source]
Calibrate the gripper for millimeter positioning.
Once this calibration is done, it is possible to control the gripper using millimeters.
- Parameters:
closemm (float) – Distance between the fingers when the gripper is fully closed.
openmm (float) – Distance between the fingers when the gripper is fully open.
Warning
Bit calibration is required before executing this function. If the bit calibration is not done, the function calibrate_bit() will be executed automatically before calibrating in millimeters.
Control
- RobotiqGripper.open(speed=255, force=255, wait=True, readStatus=True, refreshStatus=False)[source]
Open the gripper.
- Parameters:
speed (int, optional) – Gripper speed between 0 and 255. Defaults to 255.
force (int, optional) – Gripper force between 0 and 255. Defaults to 255.
wait (bool, optional) – If True, the function waits until the gripper reaches the requested position or detects an object. Defaults to True.
readStatus (bool, optional) – If True, the gripper status is read after sending the command. Defaults to True.
refreshStatus (bool, optional) – If True, the gripper status is refreshed before sending the command. The status information is used to determine if the gripper is already activated. Setting this parameter to False can make the command process faster if the gripper status is up to date. Defaults to False.
- RobotiqGripper.close(speed=255, force=255, wait=True, readStatus=True, refreshStatus=False)[source]
Close the gripper.
- Parameters:
speed (int, optional) – Gripper speed between 0 and 255. Defaults to 255.
force (int, optional) – Gripper force between 0 and 255. Defaults to 255.
wait (bool, optional) – If True, the function waits until the gripper reaches the requested position or detects an object. Defaults to True.
readStatus (bool, optional) – If True, the gripper status is read after sending the command. Defaults to True.
refreshStatus (bool, optional) – If True, the gripper status is refreshed before sending the command. The status information is used to determine if the gripper is already activated. Setting this parameter to False can make the command process faster if the gripper status is up to date. Defaults to False.
- RobotiqGripper.move(position, speed=255, force=255, wait=True, readStatus=True, refreshStatus=False)[source]
Move gripper fingers to the requested position with specified speed and force.
- Parameters:
position (int) – Target position of the gripper. Must be between 0 and 255, where 0 represents fully open and 255 represents fully closed.
speed (int, optional) – Gripper speed between 0 and 255. Defaults to 255.
force (int, optional) – Gripper force between 0 and 255. Defaults to 255.
wait (bool, optional) – If True, the function waits until the gripper reaches the requested position or detects an object. Defaults to True.
readStatus (bool, optional) – If True, the gripper status is read after sending the command. Defaults to True.
refreshStatus (bool, optional) – If True, the gripper status is refreshed before sending the command. The status information is used to determine if the gripper is already activated. Setting this parameter to False can make the command process faster if the gripper status is up to date. Defaults to False.
- RobotiqGripper.move_mm(positionmm, speed=255, force=255, wait=True, readStatus=True, refreshStatus=False)[source]
Move the gripper to the requested opening in millimeters.
- Parameters:
positionmm (float) – Target gripper opening in millimeters.
speed (int, optional) – Gripper speed between 0 and 255. Defaults to 255.
force (int, optional) – Gripper force between 0 and 255. Defaults to 255.
wait (bool, optional) – If True, the function waits until the gripper reaches the requested position or detects an object. Defaults to True.
readStatus (bool, optional) – If True, the gripper status is read after sending the command. Defaults to True.
refreshStatus (bool, optional) – If True, the gripper status is refreshed before sending the command. The status information is used to determine if the gripper is already activated. Setting this parameter to False can make the command process faster if the gripper status is up to date. Defaults to False.
Note
Millimeter calibration is required to use this function. Execute the function calibrate_mm() before using this function.
- RobotiqGripper.realTimeMove(requestedPosition, minSpeedPosDelta=5, maxSpeedPosDelta=100, continuousGrip=True, autoLock=True, minimalMotion=2, verbose=False, objectDetectionDuration=0.5)[source]
Move the gripper in real time to the requested position.
- Parameters:
requestedPosition (int) – Target position for the gripper in bits. Must be between 0 and 255, where 0 represents fully open and 255 represents fully closed.
minSpeedPosDelta (int, optional) – Minimum position delta to apply the minimum speed. Defaults to 5.
maxSpeedPosDelta (int, optional) – Position delta above which the maximum speed is applied. Defaults to 100.
continuousGrip (bool, optional) – If True, the gripper continuously tries to close on the object even after detection (force > 0). Defaults to True.
autoLock (bool, optional) – If True, the gripper automatically performs a full-speed, full-force grip after object detection. Defaults to True.
minimalMotion (int, optional) – Minimum motion in bits to perform when a motion is requested. If the position delta between the current and requested position is below this value, no motion is performed. Defaults to 2.
verbose (int, optional) – Verbose level for printing. 1 prints all executed commands; 2 prints all commands. Defaults to 0.
Examples
Make a loop to control the gripper using a joystick with pygame
>>> import pygame >>> import time >>> import pyrobotiqgripper as rq >>> grip = rq.RobotiqGripper() >>> pygame.init() >>> pygame.joystick.init() >>> js = pygame.joystick.Joystick(0) >>> js.init() >>> while True: >>> pygame.event.pump() >>> requested_pos=int((js.get_axis(0) + 1) * 255 / 2) >>> grip.realtimemove(requested_pos)
Status
- RobotiqGripper.isActivated(refreshStatus=True)[source]
Check whether the gripper is activated.
- Parameters:
refreshStatus (bool, optional) – Whether to refresh the gripper status before checking the activation state. The status information is used to determine if the gripper is already activated. Setting this parameter to False can make the check faster if the gripper status is up to date. Defaults to True.
- Returns:
True if the gripper is activated, False otherwise.
- Return type:
bool
- RobotiqGripper.isStarted(refreshStatus=True)[source]
Check whether the gripper is started.
- Returns:
True if the gripper is started, False otherwise.
- Return type:
bool
- RobotiqGripper.is_bit_calibrated()[source]
Check whether the gripper is bit calibrated.
- Returns:
True if the gripper is bit calibrated, False otherwise.
- Return type:
bool
- RobotiqGripper.is_mm_calibrated()[source]
Check whether the gripper millimeter (mm) calibration is done.
- Returns:
True if the gripper is mm calibrated, False otherwise.
- Return type:
bool
- RobotiqGripper.is_speed_calibrated()[source]
Check whether the gripper speed calibration is done.
- Returns:
True if the gripper speed is calibrated, False otherwise.
- Return type:
bool
- RobotiqGripper.gripper_vmax_bits()[source]
Return the maximum gripper speed in bits per second.
- Returns:
Maximum gripper speed in bits per second.
- Return type:
int
- RobotiqGripper.gripper_vmin_bits()[source]
Return the minimum gripper speed in bits per second.
- Returns:
Minimum gripper speed in bits per second.
- Return type:
int
- RobotiqGripper.positionCommand()[source]
Return the last commanded position value.
- Returns:
The last position command value (0-255), or None if the history is empty.
- Return type:
int | None
- RobotiqGripper.position(refreshStatus=True)[source]
Return the current position of the gripper in bits.
- Parameters:
refreshStatus (bool, optional) – Whether to refresh the gripper status before getting the position. The status information is used to determine the current position. Setting this parameter to False can make the retrieval faster if the gripper status is already up to date. Defaults to True.
- Returns:
Current gripper position in bits (0-255), or None if history is empty.
- Return type:
int | None
- RobotiqGripper.position_mm(refreshStatus=True)[source]
Return the current position of the gripper in millimeters.
- Parameters:
refreshStatus (bool, optional) – Whether to refresh the gripper status before getting the position. The status information is used to determine the current position. Setting this parameter to False can make the retrieval faster if the gripper status is already up to date. Defaults to True.
- Returns:
Current gripper position in millimeters.
- Return type:
float
Note
Calibration is required to use this function. Execute the calibration function at least once before using this function.
- RobotiqGripper.speed()[source]
Return the last set speed value.
Returns:
- int or None
The last speed value set (0-255), or None if history is empty.
- RobotiqGripper.force()[source]
Return the last set force value.
- Returns:
The last force value set (0-255), or None if the history is empty.
- Return type:
int | None
- RobotiqGripper.objectDetection(mergedHistory=None, duration=0.5, tolerance=3, refreshStatus=True, verbose=0)[source]
Estimate object detection status from history data.
- Parameters:
mergedHistory (numpy.ndarray, optional) – Pre-merged history array. If None, history is merged from status and command history. Passing a pre-merged history can speed up the estimation if this function is called multiple times in a loop. Defaults to None.
duration (float, optional) – Stability duration threshold. Object detection is considered valid only if the position is stable for longer than this duration. Defaults to 0.2.
tolerance (int, optional) – Position tolerance. The gripper is considered to be at the expected position if the difference between expected and actual position is less than this tolerance. Defaults to 3.
refreshStatus (bool, optional) – Whether to refresh the gripper status to get the object detection status from the gripper. Defaults to True.
- Returns:
Object detection status code.
- Return type:
int
- RobotiqGripper.readStatus()[source]
Retrieve gripper output register information and save it in the status history.
- RobotiqGripper.status(refreshStatus=True)[source]
Return the current gripper status as a dictionary.
- Parameters:
refreshStatus (bool, optional) – Whether to read fresh status from the gripper. Defaults to True.
- Returns:
A dictionary containing current status values for all registers.
- Return type:
dict
- RobotiqGripper.printStatus(refreshStatus=True)[source]
Print gripper status info in the Python terminal.
- Parameters:
refreshStatus (bool, optional) – Whether to read fresh status from the gripper before printing. Defaults to False. If you are sure that the status information is up to date, setting this parameter to False can make the printing faster.
Examples
>>> grip.move(100) >>> grip.print_status()
Output:
====================================================================== GRIPPER STATUS ====================================================================== gOBJ : 3 └─ Fingers are at requested position. No object detected or object has been lost / dropped. gSTA : 3 └─ Activation is completed. gGTO : 1 └─ Go to Position Request. gACT : 1 └─ Gripper activation. kFLT : 0 └─ 0 gFLT : 9 └─ Minor faults (LED continuous red). No communication during at least 1 second. gPR : 100 └─ Echo of the requested position for the Gripper: 100/255 gPO : 100 └─ Actual position of the Gripper obtained via the encoders: 100/255 gCU : 0 └─ The current is read instantaneously from the motor drive, approximate current: 0 mA ======================================================================
- RobotiqGripper.commandHistory()[source]
Return the gripper command history as a pandas DataFrame.
- Returns:
- A DataFrame containing the command history with columns for
time and various command registers (rARD, rATR, etc.).
- Return type:
pd.DataFrame
- RobotiqGripper.statusHistory()[source]
Return the gripper status history as a pandas DataFrame.
- Returns:
- A DataFrame containing the status history with columns for
time and various status registers (gOBJ, gSTA, etc.).
- Return type:
pd.DataFrame
- RobotiqGripper.history()[source]
Return the merged command and status history as a pandas DataFrame.
This method combines the command history and status history into a single DataFrame with all timestamps aligned.
- Returns:
- A DataFrame containing the merged history with columns for
time, commands, and status values.
- Return type:
pd.DataFrame
Constants
- BAUDRATE
Default baudrate of the gripper use by Robotiq gripper.
- BYTESIZE
Byte size use by Robotiq gripper
- PARITY
Parity use by Robotiq gripper
- STOPBITS
Stop bits used by Robotiq gripper
- TIMEOUT
Default timeout use for communication with Robotiq gripper
- AUTO_DETECTION
Automatically detect the USB port on which the gripper connected.
- GRIPPER_MODE_RTU_VIA_TCP
Set communication to be RTU via TCP
- GRIPPER_MODE_RTU
Set communication to be RTU
- REGISTER_DIC
Dictionary containing all input and output registers for the Robotiq gripper.
Each top-level key represents a register group:
Input registers (g / k prefix): - gOBJ : Object detection status
0: Fingers in motion, no object detected
1: Fingers stopped while opening, object detected
2: Fingers stopped while closing, object detected
3: Fingers at requested position, no object detected or lost/dropped
- gSTAGripper status
0: Reset / automatic release
1: Activation in progress
3: Activation completed
- gGTOGo-to status
0: Stopped / performing activation or release
1: Go to position requested
- gACTActivation status
0: Gripper reset
1: Gripper activation
kFLT : Controller fault codes (0–255)
gFLT : Gripper fault codes (0–255, specific faults for indices 0, 5, 7–15)
gPR : Echo of requested positions (0–255)
gPO : Actual positions read from encoders (0–255)
gCU : Instantaneous current from motor drive (0–255, in mA)
Output registers (r prefix): - rARD : Automatic release status
0: Closing auto-release
1: Opening auto-release
- rATRAutomatic release type
0: Normal
1: Emergency auto-release
- rGTOGo-to command status
0: Stop
1: Go to requested position
- rACTActivation command
0: Deactivate gripper
1: Activate gripper (must stay on until routine completes)
rPR : Target positions for gripper fingers (0–255)
rSP : Speed of gripper movement (0–255)
rFR : Final gripping force (0–255)
This dictionary is mapping integer codes to human-readable descriptions for every register.