ROS2 Control
Public Member Functions | List of all members
hardware_interface::SensorInterface Class Referenceabstract

#include <sensor_interface.hpp>

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

Public Member Functions

virtual return_type configure (const HardwareInfo &sensor_info)=0
 Configuration of the sensor from data parsed from the robot's URDF. More...
 
virtual std::vector< StateInterfaceexport_state_interfaces ()=0
 Exports all state interfaces for this sensor. More...
 
virtual return_type start ()=0
 Start exchange data with the hardware. More...
 
virtual return_type stop ()=0
 Stop exchange data with the hardware. More...
 
virtual std::string get_name () const =0
 Get name of the sensor hardware. More...
 
virtual status get_status () const =0
 Get current state of the sensor hardware. More...
 
virtual return_type read ()=0
 Read the current state values from the sensor. More...
 

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).

Member Function Documentation

◆ configure()

virtual return_type hardware_interface::SensorInterface::configure ( const HardwareInfo sensor_info)
pure virtual

Configuration of the sensor from data parsed from the robot's URDF.

Parameters
[in]sensor_infostructure with data from URDF.
Returns
return_type::OK if required data are provided and can be parsed, return_type::ERROR otherwise.

◆ export_state_interfaces()

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

Exports all state interfaces for this sensor.

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

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

Returns
std::vector<StateInterface> vector of state interfaces

◆ get_name()

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

Get name of the sensor hardware.

Returns
name.

◆ get_status()

virtual status hardware_interface::SensorInterface::get_status ( ) const
pure virtual

Get current state of the sensor hardware.

Returns
current status.

◆ read()

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

Read the current state values from the sensor.

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.

◆ start()

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

Start exchange data with the hardware.

Returns
return_type:OK if everything worked as expected, return_type::ERROR otherwise.

◆ stop()

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

Stop exchange data with the hardware.

Returns
return_type:OK if everything worked as expected, return_type::ERROR otherwise.

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