grippers_pandapy

Franka gripper interface via panda_py.

High-level interface for controlling gripper for Franka Emika Panda / FR3 robots via panda_py.

class robotblockset.franka.grippers_pandapy.panda_gripper(robot: robot | None, name: str = 'panda_gripper', hostname: str | None = None, **kwargs: Any)[source]

Bases: gripper

PandaPy-backed interface for controlling the Franka Emika Panda gripper.

Attributes:
  • Name (str) – Identifier string for the gripper instance.

  • Robot (robot or None) – Robot instance this gripper is attached to, if available.

  • hostname (str) – Hostname or IP address of the Panda/FR3 controller used by the gripper.

Initializes the gripper object with default attributes.

Parameters:
  • robot (robot, optional) – robot, optional An instance of the robot class that the gripper is attached to.

  • name (str, optional) – Name identifier for the gripper instance (default is ‘panda_gripper’).

  • hostname (str, optional) – IP address or hostname of the Panda / FR3 robot. Has to be defined if no robot is selected.

  • **kwargs (Any) – Additional keyword arguments for future extensions or configuration.

Returns:

This constructor initializes the Panda gripper interface in place.

Return type:

None

__init__(robot: robot | None, name: str = 'panda_gripper', hostname: str | None = None, **kwargs: Any) None[source]

Initializes the gripper object with default attributes.

Parameters:
  • robot (robot, optional) – robot, optional An instance of the robot class that the gripper is attached to.

  • name (str, optional) – Name identifier for the gripper instance (default is ‘panda_gripper’).

  • hostname (str, optional) – IP address or hostname of the Panda / FR3 robot. Has to be defined if no robot is selected.

  • **kwargs (Any) – Additional keyword arguments for future extensions or configuration.

Returns:

This constructor initializes the Panda gripper interface in place.

Return type:

None

property width: float

Get the current width of the gripper.

Returns:

Current gripper width.

Return type:

float

is_grasped() bool[source]

Check if the gripper is currently grasping an object.

Returns:

True if the gripper is grasping an object, False otherwise.

Return type:

bool

GetState() str[source]

Returns the current state of the gripper.

Returns:

The state of the gripper, either “Opened”, “Closed”, or “Undefined”.

Return type:

str

Grasp(width: float, speed: float = 0.1, force: int = 5, eps: float = 0.005) bool[source]

Grasps an object with the gripper at a specified width.

Parameters:
  • width (float) – The width to which the gripper should close to grasp the object.

  • speed (float, optional) – The speed at which the gripper should move (default is 0.1).

  • force (int, optional) – The force to apply during the grasp (default is 5).

  • eps (float, optional) – The tolerance for the grasping width (default is 0.005).

Returns:

True if the gripper successfully grasps, False otherwise.

Return type:

bool

Move(width: float, speed: float = 0.1) bool[source]

Moves the gripper to a specified width. :param width: The width to which the gripper should move. :type width: float :param speed: The speed at which the gripper should move (default is 0.1). :type speed: float, optional

Returns:

True if the gripper successfully moves, False otherwise.

Return type:

bool

Homing() bool[source]

Resets the gripper to an open state.

Returns:

True if the gripper successfully homes, False otherwise.

Return type:

bool

Classes

panda_gripper(robot[, name, hostname])

PandaPy-backed interface for controlling the Franka Emika Panda gripper.