Class HardwareComponentInterface

Inheritance Relationships

Base Type

  • public rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface

Derived Types

Class Documentation

class HardwareComponentInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface

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.

Subclassed by hardware_interface::ActuatorInterface, hardware_interface::SensorInterface, hardware_interface::SystemInterface

Public Functions

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

HardwareComponentInterface(HardwareComponentInterface &&other) = delete
virtual ~HardwareComponentInterface() = default
inline CallbackReturn init(const HardwareInfo &hardware_info, rclcpp::Logger logger, rclcpp::Clock::SharedPtr clock)

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

Parameters:
  • hardware_info[in] structure with data from URDF.

  • clock[in] pointer to the resource manager clock.

  • logger[in] Logger for the hardware component.

Returns:

CallbackReturn::SUCCESS if required data are provided and can be parsed.

Returns:

CallbackReturn::ERROR if any error happens or data are missing.

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

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

Warning

The parsed executor should not be used to call cancel() or use blocking callbacks such as spin().

Parameters:

params[in] A 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.

Returns:

CallbackReturn::SUCCESS if required data are provided and can be parsed.

Returns:

CallbackReturn::ERROR if any error happens or data are missing.

inline virtual CallbackReturn on_init(const HardwareInfo &hardware_info)

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

Parameters:

hardware_info[in] structure with data from URDF.

Returns:

CallbackReturn::SUCCESS if required data are provided and can be parsed.

Returns:

CallbackReturn::ERROR if any error happens or data are missing.

inline virtual CallbackReturn on_init(const hardware_interface::HardwareComponentInterfaceParams &params)

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

Warning

The parsed executor should not be used to call cancel() or use blocking callbacks such as spin().

Parameters:

params[in] A 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.

Returns:

CallbackReturn::SUCCESS if required data are provided and can be parsed.

Returns:

CallbackReturn::ERROR if any error happens or data are missing.

inline virtual std::vector<StateInterface> export_state_interfaces()

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

inline virtual std::vector<hardware_interface::InterfaceDescription> export_unlisted_state_interface_descriptions()

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

inline virtual std::vector<StateInterface::ConstSharedPtr> on_export_state_interfaces()

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

inline virtual std::vector<CommandInterface> export_command_interfaces()

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

inline virtual std::vector<hardware_interface::InterfaceDescription> export_unlisted_command_interface_descriptions()

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

inline virtual std::vector<CommandInterface::SharedPtr> on_export_command_interfaces()

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

inline virtual return_type prepare_command_mode_switch(const std::vector<std::string>&, const std::vector<std::string>&)

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:
  • start_interfaces[in] vector of string identifiers for the command interfaces starting.

  • stop_interfaces[in] vector 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.

inline virtual return_type perform_command_mode_switch(const std::vector<std::string>&, const std::vector<std::string>&)

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

Note

This is part of the realtime update loop, and should be fast.

Parameters:
  • start_interfaces[in] vector of string identifiers for the command interfaces starting.

  • stop_interfaces[in] vector 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.

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

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:
  • time[in] The time at the start of this control loop iteration

  • period[in] The measured time taken by the last control loop iteration

Returns:

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

virtual return_type read(const rclcpp::Time &time, const rclcpp::Duration &period) = 0

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:
  • time[in] The time at the start of this control loop iteration

  • period[in] The measured time taken by the last control loop iteration

Returns:

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

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

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:
  • time[in] The time at the start of this control loop iteration

  • period[in] The measured time taken by the last control loop iteration

Returns:

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

inline virtual return_type write(const rclcpp::Time&, const rclcpp::Duration&)

Write the current command values to the hardware.

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

Parameters:
  • time[in] The time at the start of this control loop iteration

  • period[in] The measured time taken by the last control loop iteration

Returns:

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

inline const std::string &get_name() const

Get name of the hardware.

Returns:

name.

inline const std::string &get_group_name() const

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

Returns:

group name.

inline const rclcpp_lifecycle::State &get_lifecycle_state() const

Get life-cycle state of the hardware.

Returns:

state.

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

Set life-cycle state of the hardware.

Returns:

state.

template<typename T>
inline void set_state(const std::string &interface_name, const T &value)

Set the value of a state interface.

Template Parameters:

T – The type of the value to be stored.

Parameters:
  • interface_name[in] The name of the state interface to access.

  • value[in] The value to store.

Throws:

std::runtime_error – This method throws a runtime error if it cannot access the state interface.

template<typename T = double>
inline T get_state(const std::string &interface_name) const

Get the value from a state interface.

Template Parameters:

T – The type of the value to be retrieved.

Parameters:

interface_name[in] The name of the state interface to access.

Throws:

std::runtime_error – This method throws a runtime error if it cannot access the state interface or its stored value.

Returns:

The value obtained from the interface.

template<typename T>
inline void set_command(const std::string &interface_name, const T &value)

Set the value of a command interface.

Template Parameters:

T – The type of the value to be stored.

Parameters:
  • interface_name – The name of the command interface to access.

  • value – The value to store.

Throws:

This – method throws a runtime error if it cannot access the command interface.

template<typename T = double>
inline T get_command(const std::string &interface_name) const

Get the value from a command interface.

Template Parameters:

T – The type of the value to be retrieved.

Parameters:

interface_name[in] The name of the command interface to access.

Throws:

std::runtime_error – This method throws a runtime error if it cannot access the command interface or its stored value.

Returns:

The value obtained from the interface.

inline rclcpp::Logger get_logger() const

Get the logger of the HardwareComponentInterface.

Returns:

logger of the HardwareComponentInterface.

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

Get the clock.

Returns:

clock that is shared with the controller manager

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

Get the default node of the HardwareComponentInterface.

Returns:

node of the HardwareComponentInterface.

inline const HardwareInfo &get_hardware_info() const

Get the hardware info of the HardwareComponentInterface.

Returns:

hardware info of the HardwareComponentInterface.

inline void prepare_for_activation()

Prepare for the activation of the hardware.

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

inline void enable_introspection(bool enable)

Enable or disable introspection of the hardware.

Parameters:

enable[in] Enable introspection if true, disable otherwise.

Protected Attributes

HardwareInfo info_
std::unordered_map<std::string, InterfaceDescription> joint_state_interfaces_
std::unordered_map<std::string, InterfaceDescription> joint_command_interfaces_
std::unordered_map<std::string, InterfaceDescription> sensor_state_interfaces_
std::unordered_map<std::string, InterfaceDescription> gpio_state_interfaces_
std::unordered_map<std::string, InterfaceDescription> gpio_command_interfaces_
std::unordered_map<std::string, InterfaceDescription> unlisted_state_interfaces_
std::unordered_map<std::string, InterfaceDescription> unlisted_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_