ros2_control - humble
Public Member Functions | Protected Attributes | List of all members
hardware_interface::SensorInterface Class Referenceabstract
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 (const rclcpp::Time &time, const rclcpp::Duration &period)=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_
 

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_example_5::ExternalRRBotForceTorqueSensorHardware, and ros2_control_demo_example_14::RRBotSensorPositionFeedback.

◆ 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_example_5::ExternalRRBotForceTorqueSensorHardware, and ros2_control_demo_example_14::RRBotSensorPositionFeedback.

◆ read()

virtual return_type hardware_interface::SensorInterface::read ( const rclcpp::Time &  time,
const rclcpp::Duration &  period 
)
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.

Parameters
[in]timeThe time at the start of this control loop iteration
[in]periodThe measured time taken by the last control loop iteration
Returns
return_type::OK if the read was successful, return_type::ERROR otherwise.

Implemented in ros2_control_demo_example_5::ExternalRRBotForceTorqueSensorHardware, and ros2_control_demo_example_14::RRBotSensorPositionFeedback.

◆ 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: