Bioscara
DALSA's DIY SCARA Robot Arm.
Loading...
Searching...
No Matches
Classes | Public Member Functions | Private Attributes | List of all members
bioscara_hardware_interfaces::BioscaraGripperHardwareInterface Class Reference

The bioscara gripper hardware interface class. More...

#include <gripper_hardware.hpp>

Inheritance diagram for bioscara_hardware_interfaces::BioscaraGripperHardwareInterface:

Classes

struct  gripper_config_t
 configuration structure holding the passed paramters from the ros2_control urdf More...
 

Public Member Functions

hardware_interface::CallbackReturn on_init (const hardware_interface::HardwareComponentInterfaceParams &params) override
 
hardware_interface::CallbackReturn on_shutdown (const rclcpp_lifecycle::State &previous_state) override
 Called on the transistion from the inactive, unconfigured and active to the finalized state.
 
hardware_interface::CallbackReturn on_configure (const rclcpp_lifecycle::State &previous_state) override
 Called on the transistion from the unconfigured to the inactive state.
 
hardware_interface::CallbackReturn on_cleanup (const rclcpp_lifecycle::State &previous_state) override
 Called on the transistion from the inactive to the unconfigured state.
 
hardware_interface::CallbackReturn on_activate (const rclcpp_lifecycle::State &previous_state) override
 Called on the transistion from the inactive to the active state.
 
hardware_interface::CallbackReturn on_deactivate (const rclcpp_lifecycle::State &previous_state) override
 Called on the transistion from the active to the inactive state.
 
hardware_interface::return_type read (const rclcpp::Time &time, const rclcpp::Duration &period) override
 Reads from the hardware and populates the state interfaces.
 
hardware_interface::return_type write (const rclcpp::Time &time, const rclcpp::Duration &period) override
 Writes commands to the hardware from the command interfaces.
 
hardware_interface::CallbackReturn on_error (const rclcpp_lifecycle::State &previous_state) override
 Called when an error in any state or state transition is thrown.
 

Private Attributes

std::unique_ptr< bioscara_hardware_drivers::BaseGripper_gripper
 Smart pointer to the local BaseGripper.
 
gripper_config_t _gripper_cfg
 configuration struct of the gripper.
 
float _last_pos = std::numeric_limits<double>::quiet_NaN()
 
float _vel = std::numeric_limits<double>::quiet_NaN()
 

Detailed Description

The bioscara gripper hardware interface class.

System interface has been chosen to allow future modifications for grippers that provide feedback. refer to the BioscaraArmHardwareInterface class for a more detailed description of the hardware life-cycle.

Member Function Documentation

◆ on_activate()

hardware_interface::CallbackReturn bioscara_hardware_interfaces::BioscaraGripperHardwareInterface::on_activate ( const rclcpp_lifecycle::State &  previous_state)
override

Called on the transistion from the inactive to the active state.

Enables PWM generation.

Parameters
previous_state
Returns
hardware_interface::CallbackReturn

◆ on_cleanup()

hardware_interface::CallbackReturn bioscara_hardware_interfaces::BioscaraGripperHardwareInterface::on_cleanup ( const rclcpp_lifecycle::State &  previous_state)
override

Called on the transistion from the inactive to the unconfigured state.

Parameters
previous_state
Returns
hardware_interface::CallbackReturn

◆ on_configure()

hardware_interface::CallbackReturn bioscara_hardware_interfaces::BioscaraGripperHardwareInterface::on_configure ( const rclcpp_lifecycle::State &  previous_state)
override

Called on the transistion from the unconfigured to the inactive state.

Parameters
previous_state
Returns
hardware_interface::CallbackReturn

◆ on_deactivate()

hardware_interface::CallbackReturn bioscara_hardware_interfaces::BioscaraGripperHardwareInterface::on_deactivate ( const rclcpp_lifecycle::State &  previous_state)
override

Called on the transistion from the active to the inactive state.

Disables PWM generation.

Parameters
previous_state
Returns
hardware_interface::CallbackReturn

◆ on_error()

hardware_interface::CallbackReturn bioscara_hardware_interfaces::BioscaraGripperHardwareInterface::on_error ( const rclcpp_lifecycle::State &  previous_state)
override

Called when an error in any state or state transition is thrown.

According to the ros2_control documentation:

‍Error handling follows the node lifecycle. If successful CallbackReturn::SUCCESS is returned and hardware is again in UNCONFIGURED state, if any ERROR or FAILURE happens the hardware ends in FINALIZED state and can not be recovered. The only option is to reload the complete plugin, but there is currently no service for this in the Controller Manager.

Since the hardware will immediatly return to the unconfigured state (source) if the error could be handled we manually call the transition functions which would normally be called to this state. Those are:

  • Previous state: active
  • Previous state: inactive
    • Deactivate hardware (on_deactivate()) -> inactive
      • call the deactivate function anyway regardless if state was active or inactive.
    • Clean-Up hardware (on_cleanup()) -> unconfigured
Parameters
previous_state
Returns
hardware_interface::CallbackReturn

◆ on_init()

hardware_interface::CallbackReturn bioscara_hardware_interfaces::BioscaraGripperHardwareInterface::on_init ( const hardware_interface::HardwareComponentInterfaceParams &  params)
override

check that only one joint is defined, more mimic joints may be defined.

◆ on_shutdown()

hardware_interface::CallbackReturn bioscara_hardware_interfaces::BioscaraGripperHardwareInterface::on_shutdown ( const rclcpp_lifecycle::State &  previous_state)
override

Called on the transistion from the inactive, unconfigured and active to the finalized state.

When transitioning directly from active to finalized on_deactivate() is automatically called before Source Code If the previous state is either inactive or active the on_cleanup() method is called first.

Parameters
previous_state
Returns
hardware_interface::CallbackReturn

◆ read()

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

Reads from the hardware and populates the state interfaces.

Invokes the bioscara_hardware_drivers::Gripper::getPosition() method to read the gripper position.

Parameters
time
period
Returns
hardware_interface::return_type

◆ write()

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

Writes commands to the hardware from the command interfaces.

Invokes the bioscara_hardware_drivers::Gripper::setPosition() method to write the command to the gripper.

Parameters
time
period
Returns
hardware_interface::return_type

Member Data Documentation

◆ _gripper

std::unique_ptr<bioscara_hardware_drivers::BaseGripper> bioscara_hardware_interfaces::BioscaraGripperHardwareInterface::_gripper
private

Smart pointer to the local BaseGripper.

This will be used to either interact with the hardware or mock hardware. A smart pointer is used to guarantee destruction when the pointer is destructed. A unique pointer is used to prevent copying of the object.

◆ _gripper_cfg

gripper_config_t bioscara_hardware_interfaces::BioscaraGripperHardwareInterface::_gripper_cfg
private

configuration struct of the gripper.

◆ _last_pos

float bioscara_hardware_interfaces::BioscaraGripperHardwareInterface::_last_pos = std::numeric_limits<double>::quiet_NaN()
private

◆ _vel

float bioscara_hardware_interfaces::BioscaraGripperHardwareInterface::_vel = std::numeric_limits<double>::quiet_NaN()
private

The documentation for this class was generated from the following files: