Class RobotiqGripperHardwareInterface

Inheritance Relationships

Base Type

  • public hardware_interface::SystemInterface

Class Documentation

class RobotiqGripperHardwareInterface : public hardware_interface::SystemInterface

Public Functions

ROBOTIQ_DRIVER_PUBLIC RobotiqGripperHardwareInterface()

Default constructor.

ROBOTIQ_DRIVER_PUBLIC ~RobotiqGripperHardwareInterface()
explicit RobotiqGripperHardwareInterface(std::unique_ptr<DriverFactory> driver_factory)

Constructor with a driver factory. This method is used for testing.

Parameters:

driver_factory – The driver that interact with the hardware.

ROBOTIQ_DRIVER_PUBLIC CallbackReturn on_init (const hardware_interface::HardwareInfo &info) override

Initialization of the hardware interface from data parsed from the robot’s URDF.

Parameters:

hardware_info – Structure with data from URDF.

Returns:

CallbackReturn::SUCCESS if required data are provided and can be parsed or CallbackReturn::ERROR if any error happens or data are missing.

ROBOTIQ_DRIVER_PUBLIC CallbackReturn on_configure (const rclcpp_lifecycle::State &previous_state) override

Connect to the hardware.

Parameters:

previous_state – The previous state.

Returns:

CallbackReturn::SUCCESS if required data are provided and can be parsed or CallbackReturn::ERROR if any error happens or data are missing.

ROBOTIQ_DRIVER_PUBLIC std::vector< hardware_interface::StateInterface > export_state_interfaces () override

This method exposes position and velocity of joints for reading.

ROBOTIQ_DRIVER_PUBLIC std::vector< hardware_interface::CommandInterface > export_command_interfaces () override

This method exposes the joints targets for writing.

ROBOTIQ_DRIVER_PUBLIC CallbackReturn on_activate (const rclcpp_lifecycle::State &previous_state) override

This method is invoked when the hardware is connected.

Parameters:

previous_state – Unconfigured, Inactive, Active or Finalized.

Returns:

CallbackReturn::SUCCESS or CallbackReturn::ERROR.

ROBOTIQ_DRIVER_PUBLIC CallbackReturn on_deactivate (const rclcpp_lifecycle::State &previous_state) override

This method is invoked when the hardware is disconnected.

Parameters:

previous_state – Unconfigured, Inactive, Active or Finalized.

Returns:

CallbackReturn::SUCCESS or CallbackReturn::ERROR.

ROBOTIQ_DRIVER_PUBLIC hardware_interface::return_type read (const rclcpp::Time &time, const rclcpp::Duration &period) override

Read data from the hardware.

ROBOTIQ_DRIVER_PUBLIC hardware_interface::return_type write (const rclcpp::Time &time, const rclcpp::Duration &period) override

Write data to hardware.

Protected Functions

void background_task()

Protected Attributes

std::unique_ptr<Driver> driver_
std::unique_ptr<DriverFactory> driver_factory_
std::thread communication_thread_
std::atomic<bool> communication_thread_is_running_
double gripper_closed_pos_
double gripper_position_
double gripper_velocity_
double gripper_position_command_
std::atomic<uint8_t> write_command_
std::atomic<uint8_t> write_force_
std::atomic<uint8_t> write_speed_
std::atomic<uint8_t> gripper_current_state_
double reactivate_gripper_cmd_
std::atomic<bool> reactivate_gripper_async_cmd_
double reactivate_gripper_response_
double gripper_force_
double gripper_speed_
std::atomic<std::optional<bool>> reactivate_gripper_async_response_

Protected Static Attributes

static constexpr double NO_NEW_CMD_ = std::numeric_limits<double>::quiet_NaN()