ros2_control - jazzy
Loading...
Searching...
No Matches
Public Member Functions | Protected Attributes | List of all members
hardware_interface::HardwareComponentInterface Class Referenceabstract

Virtual base class for all hardware components (Actuators, Sensors, and Systems). More...

#include <hardware_component_interface.hpp>

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

Public Member Functions

 HardwareComponentInterface (const HardwareComponentInterface &other)=delete
 HardwareComponentInterface copy constructor is actively deleted.
 
 HardwareComponentInterface (HardwareComponentInterface &&other)=delete
 
CallbackReturn init (const HardwareInfo &hardware_info, rclcpp::Logger logger, rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock_interface)
 
CallbackReturn init (const HardwareInfo &hardware_info, rclcpp::Logger logger, rclcpp::Clock::SharedPtr clock)
 
CallbackReturn init (const hardware_interface::HardwareComponentParams &params)
 
virtual CallbackReturn on_init (const HardwareInfo &hardware_info)
 Initialization of the hardware interface from data parsed from the robot's URDF.
 
virtual CallbackReturn on_init (const hardware_interface::HardwareComponentInterfaceParams &params)
 Initialization of the hardware interface from data parsed from the robot's URDF.
 
virtual std::vector< StateInterfaceexport_state_interfaces ()
 Exports all state interfaces for this hardware interface.
 
virtual std::vector< hardware_interface::InterfaceDescriptionexport_unlisted_state_interface_descriptions ()
 
virtual std::vector< StateInterface::ConstSharedPtr > on_export_state_interfaces ()
 
virtual std::vector< CommandInterfaceexport_command_interfaces ()
 Exports all command interfaces for this hardware interface.
 
virtual std::vector< hardware_interface::InterfaceDescriptionexport_unlisted_command_interface_descriptions ()
 
virtual std::vector< CommandInterface::SharedPtr > on_export_command_interfaces ()
 
virtual return_type prepare_command_mode_switch (const std::vector< std::string > &, const std::vector< std::string > &)
 Prepare for a new command interface switch.
 
virtual return_type perform_command_mode_switch (const std::vector< std::string > &, const std::vector< std::string > &)
 
HardwareComponentCycleStatus trigger_read (const rclcpp::Time &time, const rclcpp::Duration &period)
 Triggers the read method synchronously or asynchronously depending on the HardwareInfo.
 
virtual return_type read (const rclcpp::Time &time, const rclcpp::Duration &period)=0
 Read the current state values from the hardware.
 
HardwareComponentCycleStatus trigger_write (const rclcpp::Time &time, const rclcpp::Duration &period)
 Triggers the write method synchronously or asynchronously depending on the HardwareInfo.
 
virtual return_type write (const rclcpp::Time &, const rclcpp::Duration &)
 Write the current command values to the hardware.
 
const std::string & get_name () const
 Get name of the hardware.
 
const std::string & get_group_name () const
 Get name of the hardware group to which it belongs to.
 
const rclcpp_lifecycle::State & get_lifecycle_state () const
 Get life-cycle state of the hardware.
 
void set_lifecycle_state (const rclcpp_lifecycle::State &new_state)
 Set life-cycle state of the hardware.
 
template<typename T >
void set_state (const std::string &interface_name, const T &value)
 
template<typename T = double>
get_state (const std::string &interface_name) const
 
template<typename T >
void set_command (const std::string &interface_name, const T &value)
 
template<typename T = double>
get_command (const std::string &interface_name) const
 
rclcpp::Logger get_logger () const
 Get the logger of the Interface.
 
rclcpp::Clock::SharedPtr get_clock () const
 Get the clock of the Interface.
 
rclcpp::Node::SharedPtr get_node () const
 Get the default node of the Interface.
 
const HardwareInfoget_hardware_info () const
 Get the hardware info of the Interface.
 
void prepare_for_activation ()
 Prepare for the activation of the hardware.
 
void enable_introspection (bool enable)
 Enable or disable introspection of the hardware.
 

Protected Attributes

HardwareInfo info_
 
std::unordered_map< std::string, InterfaceDescriptionjoint_state_interfaces_
 
std::unordered_map< std::string, InterfaceDescriptionjoint_command_interfaces_
 
std::unordered_map< std::string, InterfaceDescriptionsensor_state_interfaces_
 
std::unordered_map< std::string, InterfaceDescriptiongpio_state_interfaces_
 
std::unordered_map< std::string, InterfaceDescriptiongpio_command_interfaces_
 
std::unordered_map< std::string, InterfaceDescriptionunlisted_state_interfaces_
 
std::unordered_map< std::string, InterfaceDescriptionunlisted_command_interfaces_
 
rclcpp_lifecycle::State lifecycle_state_
 
std::unique_ptr< realtime_tools::AsyncFunctionHandler< return_type > > async_handler_
 
std::vector< StateInterface::SharedPtr > joint_states_
 
std::vector< CommandInterface::SharedPtr > joint_commands_
 
std::vector< StateInterface::SharedPtr > sensor_states_
 
std::vector< StateInterface::SharedPtr > gpio_states_
 
std::vector< CommandInterface::SharedPtr > gpio_commands_
 
std::vector< StateInterface::SharedPtr > unlisted_states_
 
std::vector< CommandInterface::SharedPtr > unlisted_commands_
 
pal_statistics::RegistrationsRAII stats_registrations_
 

Detailed Description

Virtual base class for all hardware components (Actuators, Sensors, and Systems).

This class provides the common structure and functionality for all hardware components, including lifecycle management, interface handling, and asynchronous support. Hardware plugins should inherit from one of its derivatives: ActuatorInterface, SensorInterface, or SystemInterface.

Constructor & Destructor Documentation

◆ HardwareComponentInterface()

hardware_interface::HardwareComponentInterface::HardwareComponentInterface ( const HardwareComponentInterface other)
delete

HardwareComponentInterface copy constructor is actively deleted.

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

Member Function Documentation

◆ enable_introspection()

void hardware_interface::HardwareComponentInterface::enable_introspection ( bool  enable)
inline

Enable or disable introspection of the hardware.

Parameters
[in]enableEnable introspection if true, disable otherwise.

◆ export_command_interfaces()

virtual std::vector< CommandInterface > hardware_interface::HardwareComponentInterface::export_command_interfaces ( )
inlinevirtual

Exports all command interfaces for this hardware interface.

Old way of exporting the CommandInterfaces. If a empty vector is returned then the on_export_command_interfaces() method is called. If a vector with CommandInterfaces is returned then the exporting of the CommandInterfaces is only done with this function and the ownership is transferred to the resource manager. The set_command(...), get_command(...), ..., can then not be used.

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

Returns
vector of state interfaces

Reimplemented in gazebo_ros2_control::GazeboSystem, gz_ros2_control::GazeboSimSystem, mock_components::GenericSystem, and joint_state_topic_hardware_interface::JointStateTopicSystem.

◆ export_state_interfaces()

virtual std::vector< StateInterface > hardware_interface::HardwareComponentInterface::export_state_interfaces ( )
inlinevirtual

Exports all state interfaces for this hardware interface.

Old way of exporting the StateInterfaces. If a empty vector is returned then the on_export_state_interfaces() method is called. If a vector with StateInterfaces is returned then the exporting of the StateInterfaces is only done with this function and the ownership is transferred to the resource manager. The set_command(...), get_command(...), ..., can then not be used.

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

Returns
vector of state interfaces

Reimplemented in gazebo_ros2_control::GazeboSystem, gz_ros2_control::GazeboSimSystem, mock_components::GenericSystem, and joint_state_topic_hardware_interface::JointStateTopicSystem.

◆ export_unlisted_command_interface_descriptions()

virtual std::vector< hardware_interface::InterfaceDescription > hardware_interface::HardwareComponentInterface::export_unlisted_command_interface_descriptions ( )
inlinevirtual

Override this method to export custom CommandInterfaces which are not defined in the URDF file. Those interfaces will be added to the unlisted_command_interfaces_ map.

Returns
vector of descriptions to the unlisted CommandInterfaces

◆ export_unlisted_state_interface_descriptions()

virtual std::vector< hardware_interface::InterfaceDescription > hardware_interface::HardwareComponentInterface::export_unlisted_state_interface_descriptions ( )
inlinevirtual

Override this method to export custom StateInterfaces which are not defined in the URDF file. Those interfaces will be added to the unlisted_state_interfaces_ map.

Returns
vector of descriptions to the unlisted StateInterfaces

◆ get_clock()

rclcpp::Clock::SharedPtr hardware_interface::HardwareComponentInterface::get_clock ( ) const
inline

Get the clock of the Interface.

Returns
clock of the Interface.

◆ get_group_name()

const std::string & hardware_interface::HardwareComponentInterface::get_group_name ( ) const
inline

Get name of the hardware group to which it belongs to.

Returns
group name.

◆ get_hardware_info()

const HardwareInfo & hardware_interface::HardwareComponentInterface::get_hardware_info ( ) const
inline

Get the hardware info of the Interface.

Returns
hardware info of the Interface.

◆ get_lifecycle_state()

const rclcpp_lifecycle::State & hardware_interface::HardwareComponentInterface::get_lifecycle_state ( ) const
inline

Get life-cycle state of the hardware.

Returns
state.

◆ get_logger()

rclcpp::Logger hardware_interface::HardwareComponentInterface::get_logger ( ) const
inline

Get the logger of the Interface.

Returns
logger of the Interface.

◆ get_name()

const std::string & hardware_interface::HardwareComponentInterface::get_name ( ) const
inline

Get name of the hardware.

Returns
name.

◆ get_node()

rclcpp::Node::SharedPtr hardware_interface::HardwareComponentInterface::get_node ( ) const
inline

Get the default node of the Interface.

Returns
node of the Interface.

◆ init() [1/3]

CallbackReturn hardware_interface::HardwareComponentInterface::init ( const hardware_interface::HardwareComponentParams params)
inline

Initialization of the hardware interface from data parsed from the robot's URDF and also the clock and logger interfaces.

Parameters
[in]paramsA struct of type HardwareComponentParams containing all necessary parameters for initializing this specific hardware component, including its HardwareInfo, a dedicated logger, a clock, and a weak_ptr to the executor.
Warning
The parsed executor should not be used to call cancel() or use blocking callbacks such as spin().
Returns
CallbackReturn::SUCCESS if required data are provided and can be parsed.
CallbackReturn::ERROR if any error happens or data are missing.

◆ init() [2/3]

CallbackReturn hardware_interface::HardwareComponentInterface::init ( const HardwareInfo hardware_info,
rclcpp::Logger  logger,
rclcpp::Clock::SharedPtr  clock 
)
inline

Initialization of the hardware interface from data parsed from the robot's URDF and also the clock and logger interfaces.

Parameters
[in]hardware_infostructure with data from URDF.
[in]clockpointer to the resource manager clock.
[in]loggerLogger for the hardware component.
Returns
CallbackReturn::SUCCESS if required data are provided and can be parsed.
CallbackReturn::ERROR if any error happens or data are missing.

◆ init() [3/3]

CallbackReturn hardware_interface::HardwareComponentInterface::init ( const HardwareInfo hardware_info,
rclcpp::Logger  logger,
rclcpp::node_interfaces::NodeClockInterface::SharedPtr  clock_interface 
)
inline

Initialization of the hardware interface from data parsed from the robot's URDF and also the clock and logger interfaces.

Parameters
[in]hardware_infostructure with data from URDF.
[in]loggerLogger for the hardware component.
[in]clock_interfacepointer to the clock interface.
Returns
CallbackReturn::SUCCESS if required data are provided and can be parsed.
CallbackReturn::ERROR if any error happens or data are missing.

◆ on_export_command_interfaces()

virtual std::vector< CommandInterface::SharedPtr > hardware_interface::HardwareComponentInterface::on_export_command_interfaces ( )
inlinevirtual

Default implementation for exporting the CommandInterfaces. The CommandInterfaces are created according to the InterfaceDescription. The memory accessed by the controllers and hardware is assigned here and resides in the system_interface.

Actuator and System components should override this method. Sensor components can use the default.

Returns
vector of shared pointers to the created and stored CommandInterfaces

Reimplemented in hardware_interface::SensorInterface.

◆ on_export_state_interfaces()

virtual std::vector< StateInterface::ConstSharedPtr > hardware_interface::HardwareComponentInterface::on_export_state_interfaces ( )
inlinevirtual

Default implementation for exporting the StateInterfaces. The StateInterfaces are created according to the InterfaceDescription. The memory accessed by the controllers and hardware is assigned here and resides in the interface.

Returns
vector of shared pointers to the created and stored StateInterfaces

◆ on_init() [1/2]

virtual CallbackReturn hardware_interface::HardwareComponentInterface::on_init ( const hardware_interface::HardwareComponentInterfaceParams params)
inlinevirtual

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

Parameters
[in]paramsA struct of type hardware_interface::HardwareComponentInterfaceParams containing all necessary parameters for initializing this specific hardware component, specifically its HardwareInfo, and a weak_ptr to the executor.
Warning
The parsed executor should not be used to call cancel() or use blocking callbacks such as spin().
Returns
CallbackReturn::SUCCESS if required data are provided and can be parsed.
CallbackReturn::ERROR if any error happens or data are missing.

Reimplemented in mock_components::GenericSystem, ros2_control_demo_example_17::RRBotSystemPositionOnlyHardware, and joint_state_topic_hardware_interface::JointStateTopicSystem.

◆ on_init() [2/2]

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

◆ perform_command_mode_switch()

virtual return_type hardware_interface::HardwareComponentInterface::perform_command_mode_switch ( const std::vector< std::string > &  ,
const std::vector< std::string > &   
)
inlinevirtual

Perform the mode-switching for the new command interface combination.

Note
This is part of the realtime update loop, and should be fast.
Parameters
[in]start_interfacesvector of string identifiers for the command interfaces starting.
[in]stop_interfacesvector of string identifiers for the command interfaces stopping.
Returns
return_type::OK if the new command interface combination can be switched to (or) if the interface key is not relevant to this system. Returns return_type::ERROR otherwise.

Reimplemented in gazebo_ros2_control::GazeboSystem, gz_ros2_control::GazeboSimSystem, and mock_components::GenericSystem.

◆ prepare_command_mode_switch()

virtual return_type hardware_interface::HardwareComponentInterface::prepare_command_mode_switch ( const std::vector< std::string > &  ,
const std::vector< std::string > &   
)
inlinevirtual

Prepare for a new command interface switch.

Prepare for any mode-switching required by the new command interface combination.

Note
This is a non-realtime evaluation of whether a set of command interface claims are possible, and call to start preparing data structures for the upcoming switch that will occur.
Parameters
[in]start_interfacesvector of string identifiers for the command interfaces starting.
[in]stop_interfacesvector of string identifiers for the command interfaces stopping.
Returns
return_type::OK if the new command interface combination can be prepared (or) if the interface key is not relevant to this system. Returns return_type::ERROR otherwise.

Reimplemented in mock_components::GenericSystem, and ros2_control_demo_example_3::RRBotSystemMultiInterfaceHardware.

◆ prepare_for_activation()

void hardware_interface::HardwareComponentInterface::prepare_for_activation ( )
inline

Prepare for the activation of the hardware.

This method is called before the hardware is activated by the resource manager.

◆ read()

virtual return_type hardware_interface::HardwareComponentInterface::read ( const rclcpp::Time &  time,
const rclcpp::Duration &  period 
)
pure virtual

Read the current state values from the hardware.

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 gazebo_ros2_control::GazeboSystem, gz_ros2_control::GazeboSimSystem, mock_components::GenericSystem, ros2_control_demo_example_1::RRBotSystemPositionOnlyHardware, ros2_control_demo_example_10::RRBotSystemWithGPIOHardware, ros2_control_demo_example_11::CarlikeBotSystemHardware, ros2_control_demo_example_12::RRBotSystemPositionOnlyHardware, ros2_control_demo_example_14::RRBotActuatorWithoutFeedback, ros2_control_demo_example_14::RRBotSensorPositionFeedback, ros2_control_demo_example_16::DiffBotSystemHardware, ros2_control_demo_example_17::RRBotSystemPositionOnlyHardware, ros2_control_demo_example_2::DiffBotSystemHardware, ros2_control_demo_example_3::RRBotSystemMultiInterfaceHardware, ros2_control_demo_example_4::RRBotSystemWithSensorHardware, ros2_control_demo_example_5::ExternalRRBotForceTorqueSensorHardware, ros2_control_demo_example_5::RRBotSystemPositionOnlyHardware, ros2_control_demo_example_6::RRBotModularJoint, ros2_control_demo_example_7::RobotSystem, ros2_control_demo_example_8::RRBotTransmissionsSystemPositionOnlyHardware, ros2_control_demo_example_9::RRBotSystemPositionOnlyHardware, and joint_state_topic_hardware_interface::JointStateTopicSystem.

◆ set_lifecycle_state()

void hardware_interface::HardwareComponentInterface::set_lifecycle_state ( const rclcpp_lifecycle::State &  new_state)
inline

Set life-cycle state of the hardware.

Returns
state.

◆ trigger_read()

HardwareComponentCycleStatus hardware_interface::HardwareComponentInterface::trigger_read ( const rclcpp::Time &  time,
const rclcpp::Duration &  period 
)
inline

Triggers the read method synchronously or asynchronously depending on the HardwareInfo.

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. The method is called in the resource_manager's read loop

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.

◆ trigger_write()

HardwareComponentCycleStatus hardware_interface::HardwareComponentInterface::trigger_write ( const rclcpp::Time &  time,
const rclcpp::Duration &  period 
)
inline

Triggers the write method synchronously or asynchronously depending on the HardwareInfo.

The physical hardware shall be updated with the latest value from the exported command interfaces. The method is called in the resource_manager's write loop

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.

◆ write()

virtual return_type hardware_interface::HardwareComponentInterface::write ( const rclcpp::Time &  ,
const rclcpp::Duration &   
)
inlinevirtual

Write the current command values to the hardware.

The physical hardware shall be updated with the latest value from the exported command interfaces.

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.

Reimplemented in hardware_interface::SensorInterface, mock_components::GenericSystem, ros2_control_demo_example_7::RobotSystem, joint_state_topic_hardware_interface::JointStateTopicSystem, gazebo_ros2_control::GazeboSystem, gz_ros2_control::GazeboSimSystem, ros2_control_demo_example_1::RRBotSystemPositionOnlyHardware, ros2_control_demo_example_10::RRBotSystemWithGPIOHardware, ros2_control_demo_example_11::CarlikeBotSystemHardware, ros2_control_demo_example_12::RRBotSystemPositionOnlyHardware, ros2_control_demo_example_14::RRBotActuatorWithoutFeedback, ros2_control_demo_example_16::DiffBotSystemHardware, ros2_control_demo_example_17::RRBotSystemPositionOnlyHardware, ros2_control_demo_example_2::DiffBotSystemHardware, ros2_control_demo_example_3::RRBotSystemMultiInterfaceHardware, ros2_control_demo_example_4::RRBotSystemWithSensorHardware, ros2_control_demo_example_5::RRBotSystemPositionOnlyHardware, ros2_control_demo_example_6::RRBotModularJoint, ros2_control_demo_example_8::RRBotTransmissionsSystemPositionOnlyHardware, ros2_control_demo_example_9::RRBotSystemPositionOnlyHardware, hardware_interface::ActuatorInterface, and hardware_interface::SystemInterface.


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