Class GripperExampleController
Defined in File gripper_example_controller.hpp
Inheritance Relationships
Base Type
public controller_interface::ControllerInterface
Class Documentation
-
class GripperExampleController : public controller_interface::ControllerInterface
The Gripper Example Controller
Assumptions:
The Franka Hand (“Gripper”) is correctly attached to the Franka FR3 Robotic Arm.
The Robotic Arm is powered on, unlocked, and in FCI (Franka Control Interface) mode.
The Arm is positioned and ready to test only the Gripper functionality, with no movement of other joints involved.
Purpose: This controller demonstrates the Franka action interface for controlling the gripper. It uses two hard-coded goals:
Grasp Goal (see: GripperExampleController::graspGripper()):
Target width: 0.015 meters (e.g., to grasp a “Magic Marker”).
Tolerances:
epsilon.inner: 0.005 meters (inner tolerance for success).
epsilon.outer: 0.010 meters (outer tolerance for success).
Grasping force: 100.0 N (a very firm grip).
Move Goal (see: GripperExampleController::openGripper()):
Opens the gripper to a width of 0.080 meters.
Object Size Examples:
Magic Marker: 15 mm diameter - Within tolerance: success.
Bic Pen: ~8 mm diameter - Below tolerance: fail.
Mini Flashlight: ~30 mm diameter - Exceeds tolerance: fail.
No Object: ~0 mm (fingers touch) - Below tolerance: fail.
Behavior: The controller repeatedly opens and closes the gripper and evaluates whether the grasp is successful or failed based on the object’s size and the defined tolerances.
Public Functions
-
controller_interface::InterfaceConfiguration command_interface_configuration() const override
-
controller_interface::InterfaceConfiguration state_interface_configuration() const override
-
CallbackReturn on_init() override
-
CallbackReturn on_configure(const rclcpp_lifecycle::State &previous_state) override
-
CallbackReturn on_activate(const rclcpp_lifecycle::State &previous_state) override
-
CallbackReturn on_deactivate(const rclcpp_lifecycle::State &previous_state) override
-
controller_interface::return_type update(const rclcpp::Time &time, const rclcpp::Duration &period) override