ros2_control - galactic
Public Member Functions | Protected Attributes | List of all members
hardware_interface::SensorInterface Class Referenceabstract

Virtual Class to implement when integrating a stand-alone sensor into ros2_control. More...

#include <sensor_interface.hpp>

Inheritance diagram for hardware_interface::SensorInterface:
Inheritance graph
[legend]
Collaboration diagram for hardware_interface::SensorInterface:
Collaboration graph
[legend]

Public Member Functions

 SensorInterface (const SensorInterface &other)=delete
 SensorInterface copy constructor is actively deleted. More...
 
 SensorInterface (SensorInterface &&other)=default
 
virtual CallbackReturn on_init (const HardwareInfo &hardware_info)
 Initialization of the hardware interface from data parsed from the robot's URDF. More...
 
virtual std::vector< StateInterfaceexport_state_interfaces ()=0
 Exports all state interfaces for this hardware interface. More...
 
virtual return_type read ()=0
 Read the current state values from the actuator. More...
 
virtual std::string get_name () const
 Get name of the actuator hardware. More...
 
const rclcpp_lifecycle::State & get_state () const
 Get life-cycle state of the actuator hardware. More...
 
void set_state (const rclcpp_lifecycle::State &new_state)
 Set life-cycle state of the actuator hardware. More...
 

Protected Attributes

HardwareInfo info_
 
rclcpp_lifecycle::State lifecycle_state_
 

Detailed Description

Virtual Class to implement when integrating a stand-alone sensor into ros2_control.

The typical examples are Force-Torque Sensor (FTS), Interial Measurement Unit (IMU).

Methods return values have type rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn with the following meaning:

Returns
CallbackReturn::SUCCESS method execution was successful.
CallbackReturn::FAILURE method execution has failed and and can be called again.
CallbackReturn::ERROR critical error has happened that should be managed in "on_error" method.

The hardware ends after each method in a state with the following meaning:

UNCONFIGURED (on_init, on_cleanup): Hardware is initialized but communication is not started and therefore no interface is available.

INACTIVE (on_configure, on_deactivate): Communication with the hardware is started and it is configured. States can be read and non-movement hardware interfaces commanded. Hardware interfaces for movement will NOT be available. Those interfaces are: HW_IF_POSITION, HW_IF_VELOCITY, HW_IF_ACCELERATION, and HW_IF_EFFORT.

FINALIZED (on_shutdown): Hardware interface is ready for unloading/destruction. Allocated memory is cleaned up.

ACTIVE (on_activate): Power circuits of hardware are active and hardware can be moved, e.g., brakes are disabled. Command interfaces for movement are available and have to be accepted. Those interfaces are: HW_IF_POSITION, HW_IF_VELOCITY, HW_IF_ACCELERATION, and HW_IF_EFFORT.

Constructor & Destructor Documentation

◆ SensorInterface()

hardware_interface::SensorInterface::SensorInterface ( const SensorInterface other)
delete

SensorInterface copy constructor is actively deleted.

Hardware interfaces are having a unique ownership and thus can't be copied in order to avoid failed or simultaneous access to hardware.

Member Function Documentation

◆ export_state_interfaces()

virtual std::vector<StateInterface> hardware_interface::SensorInterface::export_state_interfaces ( )
pure virtual

Exports all state interfaces for this hardware interface.

The state interfaces have to be created and transferred according to the hardware info passed in for the configuration.

Note the ownership over the state interfaces is transferred to the caller.

Returns
vector of state interfaces

Implemented in ros2_control_demo_hardware::ExternalRRBotForceTorqueSensorHardware.

◆ get_name()

virtual std::string hardware_interface::SensorInterface::get_name ( ) const
inlinevirtual

Get name of the actuator hardware.

Returns
name.

◆ get_state()

const rclcpp_lifecycle::State& hardware_interface::SensorInterface::get_state ( ) const
inline

Get life-cycle state of the actuator hardware.

Returns
state.

◆ on_init()

virtual CallbackReturn hardware_interface::SensorInterface::on_init ( const HardwareInfo hardware_info)
inlinevirtual

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

Parameters
[in]hardware_infostructure with data from URDF.
Returns
CallbackReturn::SUCCESS if required data are provided and can be parsed.
CallbackReturn::ERROR if any error happens or data are missing.

Reimplemented in ros2_control_demo_hardware::ExternalRRBotForceTorqueSensorHardware.

◆ read()

virtual return_type hardware_interface::SensorInterface::read ( )
pure virtual

Read the current state values from the actuator.

The data readings from the physical hardware has to be updated and reflected accordingly in the exported state interfaces. That is, the data pointed by the interfaces shall be updated.

Returns
return_type::OK if the read was successful, return_type::ERROR otherwise.

Implemented in ros2_control_demo_hardware::ExternalRRBotForceTorqueSensorHardware.

◆ set_state()

void hardware_interface::SensorInterface::set_state ( const rclcpp_lifecycle::State &  new_state)
inline

Set life-cycle state of the actuator hardware.

Returns
state.

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