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 "control_msgs/msg/hardware_status.hpp"
28#include "hardware_interface/component_parser.hpp"
29#include "hardware_interface/handle.hpp"
30#include "hardware_interface/hardware_info.hpp"
31#include "hardware_interface/introspection.hpp"
32#include "hardware_interface/types/hardware_component_interface_params.hpp"
33#include "hardware_interface/types/hardware_component_params.hpp"
34#include "hardware_interface/types/hardware_interface_return_values.hpp"
35#include "hardware_interface/types/hardware_interface_type_values.hpp"
36#include "hardware_interface/types/lifecycle_state_names.hpp"
37#include "hardware_interface/types/trigger_type.hpp"
38#include "lifecycle_msgs/msg/state.hpp"
39#include "rclcpp/duration.hpp"
40#include "rclcpp/logger.hpp"
41#include "rclcpp/logging.hpp"
42#include "rclcpp/node_interfaces/node_clock_interface.hpp"
43#include "rclcpp/time.hpp"
44#include "rclcpp/version.h"
45#include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp"
46#include "rclcpp_lifecycle/state.hpp"
47#include "realtime_tools/async_function_handler.hpp"
48#include "realtime_tools/realtime_publisher.hpp"
49#include "realtime_tools/realtime_thread_safe_box.hpp"
54static inline rclcpp::NodeOptions get_hardware_component_node_options()
56 rclcpp::NodeOptions node_options;
58#if RCLCPP_VERSION_MAJOR >= 21
59 node_options.enable_logger_service(
true);
64using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;
79 rclcpp_lifecycle::State(
80 lifecycle_msgs::msg::State::PRIMARY_STATE_UNKNOWN, lifecycle_state_names::UNKNOWN)),
81 logger_(rclcpp::get_logger(
"hardware_component_interface"))
110 clock_ = params.
clock;
111 auto logger_copy = params.
logger;
112 logger_ = logger_copy.get_child(
119 async_thread_params.scheduling_policy =
122 async_thread_params.clock = params.
clock;
123 async_thread_params.logger = params.
logger;
127 get_logger(),
"Starting async handler with scheduler priority: %d and policy : %s",
129 async_thread_params.scheduling_policy.to_string().c_str());
130 async_handler_ = std::make_unique<realtime_tools::AsyncFunctionHandler<return_type>>();
131 const bool is_sensor_type = (info_.
type ==
"sensor");
132 async_handler_->init(
133 [
this, is_sensor_type](
const rclcpp::Time & time,
const rclcpp::Duration & period)
135 const auto read_start_time = std::chrono::steady_clock::now();
136 const auto ret_read =
read(time, period);
137 const auto read_end_time = std::chrono::steady_clock::now();
138 read_return_info_.store(ret_read, std::memory_order_release);
139 read_execution_time_.store(
140 std::chrono::duration_cast<std::chrono::nanoseconds>(read_end_time - read_start_time),
141 std::memory_order_release);
142 if (ret_read != return_type::OK)
150 const auto write_start_time = std::chrono::steady_clock::now();
151 const auto ret_write =
write(time, period);
152 const auto write_end_time = std::chrono::steady_clock::now();
153 write_return_info_.store(ret_write, std::memory_order_release);
154 write_execution_time_.store(
155 std::chrono::duration_cast<std::chrono::nanoseconds>(
156 write_end_time - write_start_time),
157 std::memory_order_release);
160 return return_type::OK;
162 async_thread_params);
163 async_handler_->start_thread();
166 if (
auto locked_executor = params.
executor.lock())
169 std::replace(node_name.begin(), node_name.end(),
'/',
'_');
170 hardware_component_node_ = std::make_shared<rclcpp::Node>(
171 node_name, params.
node_namespace, get_hardware_component_node_options());
172 locked_executor->add_node(hardware_component_node_->get_node_base_interface());
178 "Executor is not available during hardware component initialization for '%s'. Skipping "
183 double publish_rate = 0.0;
191 catch (
const std::invalid_argument &)
194 get_logger(),
"Invalid 'status_publish_rate' parameter. Using default %.1f Hz.",
199 if (publish_rate == 0.0)
203 "`status_publish_rate` is set to 0.0, hardware status publisher will not be created.");
207 control_msgs::msg::HardwareStatus status_msg_template;
210 RCLCPP_ERROR(
get_logger(),
"User-defined 'init_hardware_status_message' failed.");
211 return CallbackReturn::ERROR;
214 if (!status_msg_template.hardware_device_states.empty())
216 if (!hardware_component_node_)
220 "Hardware status message was configured, but no node is available for the publisher. "
221 "Publisher will not be created.");
227 hardware_status_publisher_ =
228 hardware_component_node_->create_publisher<control_msgs::msg::HardwareStatus>(
229 "~/hardware_status", rclcpp::SystemDefaultsQoS());
231 hardware_status_timer_ = hardware_component_node_->create_wall_timer(
232 std::chrono::duration<double>(1.0 / publish_rate),
235 std::optional<control_msgs::msg::HardwareStatus> msg_to_publish_opt;
236 hardware_status_box_.
get(msg_to_publish_opt);
238 if (msg_to_publish_opt.has_value() && hardware_status_publisher_)
240 control_msgs::msg::HardwareStatus & msg = msg_to_publish_opt.value();
243 RCLCPP_WARN_THROTTLE(
245 "User's update_hardware_status_message() failed for '%s'.",
249 msg.header.stamp = this->
get_clock()->now();
250 hardware_status_publisher_->publish(msg);
253 hardware_status_box_.
set(std::make_optional(status_msg_template));
255 catch (
const std::exception & e)
258 get_logger(),
"Exception during publisher/timer setup for hardware status: %s",
260 return CallbackReturn::ERROR;
268 "`status_publish_rate` was set to a non-zero value, but no hardware status message was "
269 "configured. Publisher will not be created. Are you sure "
270 "init_hardware_status_message() is set up properly?");
277 return on_init(interface_params);
291 control_msgs::msg::HardwareStatus & )
294 return CallbackReturn::SUCCESS;
309 return return_type::OK;
326 if (info_.
type ==
"actuator")
331 else if (info_.
type ==
"sensor")
336 else if (info_.
type ==
"system")
344 return CallbackReturn::SUCCESS;
360 "Replaced by vector<StateInterface::ConstSharedPtr> on_export_state_interfaces() method. "
361 "Exporting is handled by the Framework.")]]
virtual std::vector<StateInterface>
376 virtual std::vector<hardware_interface::InterfaceDescription>
393 std::vector<hardware_interface::InterfaceDescription> unlisted_interface_descriptions =
396 std::vector<StateInterface::ConstSharedPtr> state_interfaces;
397 state_interfaces.reserve(
398 unlisted_interface_descriptions.size() + joint_state_interfaces_.size() +
399 sensor_state_interfaces_.size() + gpio_state_interfaces_.size());
403 for (
const auto & description : unlisted_interface_descriptions)
405 auto name = description.get_name();
406 unlisted_state_interfaces_.insert(std::make_pair(name, description));
407 auto state_interface = std::make_shared<StateInterface>(description);
408 hardware_states_.insert(std::make_pair(name, state_interface));
409 unlisted_states_.push_back(state_interface);
410 state_interfaces.push_back(std::const_pointer_cast<const StateInterface>(state_interface));
413 for (
const auto & [name, descr] : joint_state_interfaces_)
415 auto state_interface = std::make_shared<StateInterface>(descr);
416 hardware_states_.insert(std::make_pair(name, state_interface));
417 joint_states_.push_back(state_interface);
418 state_interfaces.push_back(std::const_pointer_cast<const StateInterface>(state_interface));
420 for (
const auto & [name, descr] : sensor_state_interfaces_)
422 auto state_interface = std::make_shared<StateInterface>(descr);
423 hardware_states_.insert(std::make_pair(name, state_interface));
424 sensor_states_.push_back(state_interface);
425 state_interfaces.push_back(std::const_pointer_cast<const StateInterface>(state_interface));
427 for (
const auto & [name, descr] : gpio_state_interfaces_)
429 auto state_interface = std::make_shared<StateInterface>(descr);
430 hardware_states_.insert(std::make_pair(name, state_interface));
431 gpio_states_.push_back(state_interface);
432 state_interfaces.push_back(std::const_pointer_cast<const StateInterface>(state_interface));
434 return state_interfaces;
450 "Replaced by vector<CommandInterface::SharedPtr> on_export_command_interfaces() method. "
451 "Exporting is handled by the Framework.")]]
virtual std::vector<CommandInterface>
466 virtual std::vector<hardware_interface::InterfaceDescription>
486 std::vector<hardware_interface::InterfaceDescription> unlisted_interface_descriptions =
489 std::vector<CommandInterface::SharedPtr> command_interfaces;
490 command_interfaces.reserve(
491 unlisted_interface_descriptions.size() + joint_command_interfaces_.size() +
492 gpio_command_interfaces_.size());
496 for (
const auto & description : unlisted_interface_descriptions)
498 auto name = description.get_name();
499 unlisted_command_interfaces_.insert(std::make_pair(name, description));
500 auto command_interface = std::make_shared<CommandInterface>(description);
501 hardware_commands_.insert(std::make_pair(name, command_interface));
502 unlisted_commands_.push_back(command_interface);
503 command_interfaces.push_back(command_interface);
506 for (
const auto & [name, descr] : joint_command_interfaces_)
508 auto command_interface = std::make_shared<CommandInterface>(descr);
509 hardware_commands_.insert(std::make_pair(name, command_interface));
510 joint_commands_.push_back(command_interface);
511 command_interfaces.push_back(command_interface);
514 for (
const auto & [name, descr] : gpio_command_interfaces_)
516 auto command_interface = std::make_shared<CommandInterface>(descr);
517 hardware_commands_.insert(std::make_pair(name, command_interface));
518 gpio_commands_.push_back(command_interface);
519 command_interfaces.push_back(command_interface);
521 return command_interfaces;
536 const std::vector<std::string> & ,
537 const std::vector<std::string> & )
539 return return_type::OK;
553 const std::vector<std::string> & ,
554 const std::vector<std::string> & )
556 return return_type::OK;
571 const rclcpp::Time & time,
const rclcpp::Duration & period)
574 status.result = return_type::ERROR;
577 status.result = read_return_info_.load(std::memory_order_acquire);
578 const auto read_exec_time = read_execution_time_.load(std::memory_order_acquire);
579 if (read_exec_time.count() > 0)
581 status.execution_time = read_exec_time;
583 const auto result = async_handler_->trigger_async_callback(time, period);
584 status.successful = result.first;
585 if (!status.successful)
587 RCLCPP_WARN_EXPRESSION(
589 "Trigger read/write called while the previous async trigger is still in progress for "
590 "hardware interface : '%s'. Failed to trigger read/write cycle!",
592 status.result = return_type::OK;
598 const auto start_time = std::chrono::steady_clock::now();
599 status.successful =
true;
600 status.result =
read(time, period);
601 status.execution_time = std::chrono::duration_cast<std::chrono::nanoseconds>(
602 std::chrono::steady_clock::now() - start_time);
617 virtual return_type
read(
const rclcpp::Time & time,
const rclcpp::Duration & period) = 0;
630 const rclcpp::Time & time,
const rclcpp::Duration & period)
633 status.result = return_type::ERROR;
636 status.successful =
true;
637 const auto write_exec_time = write_execution_time_.load(std::memory_order_acquire);
638 if (write_exec_time.count() > 0)
640 status.execution_time = write_exec_time;
642 status.result = write_return_info_.load(std::memory_order_acquire);
646 const auto start_time = std::chrono::steady_clock::now();
647 status.successful =
true;
648 status.result =
write(time, period);
649 status.execution_time = std::chrono::duration_cast<std::chrono::nanoseconds>(
650 std::chrono::steady_clock::now() - start_time);
664 virtual return_type
write(
const rclcpp::Time & ,
const rclcpp::Duration & )
666 return return_type::OK;
693 lifecycle_state_ = new_state;
701 bool has_state(
const std::string & interface_name)
const
703 return hardware_states_.find(interface_name) != hardware_states_.end();
714 template <
typename T>
715 void set_state(
const std::string & interface_name,
const T & value)
717 auto it = hardware_states_.find(interface_name);
718 if (it == hardware_states_.end())
720 throw std::runtime_error(
723 "State interface not found: {} in hardware component: {}. "
724 "This should not happen."),
725 interface_name, info_.
name));
727 auto & handle = it->second;
728 std::unique_lock<std::shared_mutex> lock(handle->get_mutex());
729 std::ignore = handle->set_value(lock, value);
740 template <
typename T =
double>
743 auto it = hardware_states_.find(interface_name);
744 if (it == hardware_states_.end())
746 throw std::runtime_error(
749 "State interface not found: {} in hardware component: {}. "
750 "This should not happen."),
751 interface_name, info_.
name));
753 auto & handle = it->second;
754 std::shared_lock<std::shared_mutex> lock(handle->get_mutex());
755 const auto opt_value = handle->get_optional<T>(lock);
758 throw std::runtime_error(
760 FMT_COMPILE(
"Failed to get state value from interface: {}. This should not happen."),
763 return opt_value.value();
773 return hardware_commands_.find(interface_name) != hardware_commands_.end();
785 template <
typename T>
786 void set_command(
const std::string & interface_name,
const T & value)
788 auto it = hardware_commands_.find(interface_name);
789 if (it == hardware_commands_.end())
791 throw std::runtime_error(
794 "Command interface not found: {} in hardware component: {}. "
795 "This should not happen."),
796 interface_name, info_.
name));
798 auto & handle = it->second;
799 std::unique_lock<std::shared_mutex> lock(handle->get_mutex());
800 std::ignore = handle->set_value(lock, value);
811 template <
typename T =
double>
814 auto it = hardware_commands_.find(interface_name);
815 if (it == hardware_commands_.end())
817 throw std::runtime_error(
820 "Command interface not found: {} in hardware component: {}. "
821 "This should not happen."),
822 interface_name, info_.
name));
824 auto & handle = it->second;
825 std::shared_lock<std::shared_mutex> lock(handle->get_mutex());
826 const auto opt_value = handle->get_optional<T>(lock);
829 throw std::runtime_error(
831 FMT_COMPILE(
"Failed to get command value from interface: {}. This should not happen."),
834 return opt_value.value();
847 rclcpp::Clock::SharedPtr
get_clock()
const {
return clock_; }
853 rclcpp::Node::SharedPtr
get_node()
const {
return hardware_component_node_; }
870 async_handler_->pause_execution();
880 read_return_info_.store(return_type::OK, std::memory_order_release);
881 read_execution_time_.store(std::chrono::nanoseconds::zero(), std::memory_order_release);
882 write_return_info_.store(return_type::OK, std::memory_order_release);
883 write_execution_time_.store(std::chrono::nanoseconds::zero(), std::memory_order_release);
894 stats_registrations_.enableAll();
898 stats_registrations_.disableAll();
905 std::unordered_map<std::string, InterfaceDescription> joint_state_interfaces_;
906 std::unordered_map<std::string, InterfaceDescription> joint_command_interfaces_;
908 std::unordered_map<std::string, InterfaceDescription> sensor_state_interfaces_;
910 std::unordered_map<std::string, InterfaceDescription> gpio_state_interfaces_;
911 std::unordered_map<std::string, InterfaceDescription> gpio_command_interfaces_;
913 std::unordered_map<std::string, InterfaceDescription> unlisted_state_interfaces_;
914 std::unordered_map<std::string, InterfaceDescription> unlisted_command_interfaces_;
916 rclcpp_lifecycle::State lifecycle_state_;
917 std::unique_ptr<realtime_tools::AsyncFunctionHandler<return_type>> async_handler_;
920 std::vector<StateInterface::SharedPtr> joint_states_;
921 std::vector<CommandInterface::SharedPtr> joint_commands_;
923 std::vector<StateInterface::SharedPtr> sensor_states_;
925 std::vector<StateInterface::SharedPtr> gpio_states_;
926 std::vector<CommandInterface::SharedPtr> gpio_commands_;
928 std::vector<StateInterface::SharedPtr> unlisted_states_;
929 std::vector<CommandInterface::SharedPtr> unlisted_commands_;
932 rclcpp::Clock::SharedPtr clock_;
933 rclcpp::Logger logger_;
934 rclcpp::Node::SharedPtr hardware_component_node_ =
nullptr;
936 std::unordered_map<std::string, StateInterface::SharedPtr> hardware_states_;
937 std::unordered_map<std::string, CommandInterface::SharedPtr> hardware_commands_;
938 std::atomic<return_type> read_return_info_ = return_type::OK;
939 std::atomic<std::chrono::nanoseconds> read_execution_time_ = std::chrono::nanoseconds::zero();
940 std::atomic<return_type> write_return_info_ = return_type::OK;
941 std::atomic<std::chrono::nanoseconds> write_execution_time_ = std::chrono::nanoseconds::zero();
944 pal_statistics::RegistrationsRAII stats_registrations_;
945 std::shared_ptr<rclcpp::Publisher<control_msgs::msg::HardwareStatus>> hardware_status_publisher_;
947 hardware_status_box_;
948 rclcpp::TimerBase::SharedPtr hardware_status_timer_;
Virtual base class for all hardware components (Actuators, Sensors, and Systems).
Definition hardware_component_interface.hpp:75
const std::string & get_name() const
Get name of the hardware.
Definition hardware_component_interface.hpp:673
void prepare_for_activation()
Prepare for the activation of the hardware.
Definition hardware_component_interface.hpp:878
T get_state(const std::string &interface_name) const
Get the value from a state interface.
Definition hardware_component_interface.hpp:741
virtual std::vector< StateInterface > export_state_interfaces()
Exports all state interfaces for this hardware interface.
Definition hardware_component_interface.hpp:362
const rclcpp_lifecycle::State & get_lifecycle_state() const
Get life-cycle state of the hardware.
Definition hardware_component_interface.hpp:685
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:664
virtual std::vector< StateInterface::ConstSharedPtr > on_export_state_interfaces()
Definition hardware_component_interface.hpp:390
virtual std::vector< hardware_interface::InterfaceDescription > export_unlisted_command_interface_descriptions()
Definition hardware_component_interface.hpp:467
virtual std::vector< hardware_interface::InterfaceDescription > export_unlisted_state_interface_descriptions()
Definition hardware_component_interface.hpp:377
void set_state(const std::string &interface_name, const T &value)
Set the value of a state interface.
Definition hardware_component_interface.hpp:715
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:570
void set_lifecycle_state(const rclcpp_lifecycle::State &new_state)
Set life-cycle state of the hardware.
Definition hardware_component_interface.hpp:691
virtual return_type perform_command_mode_switch(const std::vector< std::string > &, const std::vector< std::string > &)
Definition hardware_component_interface.hpp:552
bool has_command(const std::string &interface_name) const
Does the command interface exist?
Definition hardware_component_interface.hpp:771
void pause_async_operations()
Pause any asynchronous operations.
Definition hardware_component_interface.hpp:866
const std::string & get_group_name() const
Get name of the hardware group to which it belongs to.
Definition hardware_component_interface.hpp:679
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:629
virtual return_type update_hardware_status_message(control_msgs::msg::HardwareStatus &)
User-overridable method to fill the hardware status message with real-time data.
Definition hardware_component_interface.hpp:306
HardwareComponentInterface(const HardwareComponentInterface &other)=delete
HardwareComponentInterface copy constructor is actively deleted.
void set_command(const std::string &interface_name, const T &value)
Set the value of a command interface.
Definition hardware_component_interface.hpp:786
rclcpp::Node::SharedPtr get_node() const
Get the default node of the HardwareComponentInterface.
Definition hardware_component_interface.hpp:853
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:535
CallbackReturn init(const hardware_interface::HardwareComponentParams ¶ms)
Definition hardware_component_interface.hpp:108
void enable_introspection(bool enable)
Enable or disable introspection of the hardware.
Definition hardware_component_interface.hpp:890
rclcpp::Logger get_logger() const
Get the logger of the HardwareComponentInterface.
Definition hardware_component_interface.hpp:841
T get_command(const std::string &interface_name) const
Get the value from a command interface.
Definition hardware_component_interface.hpp:812
virtual std::vector< CommandInterface > export_command_interfaces()
Exports all command interfaces for this hardware interface.
Definition hardware_component_interface.hpp:452
virtual std::vector< CommandInterface::SharedPtr > on_export_command_interfaces()
Definition hardware_component_interface.hpp:483
rclcpp::Clock::SharedPtr get_clock() const
Get the clock.
Definition hardware_component_interface.hpp:847
const HardwareInfo & get_hardware_info() const
Get the hardware info of the HardwareComponentInterface.
Definition hardware_component_interface.hpp:859
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:322
virtual CallbackReturn init_hardware_status_message(control_msgs::msg::HardwareStatus &)
User-overridable method to configure the structure of the HardwareStatus message.
Definition hardware_component_interface.hpp:290
bool has_state(const std::string &interface_name) const
Does the state interface exist?
Definition hardware_component_interface.hpp:701
Definition actuator.hpp:22
std::vector< InterfaceDescription > parse_command_interface_descriptions(const std::vector< ComponentInfo > &component_info)
Definition component_parser.cpp:1136
std::vector< InterfaceDescription > parse_state_interface_descriptions(const std::vector< ComponentInfo > &component_info)
Definition component_parser.cpp:1103
std::string to_lower_case(const std::string &string)
Convert a string to lower case.
Definition lexical_casts.cpp:65
double stod(const std::string &s)
Helper function to convert a std::string to double in a locale-independent way.
Definition lexical_casts.cpp:56
bool print_warnings
Whether to print warnings when the async thread doesn't meet its deadline.
Definition hardware_info.hpp:259
std::string scheduling_policy
Scheduling policy for the async worker thread.
Definition hardware_info.hpp:255
int thread_priority
Thread priority for the async worker thread.
Definition hardware_info.hpp:253
std::vector< int > cpu_affinity_cores
CPU affinity cores for the async worker thread.
Definition hardware_info.hpp:257
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:33
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:64
std::string node_namespace
The namespace used by the hardware component's internal node. This is typically same as the controlle...
Definition hardware_component_params.hpp:57
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:271
std::string type
Type of the hardware: actuator, sensor or system.
Definition hardware_info.hpp:275
HardwareAsyncParams async_params
Async Parameters.
Definition hardware_info.hpp:285
std::unordered_map< std::string, std::string > hardware_parameters
(Optional) Key-value pairs for hardware parameters.
Definition hardware_info.hpp:289
std::string group
Hardware group to which the hardware belongs.
Definition hardware_info.hpp:277
bool is_async
Component is async.
Definition hardware_info.hpp:281
std::vector< ComponentInfo > gpios
Definition hardware_info.hpp:308
std::vector< ComponentInfo > joints
Definition hardware_info.hpp:294
std::string name
Name of the hardware.
Definition hardware_info.hpp:273
std::vector< ComponentInfo > sensors
Definition hardware_info.hpp:303
unsigned int rw_rate
Component's read and write rates in Hz.
Definition hardware_info.hpp:279