API Reference
Core Class
- class pyrobotiqgripper.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_portstr
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_idint
Address of the gripper (integer) usually 9.
- gripper_typestr
Type of the gripper. Currently only “2F” is supported. Default is “2F”.
- connection_typestr
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_hoststr
Host IP address for TCP connection. Default is “127.0.0.1”
- tcp_portint
Port number for TCP connection. Default is 54321.
- debugbool
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)
- activate(reset=True, start=True, refreshStatus=True)[source]
If not already activated, activate the gripper.
Parameters:
- resetbool
Whether to reset the gripper before activation. Default is True.
- startbool
Whether to start the gripper motion immediately after activation (gGTO set to 1). Default is True.
- refreshStatusbool
Whether to refresh the gripper status before the activation process. Default is True. The status information is used to know is the gripper is already activated or not. Setting this parameter to False can make the activation process faster if you are sure that the gripper status is up to date.
Warning
When you execute this function the gripper is going to fully open and close. During this operation the gripper must be able to freely move. Do not place object inside the gripper.
- start(refreshStatus=True)[source]
Start the gripper motion.
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. Default is True. The status information is used to know if the gripper is already started or not. Setting this parameter to False can make the start process faster if you are sure that the gripper status is up to date.
- 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.
- calibrate_bit(openbit=None, closebit=None)[source]
Calibrate the maximum and minimum position bit value
Parameters:
- openbitint
Position value in bits when the gripper is open
- closebitint
Position value in bits when the gripper is closed
If no parametesr are provided, the gripper will make a full open followed by a full close to measure the maximum and minium position in bit.
- calibrate_speed(minSpeedClosingTime=None, maxSpeedClosingTime=None)[source]
Calibrate gripper speed to be able to estimate gripper position over time
If no parameters are provided, the gripper will do a closing at full speed and a closing at slow speed to evaluate. the bit calibration will also be performed.
Parameters :
- minSpeedClosingTimefloat
Time (s) is takes for the gripper to move from a full open position to a full close position at the minimum speed.
- maxSpeedClosingTimefloat
Time (s) is takes for the gripper to move from a full open position to a full close position at the maximum speed.
If no parameters are provided, the gripper will do a closing at full speed and a closing at slow speed to evaluate
- calibrate_mm(closemm, openmm)[source]
Calibrate the gripper for mm positionning.
Once the calibration is done it is possible to control the gripper in mm.
Parameters:
- closemmfloat
Distance between the fingers when the gripper is fully closed.
- openmmfloat
Distance between the fingers when the gripper is fully open.
Warning
Calibration in bit is required before executing this function. If the bit calibration is not done, the function calibrate_bit() will be executed before calibrating mm.
- open(speed=255, force=255, wait=True, readStatus=True, refreshStatus=False)[source]
Open the gripper
Parameters:
- speedint
Gripper speed between 0 and 255. Default is 255.
- forceint
Gripper force between 0 and 255. Default is 255.
- waitbool
If True, the function wait until the gripper reach the requested position or detect an object. Default is True.
- readStatusbool
If True, the gripper status is read after sending the command to the gripper. Default is True.
- refreshStatusbool
If True, the gripper status is refreshed before sending the command to the gripper. Default is False. The status information is used to know if the gripper is already activated or not. Setting this parameter to False can make the command process faster if you are sure that the gripper status is up to date.
- close(speed=255, force=255, wait=True, readStatus=True, refreshStatus=False)[source]
Close the gripper.
Parameters:
- speedint
Gripper speed between 0 and 255. Default is 255.
- forceint
Gripper force between 0 and 255. Default is 255.
- waitbool
If True, the function wait until the gripper reach the requested position or detect an object. Default is True.
- readStatusbool
If True, the gripper status is read after sending the command to the gripper. Default is True.
- refreshStatusbool
If True, the gripper status is refreshed before sending the command to the gripper. Default is False. The status information is used to know if the gripper is already activated or not. Setting this parameter to False can make the command process faster if you are sure that the gripper status is up to date.
- move(position, speed=255, force=255, wait=True, readStatus=True, refreshStatus=False)[source]
Move gripper fingers to the requested position with determined speed and force.
Parameters:
- positionint
Position of the gripper. Integer between 0 and 255. 0 being the open position and 255 being the close position.
- speedint
Gripper speed between 0 and 255. Default is 255.
- forceint
Gripper force between 0 and 255. Default is 255.
- waitbool
If True, the function wait until the gripper reach the requested position or detect an object. Default is True.
- readStatusbool
If True, the gripper status is read after sending the command to the gripper. Default is True.
- refreshStatusbool
If True, the gripper status is refreshed before sending the command to the gripper. Default is False. The status information is used to know if the gripper is already activated or not. Setting this parameter to False can make the command process faster if you are sure that the gripper status is up to date.
- move_mm(positionmm, speed=255, force=255, wait=True, readStatus=True, refreshStatus=False)[source]
Go to the requested opening expressed in mm
Parameters:
- positionmmfloat
Gripper opening in mm.
- speedint
Gripper speed between 0 and 255. Default is 255.
- forceint
Gripper force between 0 and 255. Default is 255.
- waitbool
If True, the function wait until the gripper reach the requested position or detect an object. Default is True.
- readStatusbool
If True, the gripper status is read after sending the command to the gripper. Default is True.
- refreshStatusbool
If True, the gripper status is refreshed before sending the command to the gripper. Default is False. The status information is used to know if the gripper is already activated or not. Setting this parameter to False can make the command process faster if you are sure that the gripper status is up to date.
Note
mm calibration is needed to use this function.
Execute the function calibrate mm before using this function.
- realTimeMove(requestedPosition, minSpeedPosDelta=5, maxSpeedPosDelta=100, continuousGrip=True, autoLock=True, minimalMotion=2, verbose=False)[source]
Move the gripper in real time to the requested position.
Parameters:
- requestedPositionint
Requested position for the gripper in bits. Integer between 0 and 255. 0 being the open position and 255 being the close position.
- minSpeedPosDeltaint
Minimum position delta to apply the minimum speed. Default is 5.
- maxSpeedPosDeltaint
Position delta over which the maximum speed is applied. Default is 100.
- continuousGripbool
If True, the gripper continuously try to close on object even after object detection (force>0). Default is True.
- autoLockbool
If True, the gripper automatically perform a full speed, full force grip after object detection. Default is True.
- minimalMotionint
Minimum motion in bit to perform when a motion is requested. If the position delta between the current position and the requested position is under this value, no motion is performed. Default is 2.
- verboseint
Verbose level to print. 1 print all executed command. 2 print all commands.
- isActivated(refreshStatus=True)[source]
Tells if the gripper is activated
Parameters:
- refreshStatusbool
Whether to refresh the gripper status before checking the activation status. Default is True. The status information is used to know if the gripper is already activated or not. Setting this parameter to False can make the activation status check faster if you are sure that the gripper status is up to date.
Returns:
- is_activatedbool
True if the gripper is activated. False otherwise.
- isStarted(refreshStatus=True)[source]
Tells if the gripper is started
Returns:
- is_startedbool
True if the gripper is started. False otherwise.
- is_bit_calibrated()[source]
Tells is the gripper is bit calibrated
Returns:
- is_bit_calibratedbool
True if the gripper is bit calibrated. False otherwise.
- is_mm_calibrated()[source]
Tells if the mm calibration is done.
Returns:
- is_mm_calibratedbool
True if the gripper mm is calibrated. False otherwise.
- is_speed_calibrated()[source]
Tells if the speed calibration is done.
Returns:
- is_speed_calibratedbool
True if the gripper speed is calibrated. False otherwise.
- gripper_vmax_bits()[source]
Return the maximum speed in bits per second
Returns: vmax_bits : int
Maximum gripper speed in bits per second.
- gripper_vmin_bits()[source]
Return the minimum speed in bits per second
Returns:
- vmin_bitsint
Minimum gripper speed in bits per second.
- positionCommand()[source]
Return the last commanded position value.
Returns:
- positionCommandint or None
The last position command value (0-255), or None if history is empty.
- position(refreshStatus=True)[source]
Return the position of the gripper in bits.
Parameters:
- refreshStatusbool
Whether to refresh the gripper status before getting the position. Default is True. The status information is used to know the current position of the gripper. Setting this parameter to False can make the position retrieval faster if you are sure that the gripper status is up to date.
Returns:
- positionint or None
Current gripper position in bits (0-255), or None if history is empty.
- positionmm(refreshStatus=True)[source]
Return the position of the gripper in mm.
Parameters:
- refreshStatusbool
Whether to refresh the gripper status before getting the position. Default is True. The status information is used to know the current position of the gripper. Setting this parameter to False can make the position retrieval faster if you are sure that the gripper status is up to date.
Returns:
- positionmmfloat
Current gripper position in mm
Note
Calibration is needed to use this function.
Execute the function calibrate at least 1 time before using this function.
- 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.
- force()[source]
Return the last set force value.
Returns:
- int or None
The last force value set (0-255), or None if history is empty.
- objectDetection(mergedHistory=None, duration=0.2, tolerance=3, refreshStatus=True)[source]
Estimate object detection status from history data.
Parameters:
- mergedHistorynumpy.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 you are calling this function multiple times in a loop. Default is None.
- durationfloat, optional
Stability duration threshold. Object detection is done only if the position is stable for more than this duration. Default is 0.2.
- toleranceint, optional
Position tolerance. The gripper is considered to be at the expected position if the difference between the expected and actual position is less than this tolerance. Default is 3.
- refreshStatusbool
Whether to refresh the gripper status to get the object detection status from the gripper.
Returns:
- object_detection_statusint
Object detection status code.
- commandHistory()[source]
Return the gripper command history as a pandas DataFrame.
Returns:
- command_historypd.DataFrame
A DataFrame containing the command history with columns for time and various command registers (rARD, rATR, etc.).
- readStatus()[source]
Retrieve gripper output register information and save it in the status history.
- status(refreshStatus=True)[source]
Return the current gripper status as a dictionary.
Parameters:
- refreshStatusbool, optional
Whether to read fresh status from the gripper. Default is True.
Returns:
- statusdict
A dictionary containing current status values for all registers.
- printStatus(refreshStatus=False)[source]
Print gripper status info in the python terminal
- Parameters:
refreshStatus (bool, optional) – Whether to read fresh status from the gripper before printing. Default is 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.printStatus()
Output:
====================================================================== GRIPPER STATUS ====================================================================== gOBJ : 3 └─ Fingers are at requested position. No object detected or object has been loss / 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 ======================================================================
- statusHistory()[source]
Return the gripper status history as a pandas DataFrame.
Returns:
- status_historypd.DataFrame
A DataFrame containing the status history with columns for time and various status registers (gOBJ, gSTA, etc.).
- 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:
- historypd.DataFrame
A DataFrame containing the merged history with columns for time, commands, and status values.
- Parameters:
com_port (str)
device_id (int)
connection_type (str)
tcp_host (str)
tcp_port (int)
debug (bool)
Constants
Constants for pyRobotiqGripper package.
This module contains all configuration constants used throughout the package, including communication parameters, gripper limits, and status codes.