Gripper#
Interface for controlling the Franka Hand gripper.
Gripper Class#
- class pylibfranka.Gripper#
Bases:
pybind11_objectInterface for controlling a Franka Hand gripper.
- grasp(self: pylibfranka._pylibfranka.Gripper, width: float, speed: float, force: float, epsilon_inner: float = 0.005, epsilon_outer: float = 0.005) bool#
Grasp an object.
The gripper closes at the specified speed and force until an object is detected or the target width is reached. The grasp is considered successful if the final width is within the specified tolerances.
@param width Target grasp width [m] @param speed Closing speed [m/s] @param force Grasping force [N] @param epsilon_inner Inner tolerance for grasp check [m] (default: 0.005) @param epsilon_outer Outer tolerance for grasp check [m] (default: 0.005) @return True if grasp successful :raises CommandException: if the command fails :raises NetworkException: if the connection is lost
- homing(self: pylibfranka._pylibfranka.Gripper) bool#
Perform homing to find maximum width.
Homing moves the gripper fingers to the maximum width to calibrate the position. This should be performed after powering on the gripper or when the gripper state is uncertain.
@return True if successful :raises CommandException: if the command fails :raises NetworkException: if the connection is lost
- move(self: pylibfranka._pylibfranka.Gripper, arg0: float, arg1: float) bool#
Move gripper fingers to a specific width.
Moves the gripper to the specified width at the given speed. Use this for opening and closing the gripper without force control.
@param width Target width [m] @param speed Movement speed [m/s] @return True if successful :raises CommandException: if the command fails :raises NetworkException: if the connection is lost
- read_once(self: pylibfranka._pylibfranka.Gripper) pylibfranka._pylibfranka.GripperState#
Read current gripper state once.
Queries the gripper for its current state including width, temperature, and grasp status.
@return Current gripper state :raises NetworkException: if the connection is lost
- server_version(self: pylibfranka._pylibfranka.Gripper) int#
Get gripper server version.
@return Server version information
- stop(self: pylibfranka._pylibfranka.Gripper) bool#
Stop current gripper motion.
Stops any ongoing gripper movement immediately.
@return True if successful :raises CommandException: if the command fails :raises NetworkException: if the connection is lost
The Gripper class provides control of the Franka Hand parallel-jaw gripper.
Methods#
- Gripper.__init__(self: pylibfranka._pylibfranka.Gripper, arg0: str) None
Connect to gripper.
Establishes connection to the Franka Hand gripper at the specified address.
@param franka_address IP address or hostname of the robot :raises NetworkException: if the connection cannot be established
- Gripper.homing(self: pylibfranka._pylibfranka.Gripper) bool
Perform homing to find maximum width.
Homing moves the gripper fingers to the maximum width to calibrate the position. This should be performed after powering on the gripper or when the gripper state is uncertain.
@return True if successful :raises CommandException: if the command fails :raises NetworkException: if the connection is lost
- Gripper.move(self: pylibfranka._pylibfranka.Gripper, arg0: float, arg1: float) bool
Move gripper fingers to a specific width.
Moves the gripper to the specified width at the given speed. Use this for opening and closing the gripper without force control.
@param width Target width [m] @param speed Movement speed [m/s] @return True if successful :raises CommandException: if the command fails :raises NetworkException: if the connection is lost
- Gripper.grasp(self: pylibfranka._pylibfranka.Gripper, width: float, speed: float, force: float, epsilon_inner: float = 0.005, epsilon_outer: float = 0.005) bool
Grasp an object.
The gripper closes at the specified speed and force until an object is detected or the target width is reached. The grasp is considered successful if the final width is within the specified tolerances.
@param width Target grasp width [m] @param speed Closing speed [m/s] @param force Grasping force [N] @param epsilon_inner Inner tolerance for grasp check [m] (default: 0.005) @param epsilon_outer Outer tolerance for grasp check [m] (default: 0.005) @return True if grasp successful :raises CommandException: if the command fails :raises NetworkException: if the connection is lost
- Gripper.stop(self: pylibfranka._pylibfranka.Gripper) bool
Stop current gripper motion.
Stops any ongoing gripper movement immediately.
@return True if successful :raises CommandException: if the command fails :raises NetworkException: if the connection is lost
- Gripper.read_once(self: pylibfranka._pylibfranka.Gripper) pylibfranka._pylibfranka.GripperState
Read current gripper state once.
Queries the gripper for its current state including width, temperature, and grasp status.
@return Current gripper state :raises NetworkException: if the connection is lost
GripperState Class#
- class pylibfranka.GripperState#
Bases:
pybind11_objectCurrent state of the Franka Hand gripper.
- property is_grasped#
True if object is grasped
- property max_width#
Maximum gripper width [m]
- property temperature#
Gripper temperature [°C]
- property time#
Timestamp
- property width#
Current gripper width [m]
Current state of the Franka Hand gripper.
See Also#
Robot– Main robot control interfaceGripperState– Gripper state information