API Reference

Core Class

class pyrobotiqgripper.RobotiqGripper(com_port='auto', device_id=9, gripper_type='2F', connection_type='RTU', tcp_host='127.0.0.1', tcp_port=54321, debug=False, **kwargs)[source]

Bases: object

Class use to control Robotiq grippers (2F85, 2F140 or hande).

This class provides methods to initialize, open, close, and monitor the gripper.

Parameters:
  • com_port (str)

  • device_id (int)

  • gripper_type (str)

  • connection_type (str)

  • tcp_host (str)

  • tcp_port (int)

  • debug (bool)

com_port

COM port to which the gripper is connected. If 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.

Type:

str

device_id

Address of the gripper (integer) usually 9.

Type:

int

gripper_type

Type of the gripper. Currently only “2F” is supported. Default is “

Type:

str

connection_type

Type of connection to the gripper. GRIPPER_MODE_RTU for direct Modbus RTU connection (e.g. via USB/RS485 adapter). GRIPPER_MODE_RTU_VIA_TCP for Modbus RTU connection via TCP (e.g. when using the UR RS485 URCAP). Default is GRIPPER_MODE_RTU.

Type:

str

tcp_host

Host IP address for TCP connection. Default is “127.0.0.1”.

Type:

str

tcp_port

Port for TCP connection. Default is 54321.

Type:

int

debug

If True, enable debug logging for Modbus communication. Default is False.

Type:

bool

Examples

Gripper connected at PC USB port:
>>> gripper = RobotiqGripper()
>>> gripper.connect()
>>> gripper.resetActivate()
>>> gripper.open()
>>> gripper.close()
>>> gripper.move(100) #Move at position 100 in bit
>>> print(gripper.position) #Print gripper position in bit
>>> gripper.calibrate(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:
>>> gripper = RobotiqGripper(connection_type=GRIPPER_MODE_RTU_VIA_TCP,tcp_host="192.168.1.100")
>>> gripper.connect()
>>> gripper.resetActivate()
>>> gripper.open()

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, gripper_type='2F', 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_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. GRIPPER_MODE_RTU for direct Modbus RTU connection (e.g. via USB/RS485 adapter). GRIPPER_MODE_RTU_VIA_TCP for Modbus RTU connection via TCP (e.g. when using the UR RS485 URCAP). Default is GRIPPER_MODE_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:
>>> gripper = RobotiqGripper()
>>> gripper.connect()
>>> gripper.resetActivate()
>>> gripper.open()
>>> gripper.close()
>>> gripper.move(100) #Move at position 100 in bit
>>> print(gripper.position) #Print gripper position in bit
>>> gripper.calibrate(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:
>>> gripper = RobotiqGripper(connection_type=GRIPPER_MODE_RTU_VIA_TCP,tcp_host="192.168.1.100")
>>> gripper.connect()
>>> gripper.resetActivate()
>>> gripper.open()
Parameters:
  • com_port (str)

  • device_id (int)

  • gripper_type (str)

  • connection_type (str)

  • tcp_host (str)

  • tcp_port (int)

  • debug (bool)

connect()[source]

Connect to the gripper. If the connection is already established, do nothing.

disconnect()[source]

Disconnect from the gripper. If the connection is already closed, do nothing.

realTimeMove(requestedPosition, minSpeedPosDelta=5, maxSpeedPosDelta=100, continuousGrip=True, autoLock=True, minimalMotion=2)[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.

readStatus()[source]

Retrieve gripper output register information and save it in the parameter dictionary.

reset()[source]

Reset the gripper (clear previous activation if any)

activate()[source]

If not already activated, activate the gripper. Goto bit is set to 1 which means that once activated the gripper will move the the finger position saved in its position register.

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.

resetActivate()[source]

Reset the gripper (clear previous activation if any) and activat the gripper. During this operation the gripper will open and close.

move(position, speed=None, force=None, wait=False, readStatus=True)[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 False.

close(speed=255, force=255, wait=False, readStatus=True)[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.

open(speed=255, force=255, wait=False, readStatus=True)[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.

move_mm(positionmm, speed=None, force=None, wait=False, readStatus=True)[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.

Note

Calibration is needed to use this function.

Execute the function calibrate at least 1 time before using this function.

getPosition()[source]

Return the position of the gripper in bits

Returns:

positionint

Position of the gripper in bits.

getPositionmm()[source]

Return the position of the gripper in mm.

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.

calibrate(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.

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.

printStatus()[source]

Print gripper status info in the python terminal

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

======================================================================
isActivated()[source]

Tells if the gripper is activated

Returns:

is_activatedbool

True if the gripper is activated. False otherwise.

isCalibrated()[source]

Return if the gripper is qualibrated

Returns:

is_calibratedbool

True if the gripper is calibrated. False otherwise.

waitComplete()[source]

Wait until the gripper has completed its motion or detect an object.

Constants

Constants for pyRobotiqGripper package.

This module contains all configuration constants used throughout the package, including communication parameters, gripper limits, and status codes.

Exceptions

Custom exceptions for pyRobotiqGripper package.

exception pyrobotiqgripper.exceptions.RobotiqGripperError[source]

Bases: Exception

Base exception for all pyRobotiqGripper errors.

exception pyrobotiqgripper.exceptions.GripperConnectionError[source]

Bases: RobotiqGripperError

Raised when connection to gripper fails or is lost.

exception pyrobotiqgripper.exceptions.GripperNotActivatedError[source]

Bases: RobotiqGripperError

Raised when an action is requested but gripper is not activated.

__init__()[source]
exception pyrobotiqgripper.exceptions.GripperNotCalibratedError[source]

Bases: RobotiqGripperError

Raised when mm-based operations are used without calibration.

__init__()[source]
exception pyrobotiqgripper.exceptions.GripperTimeoutError(operation='Operation', timeout=10)[source]

Bases: RobotiqGripperError

Raised when gripper operation exceeds timeout.

Parameters:
  • operation (str)

  • timeout (float)

__init__(operation='Operation', timeout=10)[source]
Parameters:
  • operation (str)

  • timeout (float)

exception pyrobotiqgripper.exceptions.GripperPositionError(position, min_val=0, max_val=255)[source]

Bases: RobotiqGripperError

Raised when an invalid position is requested.

Parameters:
  • position (int)

  • min_val (int)

  • max_val (int)

__init__(position, min_val=0, max_val=255)[source]
Parameters:
  • position (int)

  • min_val (int)

  • max_val (int)

exception pyrobotiqgripper.exceptions.GripperCalibrationError[source]

Bases: RobotiqGripperError

Raised when calibration data is invalid.

exception pyrobotiqgripper.exceptions.GripperCommunicationError[source]

Bases: RobotiqGripperError

Raised when Modbus communication fails.

exception pyrobotiqgripper.exceptions.UnsupportedGripperTypeError(gripper_type)[source]

Bases: RobotiqGripperError

Raised when an unsupported gripper type is specified.

Parameters:

gripper_type (str)

__init__(gripper_type)[source]
Parameters:

gripper_type (str)

Utilities

Utility functions for pyRobotiqGripper package.

This module provides helper functions for common operations used by the gripper control system, including list manipulation and mathematical utilities.

pyrobotiqgripper.utils.modbus_probe_with_timeout(port, device_id, timeout=1.0)[source]
pyrobotiqgripper.utils.sign(value)[source]

Return the sign of a value

Parameters:

value (-) – Value for which the sign have to be evaluated.

Returns:

Sign of the value. 1 if positif. -1 if negative.

Return type:

  • valueSign

pyrobotiqgripper.utils.listIdValueUnderThreshold(lst, threshold)[source]

Return the list id of the first value under a given threshold.

Parameters:
  • lst (-) – list of values

  • threshold (-) – Threshold under which should be the serached value

Returns:

List id of the first value under a given threshold

Return type:

  • lstIf (int)

pyrobotiqgripper.utils.listSubstract(lst, value)[source]

Substract a value to all values of a list.

Parameters:
  • lst (-) – list of values

  • value (-) – value to substract to all values of the list

pyrobotiqgripper.utils.areValueIdentical(lst)[source]

Return True if all values of the list are identical, False otherwise.

Parameters:

lst (-) – list of values

Returns:

True if all values of the list are identical, False otherwise.

Return type:

  • res (bool)

pyrobotiqgripper.utils.updateList(lst, value)[source]

Shift all values of the given list of 1 to the right and set the given value as the first value of the list

Parameters:
  • lst (-) – list to be updated

  • value (-) – value to set a the beginning of the list