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_lifecycle/node_interfaces/lifecycle_node_interface.hpp"
44#include "rclcpp_lifecycle/state.hpp"
45#include "realtime_tools/async_function_handler.hpp"
50using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;
65 rclcpp_lifecycle::State(
66 lifecycle_msgs::msg::State::PRIMARY_STATE_UNKNOWN, lifecycle_state_names::UNKNOWN)),
67 logger_(rclcpp::get_logger(
"hardware_component_interface"))
91 [[deprecated(
"Use init(HardwareInfo, rclcpp::Logger, rclcpp::Clock::SharedPtr) instead.")]]
93 const HardwareInfo & hardware_info, rclcpp::Logger logger,
94 rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock_interface)
96 return this->
init(hardware_info, logger, clock_interface->get_clock());
109 "Replaced by CallbackReturn init(const hardware_interface::HardwareComponentParams & "
110 "params). Initialization is handled by the Framework.")]]
112 const HardwareInfo & hardware_info, rclcpp::Logger logger, rclcpp::Clock::SharedPtr clock)
116 params.
clock = clock;
135 clock_ = params.
clock;
136 auto logger_copy = params.
logger;
137 logger_ = logger_copy.get_child(
144 async_handler_ = std::make_unique<realtime_tools::AsyncFunctionHandler<return_type>>();
145 async_handler_->init(
146 [
this](
const rclcpp::Time & time,
const rclcpp::Duration & period)
148 const auto read_start_time = std::chrono::steady_clock::now();
149 const auto ret_read =
read(time, period);
150 const auto read_end_time = std::chrono::steady_clock::now();
151 read_return_info_.store(ret_read, std::memory_order_release);
152 read_execution_time_.store(
153 std::chrono::duration_cast<std::chrono::nanoseconds>(read_end_time - read_start_time),
154 std::memory_order_release);
155 if (ret_read != return_type::OK)
159 if (info_.
type !=
"sensor")
161 const auto write_start_time = std::chrono::steady_clock::now();
162 const auto ret_write =
write(time, period);
163 const auto write_end_time = std::chrono::steady_clock::now();
164 write_return_info_.store(ret_write, std::memory_order_release);
165 write_execution_time_.store(
166 std::chrono::duration_cast<std::chrono::nanoseconds>(
167 write_end_time - write_start_time),
168 std::memory_order_release);
171 return return_type::OK;
174 async_handler_->start_thread();
177 if (
auto locked_executor = params.
executor.lock())
181 node_name.begin(), node_name.end(), node_name.begin(),
182 [](
unsigned char c) { return std::tolower(c); });
183 std::replace(node_name.begin(), node_name.end(),
'/',
'_');
184 hardware_component_node_ = std::make_shared<rclcpp::Node>(node_name);
185 locked_executor->add_node(hardware_component_node_->get_node_base_interface());
191 "Executor is not available during hardware component initialization for '%s'. Skipping "
199 return on_init(interface_params);
208 [[deprecated(
"Use on_init(const HardwareComponentInterfaceParams & params) instead.")]]
211 info_ = hardware_info;
212 if (info_.
type ==
"actuator")
217 else if (info_.
type ==
"sensor")
222 else if (info_.
type ==
"system")
230 return CallbackReturn::SUCCESS;
247#pragma GCC diagnostic push
248#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
250#pragma GCC diagnostic pop
266 "Replaced by vector<StateInterface::ConstSharedPtr> on_export_state_interfaces() method. "
267 "Exporting is handled by the Framework.")]]
282 virtual std::vector<hardware_interface::InterfaceDescription>
299 std::vector<hardware_interface::InterfaceDescription> unlisted_interface_descriptions =
302 std::vector<StateInterface::ConstSharedPtr> state_interfaces;
303 state_interfaces.reserve(
304 unlisted_interface_descriptions.size() + joint_state_interfaces_.size() +
305 sensor_state_interfaces_.size() + gpio_state_interfaces_.size());
309 for (
const auto & description : unlisted_interface_descriptions)
311 auto name = description.get_name();
312 unlisted_state_interfaces_.insert(std::make_pair(name, description));
313 auto state_interface = std::make_shared<StateInterface>(description);
314 hardware_states_.insert(std::make_pair(name, state_interface));
315 unlisted_states_.push_back(state_interface);
316 state_interfaces.push_back(std::const_pointer_cast<const StateInterface>(state_interface));
319 for (
const auto & [name, descr] : joint_state_interfaces_)
321 auto state_interface = std::make_shared<StateInterface>(descr);
322 hardware_states_.insert(std::make_pair(name, state_interface));
323 joint_states_.push_back(state_interface);
324 state_interfaces.push_back(std::const_pointer_cast<const StateInterface>(state_interface));
326 for (
const auto & [name, descr] : sensor_state_interfaces_)
328 auto state_interface = std::make_shared<StateInterface>(descr);
329 hardware_states_.insert(std::make_pair(name, state_interface));
330 sensor_states_.push_back(state_interface);
331 state_interfaces.push_back(std::const_pointer_cast<const StateInterface>(state_interface));
333 for (
const auto & [name, descr] : gpio_state_interfaces_)
335 auto state_interface = std::make_shared<StateInterface>(descr);
336 hardware_states_.insert(std::make_pair(name, state_interface));
337 gpio_states_.push_back(state_interface);
338 state_interfaces.push_back(std::const_pointer_cast<const StateInterface>(state_interface));
340 return state_interfaces;
356 "Replaced by vector<CommandInterface::SharedPtr> on_export_command_interfaces() method. "
357 "Exporting is handled by the Framework.")]]
372 virtual std::vector<hardware_interface::InterfaceDescription>
392 std::vector<hardware_interface::InterfaceDescription> unlisted_interface_descriptions =
395 std::vector<CommandInterface::SharedPtr> command_interfaces;
396 command_interfaces.reserve(
397 unlisted_interface_descriptions.size() + joint_command_interfaces_.size() +
398 gpio_command_interfaces_.size());
402 for (
const auto & description : unlisted_interface_descriptions)
404 auto name = description.get_name();
405 unlisted_command_interfaces_.insert(std::make_pair(name, description));
406 auto command_interface = std::make_shared<CommandInterface>(description);
407 hardware_commands_.insert(std::make_pair(name, command_interface));
408 unlisted_commands_.push_back(command_interface);
409 command_interfaces.push_back(command_interface);
412 for (
const auto & [name, descr] : joint_command_interfaces_)
414 auto command_interface = std::make_shared<CommandInterface>(descr);
415 hardware_commands_.insert(std::make_pair(name, command_interface));
416 joint_commands_.push_back(command_interface);
417 command_interfaces.push_back(command_interface);
420 for (
const auto & [name, descr] : gpio_command_interfaces_)
422 auto command_interface = std::make_shared<CommandInterface>(descr);
423 hardware_commands_.insert(std::make_pair(name, command_interface));
424 gpio_commands_.push_back(command_interface);
425 command_interfaces.push_back(command_interface);
427 return command_interfaces;
442 const std::vector<std::string> & ,
443 const std::vector<std::string> & )
445 return return_type::OK;
459 const std::vector<std::string> & ,
460 const std::vector<std::string> & )
462 return return_type::OK;
477 const rclcpp::Time & time,
const rclcpp::Duration & period)
480 status.result = return_type::ERROR;
483 status.result = read_return_info_.load(std::memory_order_acquire);
484 const auto read_exec_time = read_execution_time_.load(std::memory_order_acquire);
485 if (read_exec_time.count() > 0)
487 status.execution_time = read_exec_time;
489 const auto result = async_handler_->trigger_async_callback(time, period);
490 status.successful = result.first;
491 if (!status.successful)
495 "Trigger read/write called while the previous async trigger is still in progress for "
496 "hardware interface : '%s'. Failed to trigger read/write cycle!",
498 status.result = return_type::OK;
504 const auto start_time = std::chrono::steady_clock::now();
505 status.successful =
true;
506 status.result =
read(time, period);
507 status.execution_time = std::chrono::duration_cast<std::chrono::nanoseconds>(
508 std::chrono::steady_clock::now() - start_time);
523 virtual return_type
read(
const rclcpp::Time & time,
const rclcpp::Duration & period) = 0;
536 const rclcpp::Time & time,
const rclcpp::Duration & period)
539 status.result = return_type::ERROR;
542 status.successful =
true;
543 const auto write_exec_time = write_execution_time_.load(std::memory_order_acquire);
544 if (write_exec_time.count() > 0)
546 status.execution_time = write_exec_time;
548 status.result = write_return_info_.load(std::memory_order_acquire);
552 const auto start_time = std::chrono::steady_clock::now();
553 status.successful =
true;
554 status.result =
write(time, period);
555 status.execution_time = std::chrono::duration_cast<std::chrono::nanoseconds>(
556 std::chrono::steady_clock::now() - start_time);
570 virtual return_type
write(
const rclcpp::Time & ,
const rclcpp::Duration & )
572 return return_type::OK;
599 lifecycle_state_ = new_state;
602 template <
typename T>
603 void set_state(
const std::string & interface_name,
const T & value)
605 auto it = hardware_states_.find(interface_name);
606 if (it == hardware_states_.end())
608 throw std::runtime_error(
611 "State interface not found: {} in hardware component: {}. "
612 "This should not happen."),
613 interface_name, info_.
name));
615 auto & handle = it->second;
616 std::unique_lock<std::shared_mutex> lock(handle->get_mutex());
617 std::ignore = handle->set_value(lock, value);
620 template <
typename T =
double>
621 T get_state(
const std::string & interface_name)
const
623 auto it = hardware_states_.find(interface_name);
624 if (it == hardware_states_.end())
626 throw std::runtime_error(
629 "State interface not found: {} in hardware component: {}. "
630 "This should not happen."),
631 interface_name, info_.
name));
633 auto & handle = it->second;
634 std::shared_lock<std::shared_mutex> lock(handle->get_mutex());
635 const auto opt_value = handle->get_optional<T>(lock);
638 throw std::runtime_error(
640 FMT_COMPILE(
"Failed to get state value from interface: {}. This should not happen."),
643 return opt_value.value();
646 template <
typename T>
647 void set_command(
const std::string & interface_name,
const T & value)
649 auto it = hardware_commands_.find(interface_name);
650 if (it == hardware_commands_.end())
652 throw std::runtime_error(
655 "Command interface not found: {} in hardware component: {}. "
656 "This should not happen."),
657 interface_name, info_.
name));
659 auto & handle = it->second;
660 std::unique_lock<std::shared_mutex> lock(handle->get_mutex());
661 std::ignore = handle->set_value(lock, value);
664 template <
typename T =
double>
665 T get_command(
const std::string & interface_name)
const
667 auto it = hardware_commands_.find(interface_name);
668 if (it == hardware_commands_.end())
670 throw std::runtime_error(
673 "Command interface not found: {} in hardware component: {}. "
674 "This should not happen."),
675 interface_name, info_.
name));
677 auto & handle = it->second;
678 std::shared_lock<std::shared_mutex> lock(handle->get_mutex());
679 const auto opt_value = handle->get_optional<
double>(lock);
682 throw std::runtime_error(
684 FMT_COMPILE(
"Failed to get command value from interface: {}. This should not happen."),
687 return opt_value.value();
700 rclcpp::Clock::SharedPtr
get_clock()
const {
return clock_; }
706 rclcpp::Node::SharedPtr
get_node()
const {
return hardware_component_node_; }
720 read_return_info_.store(return_type::OK, std::memory_order_release);
721 read_execution_time_.store(std::chrono::nanoseconds::zero(), std::memory_order_release);
722 write_return_info_.store(return_type::OK, std::memory_order_release);
723 write_execution_time_.store(std::chrono::nanoseconds::zero(), std::memory_order_release);
734 stats_registrations_.enableAll();
738 stats_registrations_.disableAll();
745 std::unordered_map<std::string, InterfaceDescription> joint_state_interfaces_;
746 std::unordered_map<std::string, InterfaceDescription> joint_command_interfaces_;
748 std::unordered_map<std::string, InterfaceDescription> sensor_state_interfaces_;
750 std::unordered_map<std::string, InterfaceDescription> gpio_state_interfaces_;
751 std::unordered_map<std::string, InterfaceDescription> gpio_command_interfaces_;
753 std::unordered_map<std::string, InterfaceDescription> unlisted_state_interfaces_;
754 std::unordered_map<std::string, InterfaceDescription> unlisted_command_interfaces_;
756 rclcpp_lifecycle::State lifecycle_state_;
757 std::unique_ptr<realtime_tools::AsyncFunctionHandler<return_type>> async_handler_;
760 std::vector<StateInterface::SharedPtr> joint_states_;
761 std::vector<CommandInterface::SharedPtr> joint_commands_;
763 std::vector<StateInterface::SharedPtr> sensor_states_;
765 std::vector<StateInterface::SharedPtr> gpio_states_;
766 std::vector<CommandInterface::SharedPtr> gpio_commands_;
768 std::vector<StateInterface::SharedPtr> unlisted_states_;
769 std::vector<CommandInterface::SharedPtr> unlisted_commands_;
772 rclcpp::Clock::SharedPtr clock_;
773 rclcpp::Logger logger_;
774 rclcpp::Node::SharedPtr hardware_component_node_ =
nullptr;
776 std::unordered_map<std::string, StateInterface::SharedPtr> hardware_states_;
777 std::unordered_map<std::string, CommandInterface::SharedPtr> hardware_commands_;
778 std::atomic<return_type> read_return_info_ = return_type::OK;
779 std::atomic<std::chrono::nanoseconds> read_execution_time_ = std::chrono::nanoseconds::zero();
780 std::atomic<return_type> write_return_info_ = return_type::OK;
781 std::atomic<std::chrono::nanoseconds> write_execution_time_ = std::chrono::nanoseconds::zero();
784 pal_statistics::RegistrationsRAII stats_registrations_;
Virtual base class for all hardware components (Actuators, Sensors, and Systems).
Definition hardware_component_interface.hpp:61
const std::string & get_name() const
Get name of the hardware.
Definition hardware_component_interface.hpp:579
void prepare_for_activation()
Prepare for the activation of the hardware.
Definition hardware_component_interface.hpp:718
virtual std::vector< StateInterface > export_state_interfaces()
Exports all state interfaces for this hardware interface.
Definition hardware_component_interface.hpp:268
const rclcpp_lifecycle::State & get_lifecycle_state() const
Get life-cycle state of the hardware.
Definition hardware_component_interface.hpp:591
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 &, const rclcpp::Duration &)
Write the current command values to the hardware.
Definition hardware_component_interface.hpp:570
virtual std::vector< StateInterface::ConstSharedPtr > on_export_state_interfaces()
Definition hardware_component_interface.hpp:296
virtual std::vector< hardware_interface::InterfaceDescription > export_unlisted_command_interface_descriptions()
Definition hardware_component_interface.hpp:373
virtual std::vector< hardware_interface::InterfaceDescription > export_unlisted_state_interface_descriptions()
Definition hardware_component_interface.hpp:283
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.hpp:476
void set_lifecycle_state(const rclcpp_lifecycle::State &new_state)
Set life-cycle state of the hardware.
Definition hardware_component_interface.hpp:597
virtual return_type perform_command_mode_switch(const std::vector< std::string > &, const std::vector< std::string > &)
Definition hardware_component_interface.hpp:458
const std::string & get_group_name() const
Get name of the hardware group to which it belongs to.
Definition hardware_component_interface.hpp:585
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.hpp:535
CallbackReturn init(const HardwareInfo &hardware_info, rclcpp::Logger logger, rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock_interface)
Definition hardware_component_interface.hpp:92
HardwareComponentInterface(const HardwareComponentInterface &other)=delete
HardwareComponentInterface copy constructor is actively deleted.
rclcpp::Node::SharedPtr get_node() const
Get the default node of the Interface.
Definition hardware_component_interface.hpp:706
virtual return_type prepare_command_mode_switch(const std::vector< std::string > &, const std::vector< std::string > &)
Prepare for a new command interface switch.
Definition hardware_component_interface.hpp:441
CallbackReturn init(const hardware_interface::HardwareComponentParams ¶ms)
Definition hardware_component_interface.hpp:133
CallbackReturn init(const HardwareInfo &hardware_info, rclcpp::Logger logger, rclcpp::Clock::SharedPtr clock)
Definition hardware_component_interface.hpp:111
void enable_introspection(bool enable)
Enable or disable introspection of the hardware.
Definition hardware_component_interface.hpp:730
rclcpp::Logger get_logger() const
Get the logger of the Interface.
Definition hardware_component_interface.hpp:694
virtual std::vector< CommandInterface > export_command_interfaces()
Exports all command interfaces for this hardware interface.
Definition hardware_component_interface.hpp:358
virtual std::vector< CommandInterface::SharedPtr > on_export_command_interfaces()
Definition hardware_component_interface.hpp:389
rclcpp::Clock::SharedPtr get_clock() const
Get the clock of the Interface.
Definition hardware_component_interface.hpp:700
const HardwareInfo & get_hardware_info() const
Get the hardware info of the Interface.
Definition hardware_component_interface.hpp:712
virtual CallbackReturn on_init(const hardware_interface::HardwareComponentInterfaceParams ¶ms)
Initialization of the hardware interface from data parsed from the robot's URDF.
Definition hardware_component_interface.hpp:243
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.hpp:209
Definition actuator.hpp:22
std::vector< InterfaceDescription > parse_command_interface_descriptions(const std::vector< ComponentInfo > &component_info)
Definition component_parser.cpp:1067
std::vector< InterfaceDescription > parse_state_interface_descriptions(const std::vector< ComponentInfo > &component_info)
Definition component_parser.cpp:1034
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
rclcpp::Executor::WeakPtr executor
Weak pointer to the rclcpp::Executor instance. Hardware components can use this (after locking) to ad...
Definition hardware_component_interface_params.hpp:46
hardware_interface::HardwareInfo hardware_info
Reference to the HardwareInfo struct for this specific component, parsed from the URDF....
Definition hardware_component_interface_params.hpp:39
Parameters required for the initialization of a specific hardware component plugin....
Definition hardware_component_params.hpp:32
rclcpp::Executor::WeakPtr executor
Weak pointer to the rclcpp::Executor instance. Hardware components can use this (after locking) to ad...
Definition hardware_component_params.hpp:57
rclcpp::Logger logger
A logger instance taken from resource manager.
Definition hardware_component_params.hpp:44
rclcpp::Clock::SharedPtr clock
Shared pointer to the rclcpp::Clock to be used by this hardware component. Typically,...
Definition hardware_component_params.hpp:50
hardware_interface::HardwareInfo hardware_info
Reference to the HardwareInfo struct for this specific component, parsed from the URDF....
Definition hardware_component_params.hpp:39
This structure stores information about hardware defined in a robot's URDF.
Definition hardware_info.hpp:234
std::string type
Type of the hardware: actuator, sensor or system.
Definition hardware_info.hpp:238
int thread_priority
Async thread priority.
Definition hardware_info.hpp:246
std::string group
Hardware group to which the hardware belongs.
Definition hardware_info.hpp:240
bool is_async
Component is async.
Definition hardware_info.hpp:244
std::vector< ComponentInfo > gpios
Definition hardware_info.hpp:269
std::vector< ComponentInfo > joints
Definition hardware_info.hpp:255
std::string name
Name of the hardware.
Definition hardware_info.hpp:236
std::vector< ComponentInfo > sensors
Definition hardware_info.hpp:264