15#ifndef HARDWARE_INTERFACE__HARDWARE_COMPONENT_INTERFACE_HPP_
16#define HARDWARE_INTERFACE__HARDWARE_COMPONENT_INTERFACE_HPP_
18#include <fmt/compile.h>
23#include <unordered_map>
27#include "hardware_interface/component_parser.hpp"
28#include "hardware_interface/handle.hpp"
29#include "hardware_interface/hardware_info.hpp"
30#include "hardware_interface/introspection.hpp"
31#include "hardware_interface/types/hardware_component_interface_params.hpp"
32#include "hardware_interface/types/hardware_component_params.hpp"
33#include "hardware_interface/types/hardware_interface_return_values.hpp"
34#include "hardware_interface/types/hardware_interface_type_values.hpp"
35#include "hardware_interface/types/lifecycle_state_names.hpp"
36#include "hardware_interface/types/trigger_type.hpp"
37#include "lifecycle_msgs/msg/state.hpp"
38#include "rclcpp/duration.hpp"
39#include "rclcpp/logger.hpp"
40#include "rclcpp/logging.hpp"
41#include "rclcpp/node_interfaces/node_clock_interface.hpp"
42#include "rclcpp/time.hpp"
43#include "rclcpp/version.h"
44#include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp"
45#include "rclcpp_lifecycle/state.hpp"
46#include "realtime_tools/async_function_handler.hpp"
51using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;
86 [[deprecated(
"Use init(HardwareInfo, rclcpp::Logger, rclcpp::Clock::SharedPtr) instead.")]]
88 const HardwareInfo & hardware_info, rclcpp::Logger logger,
89 rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock_interface)
91#pragma GCC diagnostic push
92#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
93 return this->
init(hardware_info, logger, clock_interface->get_clock());
94#pragma GCC diagnostic pop
107 "Replaced by CallbackReturn init(const hardware_interface::HardwareComponentParams & "
108 "params). Initialization is handled by the Framework.")]]
110 const HardwareInfo & hardware_info, rclcpp::Logger logger, rclcpp::Clock::SharedPtr clock)
114 params.
clock = clock;
139 [[deprecated(
"Use on_init(const HardwareComponentInterfaceParams & params) instead.")]]
152 virtual CallbackReturn
on_init(
175 "Replaced by vector<StateInterface::ConstSharedPtr> on_export_state_interfaces() method. "
176 "Exporting is handled by the Framework.")]]
virtual std::vector<StateInterface>
185 virtual std::vector<hardware_interface::InterfaceDescription>
210 "Replaced by vector<CommandInterface::SharedPtr> on_export_command_interfaces() method. "
211 "Exporting is handled by the Framework.")]]
virtual std::vector<CommandInterface>
220 virtual std::vector<hardware_interface::InterfaceDescription>
247 const std::vector<std::string> & start_interfaces,
248 const std::vector<std::string> & stop_interfaces);
261 const std::vector<std::string> & start_interfaces,
262 const std::vector<std::string> & stop_interfaces);
276 const rclcpp::Time & time,
const rclcpp::Duration & period);
288 virtual return_type
read(
const rclcpp::Time & time,
const rclcpp::Duration & period) = 0;
301 const rclcpp::Time & time,
const rclcpp::Duration & period);
312 virtual return_type
write(
const rclcpp::Time & time,
const rclcpp::Duration & period);
318 const std::string &
get_name()
const;
352 virtual bool has_state(
const std::string & interface_name)
const;
362 const std::string & interface_name)
const;
375 template <
typename T>
377 const StateInterface::SharedPtr & interface_handle,
const T & value,
bool wait_until_set)
379 if (!interface_handle)
381 throw std::runtime_error(
383 "State interface handle is null in hardware component: {}, while calling set_state "
384 "method. This should not happen.",
387 return interface_handle->set_value(value, wait_until_set);
399 template <
typename T>
400 void set_state(
const std::string & interface_name,
const T & value)
415 template <
typename T>
417 const StateInterface::SharedPtr & interface_handle, T & state,
bool wait_until_get)
const
419 if (!interface_handle)
421 throw std::runtime_error(
423 "State interface handle is null in hardware component: {}, while calling get_state "
424 "method. This should not happen.",
427 const bool success = interface_handle->get_value(state, wait_until_get);
428 if (!success && wait_until_get)
430 throw std::runtime_error(
432 "Failed to get state value from interface: {} in hardware component: {}. This should "
434 interface_handle->get_name(), info_.
name));
448 template <
typename T =
double>
461 virtual bool has_command(
const std::string & interface_name)
const;
471 const std::string & interface_name)
const;
483 template <
typename T>
485 const CommandInterface::SharedPtr & interface_handle,
const T & value,
bool wait_until_set)
487 if (!interface_handle)
489 throw std::runtime_error(
491 "Command interface handle is null in hardware component: {}, while calling set_command "
492 "method. This should not happen.",
495 return interface_handle->set_value(value, wait_until_set);
507 template <
typename T>
508 void set_command(
const std::string & interface_name,
const T & value)
523 template <
typename T>
525 const CommandInterface::SharedPtr & interface_handle, T & command,
bool wait_until_get)
const
527 if (!interface_handle)
529 throw std::runtime_error(
531 "Command interface handle is null in hardware component: {}, while calling get_command "
532 "method. This should not happen.",
535 const bool success = interface_handle->get_value(command, wait_until_get);
536 if (!success && wait_until_get)
538 throw std::runtime_error(
540 "Failed to get command value from interface: {} in hardware component: {}. This should "
542 interface_handle->get_name(), info_.
name));
556 template <
typename T =
double>
574 virtual rclcpp::Clock::SharedPtr
get_clock()
const;
580 virtual rclcpp::Node::SharedPtr
get_node()
const;
610 std::unordered_map<std::string, InterfaceDescription> joint_state_interfaces_;
611 std::unordered_map<std::string, InterfaceDescription> joint_command_interfaces_;
613 std::unordered_map<std::string, InterfaceDescription> sensor_state_interfaces_;
615 std::unordered_map<std::string, InterfaceDescription> gpio_state_interfaces_;
616 std::unordered_map<std::string, InterfaceDescription> gpio_command_interfaces_;
618 std::unordered_map<std::string, InterfaceDescription> unlisted_state_interfaces_;
619 std::unordered_map<std::string, InterfaceDescription> unlisted_command_interfaces_;
621 rclcpp_lifecycle::State lifecycle_state_;
622 std::unique_ptr<realtime_tools::AsyncFunctionHandler<return_type>> async_handler_;
625 std::vector<StateInterface::SharedPtr> joint_states_;
626 std::vector<CommandInterface::SharedPtr> joint_commands_;
628 std::vector<StateInterface::SharedPtr> sensor_states_;
630 std::vector<StateInterface::SharedPtr> gpio_states_;
631 std::vector<CommandInterface::SharedPtr> gpio_commands_;
633 std::vector<StateInterface::SharedPtr> unlisted_states_;
634 std::vector<CommandInterface::SharedPtr> unlisted_commands_;
637 class HardwareComponentInterfaceImpl;
638 std::unique_ptr<HardwareComponentInterfaceImpl> impl_;
641 pal_statistics::RegistrationsRAII stats_registrations_;
Virtual base class for all hardware components (Actuators, Sensors, and Systems).
Definition hardware_component_interface.hpp:62
const std::string & get_name() const
Get name of the hardware.
Definition hardware_component_interface.cpp:387
void prepare_for_activation()
Prepare for the activation of the hardware.
Definition hardware_component_interface.cpp:465
virtual std::vector< hardware_interface::InterfaceDescription > export_unlisted_state_interface_descriptions()
Definition hardware_component_interface.cpp:195
T get_state(const std::string &interface_name) const
Get the value from a state interface.
Definition hardware_component_interface.hpp:449
bool get_state(const StateInterface::SharedPtr &interface_handle, T &state, bool wait_until_get) const
Definition hardware_component_interface.hpp:416
const rclcpp_lifecycle::State & get_lifecycle_state() const
Get life-cycle state of the hardware.
Definition hardware_component_interface.cpp:391
virtual return_type read(const rclcpp::Time &time, const rclcpp::Duration &period)=0
Read the current state values from the hardware.
virtual return_type write(const rclcpp::Time &time, const rclcpp::Duration &period)
Write the current command values to the hardware.
Definition hardware_component_interface.cpp:381
bool set_command(const CommandInterface::SharedPtr &interface_handle, const T &value, bool wait_until_set)
Set the value of a command interface.
Definition hardware_component_interface.hpp:484
virtual rclcpp::NodeOptions define_custom_node_options() const
Define custom node options for the hardware component interface.
Definition hardware_component_interface.cpp:176
void set_state(const std::string &interface_name, const T &value)
Set the value of a state interface.
Definition hardware_component_interface.hpp:400
HardwareComponentCycleStatus trigger_read(const rclcpp::Time &time, const rclcpp::Duration &period)
Triggers the read method synchronously or asynchronously depending on the HardwareInfo.
Definition hardware_component_interface.cpp:318
virtual std::vector< CommandInterface::SharedPtr > on_export_command_interfaces()
Definition hardware_component_interface.cpp:263
virtual CallbackReturn on_init(const HardwareInfo &hardware_info)
Initialization of the hardware interface from data parsed from the robot's URDF.
Definition hardware_component_interface.cpp:141
void set_lifecycle_state(const rclcpp_lifecycle::State &new_state)
Set life-cycle state of the hardware.
Definition hardware_component_interface.cpp:396
virtual bool has_command(const std::string &interface_name) const
Does the command interface exist?
Definition hardware_component_interface.cpp:426
void pause_async_operations()
Pause any asynchronous operations.
Definition hardware_component_interface.cpp:456
const std::string & get_group_name() const
Get name of the hardware group to which it belongs to.
Definition hardware_component_interface.cpp:389
HardwareComponentCycleStatus trigger_write(const rclcpp::Time &time, const rclcpp::Duration &period)
Triggers the write method synchronously or asynchronously depending on the HardwareInfo.
Definition hardware_component_interface.cpp:355
virtual std::vector< hardware_interface::InterfaceDescription > export_unlisted_command_interface_descriptions()
Definition hardware_component_interface.cpp:257
virtual std::vector< CommandInterface > export_command_interfaces()
Exports all command interfaces for this hardware interface.
Definition hardware_component_interface.cpp:248
bool get_command(const CommandInterface::SharedPtr &interface_handle, T &command, bool wait_until_get) const
Definition hardware_component_interface.hpp:524
CallbackReturn init(const HardwareInfo &hardware_info, rclcpp::Logger logger, rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock_interface)
Definition hardware_component_interface.hpp:87
virtual const StateInterface::SharedPtr & get_state_interface_handle(const std::string &interface_name) const
Get the state interface handle.
Definition hardware_component_interface.cpp:412
HardwareComponentInterface(const HardwareComponentInterface &other)=delete
HardwareComponentInterface copy constructor is actively deleted.
uint8_t get_lifecycle_id() const
Get the lifecycle id of the hardware component interface.
Definition hardware_component_interface.cpp:402
bool set_state(const StateInterface::SharedPtr &interface_handle, const T &value, bool wait_until_set)
Set the value of a state interface.
Definition hardware_component_interface.hpp:376
void set_command(const std::string &interface_name, const T &value)
Set the value of a command interface.
Definition hardware_component_interface.hpp:508
virtual return_type prepare_command_mode_switch(const std::vector< std::string > &start_interfaces, const std::vector< std::string > &stop_interfaces)
Prepare for a new command interface switch.
Definition hardware_component_interface.cpp:304
virtual rclcpp::Node::SharedPtr get_node() const
Get the default node of the HardwareComponentInterface.
Definition hardware_component_interface.cpp:449
virtual std::vector< StateInterface::ConstSharedPtr > on_export_state_interfaces()
Definition hardware_component_interface.cpp:201
virtual std::vector< StateInterface > export_state_interfaces()
Exports all state interfaces for this hardware interface.
Definition hardware_component_interface.cpp:186
CallbackReturn init(const HardwareInfo &hardware_info, rclcpp::Logger logger, rclcpp::Clock::SharedPtr clock)
Definition hardware_component_interface.hpp:109
void enable_introspection(bool enable)
Enable or disable introspection of the hardware.
Definition hardware_component_interface.cpp:473
virtual const CommandInterface::SharedPtr & get_command_interface_handle(const std::string &interface_name) const
Get the command interface handle.
Definition hardware_component_interface.cpp:431
virtual rclcpp::Logger get_logger() const
Get the logger of the HardwareComponentInterface.
Definition hardware_component_interface.cpp:445
T get_command(const std::string &interface_name) const
Get the value from a command interface.
Definition hardware_component_interface.hpp:557
virtual rclcpp::Clock::SharedPtr get_clock() const
Get the clock.
Definition hardware_component_interface.cpp:447
const HardwareInfo & get_hardware_info() const
Get the hardware info of the HardwareComponentInterface.
Definition hardware_component_interface.cpp:454
virtual return_type perform_command_mode_switch(const std::vector< std::string > &start_interfaces, const std::vector< std::string > &stop_interfaces)
Definition hardware_component_interface.cpp:311
virtual bool has_state(const std::string &interface_name) const
Does the state interface exist?
Definition hardware_component_interface.cpp:407
Definition actuator.hpp:22
Definition hardware_interface_return_values.hpp:41
Parameters required for the initialization of a specific hardware component plugin....
Definition hardware_component_interface_params.hpp:32
Parameters required for the initialization of a specific hardware component plugin....
Definition hardware_component_params.hpp:33
rclcpp::Logger logger
A logger instance taken from resource manager.
Definition hardware_component_params.hpp:45
rclcpp::Clock::SharedPtr clock
Shared pointer to the rclcpp::Clock to be used by this hardware component. Typically,...
Definition hardware_component_params.hpp:51
hardware_interface::HardwareInfo hardware_info
Reference to the HardwareInfo struct for this specific component, parsed from the URDF....
Definition hardware_component_params.hpp:40
This structure stores information about hardware defined in a robot's URDF.
Definition hardware_info.hpp:360
std::string name
Name of the hardware.
Definition hardware_info.hpp:362