grippers_ros2
ROS 2 gripper interface implementations.
This module defines ROS 2-backed gripper wrappers used by RobotBlockSet robot interfaces.
- class robotblockset.ros2.grippers_ros2.FrankaGripper(robot: robot | None = None, namespace: str = 'franka_gripper', **kwargs: Any)[source]
Bases:
gripperROS 2 action-based interface for the Franka gripper (Panda / FR3).
Uses
franka_msgsaction servers for homing, moving, and grasping, and astd_srvs/Triggerservice for stopping.Can be used standalone (
robot=None) or attached to an existingrobotinstance.- Attributes:
Name (str) – Identifier for the gripper instance.
GripperTagNames (str) – Tag used for identifying the gripper in logs or systems.
Robot (robot or None) – The robot associated with the gripper, or
Noneif standalone.
Initialize the Franka gripper ROS 2 wrapper.
- Parameters:
robot (robot, optional) – Robot instance to which the gripper is attached. Must be an
robotsubclass instance. IfNone, a minimal internal node is created and spun in a background thread so the gripper can be used standalone.namespace (str, optional) – ROS 2 namespace the
franka_gripper_noderuns in. The node is always namedfranka_gripper, so topics resolve to/{namespace}/franka_gripper/{action}. Defaults to"franka_gripper"which matches the standard launch setup.**kwargs (Any) – Additional keyword arguments for future extensions or configuration.
- __init__(robot: robot | None = None, namespace: str = 'franka_gripper', **kwargs: Any) None[source]
Initialize the Franka gripper ROS 2 wrapper.
- Parameters:
robot (robot, optional) – Robot instance to which the gripper is attached. Must be an
robotsubclass instance. IfNone, a minimal internal node is created and spun in a background thread so the gripper can be used standalone.namespace (str, optional) – ROS 2 namespace the
franka_gripper_noderuns in. The node is always namedfranka_gripper, so topics resolve to/{namespace}/franka_gripper/{action}. Defaults to"franka_gripper"which matches the standard launch setup.**kwargs (Any) – Additional keyword arguments for future extensions or configuration.
- property width: float
Get the last known gripper width from joint-state feedback.
- Returns:
Current gripper finger width in metres.
- Return type:
float
- GetState() str[source]
Return the current state of the gripper as a human-readable string.
- Returns:
"Opened","Closed", or"Undefined".- Return type:
str
- Grasp(width: float, speed: float = 0.1, force: float = 5.0, eps: float = 0.005) bool[source]
Grasp an object with the gripper.
- Parameters:
width (float) – Target grasp width in metres.
speed (float, optional) – Closing speed in m/s (default 0.1).
force (float, optional) – Grasp force in N (default 5.0).
eps (float, optional) – Inner and outer epsilon tolerance in metres (default 0.005).
- Returns:
Trueif the grasp was reported as successful,Falseotherwise.- Return type:
bool
- Move(width: float, speed: float = 0.1) bool[source]
Move the gripper to a specified width.
- Parameters:
width (float) – Target width in metres.
speed (float, optional) – Desired speed in m/s (default 0.1).
- Returns:
Trueif the move was reported as successful,Falseotherwise.- Return type:
bool
- Homing() bool[source]
Home the gripper and open it fully.
- Returns:
Trueif homing was reported as successful,Falseotherwise.- Return type:
bool
- Stop(timeout_sec: float = 1.0) bool | None[source]
Stop any ongoing gripper action.
- Parameters:
timeout_sec (float, optional) – Timeout in seconds for the service call (default 1.0).
- Returns:
Trueif the stop service call succeeded,Noneif it was unavailable or timed out.- Return type:
bool or None
Classes
|
ROS 2 action-based interface for the Franka gripper (Panda / FR3). |