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"
51static inline rclcpp::NodeOptions get_hardware_component_node_options()
53 rclcpp::NodeOptions node_options;
55#if RCLCPP_VERSION_MAJOR >= 21
56 node_options.enable_logger_service(
true);
61using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;
76 rclcpp_lifecycle::State(
77 lifecycle_msgs::msg::State::PRIMARY_STATE_UNKNOWN, lifecycle_state_names::UNKNOWN)),
78 logger_(rclcpp::get_logger(
"hardware_component_interface"))
102 [[deprecated(
"Use init(HardwareInfo, rclcpp::Logger, rclcpp::Clock::SharedPtr) instead.")]]
104 const HardwareInfo & hardware_info, rclcpp::Logger logger,
105 rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock_interface)
107#pragma GCC diagnostic push
108#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
109 return this->
init(hardware_info, logger, clock_interface->get_clock());
110#pragma GCC diagnostic pop
123 "Replaced by CallbackReturn init(const hardware_interface::HardwareComponentParams & "
124 "params). Initialization is handled by the Framework.")]]
126 const HardwareInfo & hardware_info, rclcpp::Logger logger, rclcpp::Clock::SharedPtr clock)
130 params.
clock = clock;
149 clock_ = params.
clock;
156 async_thread_params.scheduling_policy =
159 async_thread_params.clock = params.
clock;
164 get_logger(),
"Starting async handler with scheduler priority: %d and policy : %s",
166 async_thread_params.scheduling_policy.to_string().c_str());
167 async_handler_ = std::make_unique<realtime_tools::AsyncFunctionHandler<return_type>>();
168 const bool is_sensor_type = (info_.
type ==
"sensor");
169 async_handler_->init(
170 [
this, is_sensor_type](
const rclcpp::Time & time,
const rclcpp::Duration & period)
172 const auto read_start_time = std::chrono::steady_clock::now();
173 const auto ret_read =
read(time, period);
174 const auto read_end_time = std::chrono::steady_clock::now();
175 read_return_info_.store(ret_read, std::memory_order_release);
176 read_execution_time_.store(
177 std::chrono::duration_cast<std::chrono::nanoseconds>(read_end_time - read_start_time),
178 std::memory_order_release);
179 if (ret_read != return_type::OK)
184 !is_sensor_type && lifecycle_id_cache_.load(std::memory_order_acquire) ==
185 lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE)
187 const auto write_start_time = std::chrono::steady_clock::now();
188 const auto ret_write =
write(time, period);
189 const auto write_end_time = std::chrono::steady_clock::now();
190 write_return_info_.store(ret_write, std::memory_order_release);
191 write_execution_time_.store(
192 std::chrono::duration_cast<std::chrono::nanoseconds>(
193 write_end_time - write_start_time),
194 std::memory_order_release);
197 return return_type::OK;
199 async_thread_params);
200 async_handler_->start_thread();
203 if (
auto locked_executor = params.
executor.lock())
206 std::replace(node_name.begin(), node_name.end(),
'/',
'_');
207 hardware_component_node_ = std::make_shared<rclcpp::Node>(
208 node_name, params.
node_namespace, get_hardware_component_node_options());
209 locked_executor->add_node(hardware_component_node_->get_node_base_interface());
215 "Executor is not available during hardware component initialization for '%s'. Skipping "
223 return on_init(interface_params);
232 [[deprecated(
"Use on_init(const HardwareComponentInterfaceParams & params) instead.")]]
235 info_ = hardware_info;
236 if (info_.
type ==
"actuator")
241 else if (info_.
type ==
"sensor")
246 else if (info_.
type ==
"system")
254 return CallbackReturn::SUCCESS;
271#pragma GCC diagnostic push
272#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
274#pragma GCC diagnostic pop
290 "Replaced by vector<StateInterface::ConstSharedPtr> on_export_state_interfaces() method. "
291 "Exporting is handled by the Framework.")]]
306 virtual std::vector<hardware_interface::InterfaceDescription>
323 std::vector<hardware_interface::InterfaceDescription> unlisted_interface_descriptions =
326 std::vector<StateInterface::ConstSharedPtr> state_interfaces;
327 state_interfaces.reserve(
328 unlisted_interface_descriptions.size() + joint_state_interfaces_.size() +
329 sensor_state_interfaces_.size() + gpio_state_interfaces_.size());
333 for (
const auto & description : unlisted_interface_descriptions)
335 auto name = description.get_name();
336 unlisted_state_interfaces_.insert(std::make_pair(name, description));
337 auto state_interface = std::make_shared<StateInterface>(description);
338 hardware_states_.insert(std::make_pair(name, state_interface));
339 unlisted_states_.push_back(state_interface);
340 state_interfaces.push_back(std::const_pointer_cast<const StateInterface>(state_interface));
343 for (
const auto & [name, descr] : joint_state_interfaces_)
345 auto state_interface = std::make_shared<StateInterface>(descr);
346 hardware_states_.insert(std::make_pair(name, state_interface));
347 joint_states_.push_back(state_interface);
348 state_interfaces.push_back(std::const_pointer_cast<const StateInterface>(state_interface));
350 for (
const auto & [name, descr] : sensor_state_interfaces_)
352 auto state_interface = std::make_shared<StateInterface>(descr);
353 hardware_states_.insert(std::make_pair(name, state_interface));
354 sensor_states_.push_back(state_interface);
355 state_interfaces.push_back(std::const_pointer_cast<const StateInterface>(state_interface));
357 for (
const auto & [name, descr] : gpio_state_interfaces_)
359 auto state_interface = std::make_shared<StateInterface>(descr);
360 hardware_states_.insert(std::make_pair(name, state_interface));
361 gpio_states_.push_back(state_interface);
362 state_interfaces.push_back(std::const_pointer_cast<const StateInterface>(state_interface));
364 return state_interfaces;
380 "Replaced by vector<CommandInterface::SharedPtr> on_export_command_interfaces() method. "
381 "Exporting is handled by the Framework.")]]
396 virtual std::vector<hardware_interface::InterfaceDescription>
416 std::vector<hardware_interface::InterfaceDescription> unlisted_interface_descriptions =
419 std::vector<CommandInterface::SharedPtr> command_interfaces;
420 command_interfaces.reserve(
421 unlisted_interface_descriptions.size() + joint_command_interfaces_.size() +
422 gpio_command_interfaces_.size());
426 for (
const auto & description : unlisted_interface_descriptions)
428 auto name = description.get_name();
429 unlisted_command_interfaces_.insert(std::make_pair(name, description));
430 auto command_interface = std::make_shared<CommandInterface>(description);
431 hardware_commands_.insert(std::make_pair(name, command_interface));
432 unlisted_commands_.push_back(command_interface);
433 command_interfaces.push_back(command_interface);
436 for (
const auto & [name, descr] : joint_command_interfaces_)
438 auto command_interface = std::make_shared<CommandInterface>(descr);
439 hardware_commands_.insert(std::make_pair(name, command_interface));
440 joint_commands_.push_back(command_interface);
441 command_interfaces.push_back(command_interface);
444 for (
const auto & [name, descr] : gpio_command_interfaces_)
446 auto command_interface = std::make_shared<CommandInterface>(descr);
447 hardware_commands_.insert(std::make_pair(name, command_interface));
448 gpio_commands_.push_back(command_interface);
449 command_interfaces.push_back(command_interface);
451 return command_interfaces;
466 const std::vector<std::string> & ,
467 const std::vector<std::string> & )
469 return return_type::OK;
483 const std::vector<std::string> & ,
484 const std::vector<std::string> & )
486 return return_type::OK;
501 const rclcpp::Time & time,
const rclcpp::Duration & period)
504 status.result = return_type::ERROR;
507 status.result = read_return_info_.load(std::memory_order_acquire);
508 const auto read_exec_time = read_execution_time_.load(std::memory_order_acquire);
509 if (read_exec_time.count() > 0)
511 status.execution_time = read_exec_time;
513 const auto result = async_handler_->trigger_async_callback(time, period);
514 status.successful = result.first;
515 if (!status.successful)
517 RCLCPP_WARN_EXPRESSION(
519 "Trigger read/write called while the previous async trigger is still in progress for "
520 "hardware interface : '%s'. Failed to trigger read/write cycle!",
522 status.result = return_type::OK;
528 const auto start_time = std::chrono::steady_clock::now();
529 status.successful =
true;
530 status.result =
read(time, period);
531 status.execution_time = std::chrono::duration_cast<std::chrono::nanoseconds>(
532 std::chrono::steady_clock::now() - start_time);
547 virtual return_type
read(
const rclcpp::Time & time,
const rclcpp::Duration & period) = 0;
560 const rclcpp::Time & time,
const rclcpp::Duration & period)
563 status.result = return_type::ERROR;
566 status.successful =
true;
567 const auto write_exec_time = write_execution_time_.load(std::memory_order_acquire);
568 if (write_exec_time.count() > 0)
570 status.execution_time = write_exec_time;
572 status.result = write_return_info_.load(std::memory_order_acquire);
576 const auto start_time = std::chrono::steady_clock::now();
577 status.successful =
true;
578 status.result =
write(time, period);
579 status.execution_time = std::chrono::duration_cast<std::chrono::nanoseconds>(
580 std::chrono::steady_clock::now() - start_time);
594 virtual return_type
write(
const rclcpp::Time & ,
const rclcpp::Duration & )
596 return return_type::OK;
629 lifecycle_state_ = new_state;
630 lifecycle_id_cache_.store(new_state.id(), std::memory_order_release);
633 uint8_t get_lifecycle_id()
const {
return lifecycle_id_cache_.load(std::memory_order_acquire); }
640 bool has_state(
const std::string & interface_name)
const
642 return hardware_states_.find(interface_name) != hardware_states_.end();
653 const std::string & interface_name)
const
655 auto it = hardware_states_.find(interface_name);
656 if (it == hardware_states_.end())
658 throw std::runtime_error(
660 "The requested state interface not found: '{}' in hardware component: '{}'.",
661 interface_name, info_.
name));
677 template <
typename T>
679 const StateInterface::SharedPtr & interface_handle,
const T & value,
bool wait_until_set)
681 if (!interface_handle)
683 throw std::runtime_error(
685 "State interface handle is null in hardware component: {}, while calling set_state "
686 "method. This should not happen.",
689 return interface_handle->set_value(value, wait_until_set);
701 template <
typename T>
702 void set_state(
const std::string & interface_name,
const T & value)
717 template <
typename T>
719 const StateInterface::SharedPtr & interface_handle, T & state,
bool wait_until_get)
const
721 if (!interface_handle)
723 throw std::runtime_error(
725 "State interface handle is null in hardware component: {}, while calling get_state "
726 "method. This should not happen.",
729 const bool success = interface_handle->get_value(state, wait_until_get);
730 if (!success && wait_until_get)
732 throw std::runtime_error(
734 "Failed to get state value from interface: {} in hardware component: {}. This should "
736 interface_handle->get_name(), info_.
name));
750 template <
typename T =
double>
765 return hardware_commands_.find(interface_name) != hardware_commands_.end();
776 const std::string & interface_name)
const
778 auto it = hardware_commands_.find(interface_name);
779 if (it == hardware_commands_.end())
781 throw std::runtime_error(
783 "The requested command interface not found: '{}' in hardware component: '{}'.",
784 interface_name, info_.
name));
799 template <
typename T>
801 const CommandInterface::SharedPtr & interface_handle,
const T & value,
bool wait_until_set)
803 if (!interface_handle)
805 throw std::runtime_error(
807 "Command interface handle is null in hardware component: {}, while calling set_command "
808 "method. This should not happen.",
811 return interface_handle->set_value(value, wait_until_set);
823 template <
typename T>
824 void set_command(
const std::string & interface_name,
const T & value)
839 template <
typename T>
841 const CommandInterface::SharedPtr & interface_handle, T & command,
bool wait_until_get)
const
843 if (!interface_handle)
845 throw std::runtime_error(
847 "Command interface handle is null in hardware component: {}, while calling get_command "
848 "method. This should not happen.",
851 const bool success = interface_handle->get_value(command, wait_until_get);
852 if (!success && wait_until_get)
854 throw std::runtime_error(
856 "Failed to get command value from interface: {} in hardware component: {}. This should "
858 interface_handle->get_name(), info_.
name));
872 template <
typename T =
double>
890 rclcpp::Clock::SharedPtr
get_clock()
const {
return clock_; }
896 rclcpp::Node::SharedPtr
get_node()
const {
return hardware_component_node_; }
913 async_handler_->pause_execution();
923 read_return_info_.store(return_type::OK, std::memory_order_release);
924 read_execution_time_.store(std::chrono::nanoseconds::zero(), std::memory_order_release);
925 write_return_info_.store(return_type::OK, std::memory_order_release);
926 write_execution_time_.store(std::chrono::nanoseconds::zero(), std::memory_order_release);
937 stats_registrations_.enableAll();
941 stats_registrations_.disableAll();
948 std::unordered_map<std::string, InterfaceDescription> joint_state_interfaces_;
949 std::unordered_map<std::string, InterfaceDescription> joint_command_interfaces_;
951 std::unordered_map<std::string, InterfaceDescription> sensor_state_interfaces_;
953 std::unordered_map<std::string, InterfaceDescription> gpio_state_interfaces_;
954 std::unordered_map<std::string, InterfaceDescription> gpio_command_interfaces_;
956 std::unordered_map<std::string, InterfaceDescription> unlisted_state_interfaces_;
957 std::unordered_map<std::string, InterfaceDescription> unlisted_command_interfaces_;
959 rclcpp_lifecycle::State lifecycle_state_;
960 std::atomic<uint8_t> lifecycle_id_cache_ = lifecycle_msgs::msg::State::PRIMARY_STATE_UNKNOWN;
961 std::unique_ptr<realtime_tools::AsyncFunctionHandler<return_type>> async_handler_;
964 std::vector<StateInterface::SharedPtr> joint_states_;
965 std::vector<CommandInterface::SharedPtr> joint_commands_;
967 std::vector<StateInterface::SharedPtr> sensor_states_;
969 std::vector<StateInterface::SharedPtr> gpio_states_;
970 std::vector<CommandInterface::SharedPtr> gpio_commands_;
972 std::vector<StateInterface::SharedPtr> unlisted_states_;
973 std::vector<CommandInterface::SharedPtr> unlisted_commands_;
976 rclcpp::Clock::SharedPtr clock_;
977 rclcpp::Logger logger_;
978 rclcpp::Node::SharedPtr hardware_component_node_ =
nullptr;
980 std::unordered_map<std::string, StateInterface::SharedPtr> hardware_states_;
981 std::unordered_map<std::string, CommandInterface::SharedPtr> hardware_commands_;
982 std::atomic<return_type> read_return_info_ = return_type::OK;
983 std::atomic<std::chrono::nanoseconds> read_execution_time_ = std::chrono::nanoseconds::zero();
984 std::atomic<return_type> write_return_info_ = return_type::OK;
985 std::atomic<std::chrono::nanoseconds> write_execution_time_ = std::chrono::nanoseconds::zero();
988 pal_statistics::RegistrationsRAII stats_registrations_;
Virtual base class for all hardware components (Actuators, Sensors, and Systems).
Definition hardware_component_interface.hpp:72
const std::string & get_name() const
Get name of the hardware.
Definition hardware_component_interface.hpp:603
void prepare_for_activation()
Prepare for the activation of the hardware.
Definition hardware_component_interface.hpp:921
T get_state(const std::string &interface_name) const
Get the value from a state interface.
Definition hardware_component_interface.hpp:751
bool get_state(const StateInterface::SharedPtr &interface_handle, T &state, bool wait_until_get) const
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:292
const rclcpp_lifecycle::State & get_lifecycle_state() const
Get life-cycle state of the hardware.
Definition hardware_component_interface.hpp:618
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:594
virtual std::vector< StateInterface::ConstSharedPtr > on_export_state_interfaces()
Definition hardware_component_interface.hpp:320
virtual std::vector< hardware_interface::InterfaceDescription > export_unlisted_command_interface_descriptions()
Definition hardware_component_interface.hpp:397
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:800
virtual std::vector< hardware_interface::InterfaceDescription > export_unlisted_state_interface_descriptions()
Definition hardware_component_interface.hpp:307
void set_state(const std::string &interface_name, const T &value)
Set the value of a state interface.
Definition hardware_component_interface.hpp:702
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:500
void set_lifecycle_state(const rclcpp_lifecycle::State &new_state)
Set life-cycle state of the hardware.
Definition hardware_component_interface.hpp:627
virtual return_type perform_command_mode_switch(const std::vector< std::string > &, const std::vector< std::string > &)
Definition hardware_component_interface.hpp:482
bool has_command(const std::string &interface_name) const
Does the command interface exist?
Definition hardware_component_interface.hpp:763
void pause_async_operations()
Pause any asynchronous operations.
Definition hardware_component_interface.hpp:909
const std::string & get_group_name() const
Get name of the hardware group to which it belongs to.
Definition hardware_component_interface.hpp:609
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:559
bool get_command(const CommandInterface::SharedPtr &interface_handle, T &command, bool wait_until_get) const
Definition hardware_component_interface.hpp:840
CallbackReturn init(const HardwareInfo &hardware_info, rclcpp::Logger logger, rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock_interface)
Definition hardware_component_interface.hpp:103
const StateInterface::SharedPtr & get_state_interface_handle(const std::string &interface_name) const
Get the state interface handle.
Definition hardware_component_interface.hpp:652
HardwareComponentInterface(const HardwareComponentInterface &other)=delete
HardwareComponentInterface copy constructor is actively deleted.
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:678
void set_command(const std::string &interface_name, const T &value)
Set the value of a command interface.
Definition hardware_component_interface.hpp:824
rclcpp::Node::SharedPtr get_node() const
Get the default node of the Interface.
Definition hardware_component_interface.hpp:896
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:465
CallbackReturn init(const hardware_interface::HardwareComponentParams ¶ms)
Definition hardware_component_interface.hpp:147
CallbackReturn init(const HardwareInfo &hardware_info, rclcpp::Logger logger, rclcpp::Clock::SharedPtr clock)
Definition hardware_component_interface.hpp:125
void enable_introspection(bool enable)
Enable or disable introspection of the hardware.
Definition hardware_component_interface.hpp:933
const CommandInterface::SharedPtr & get_command_interface_handle(const std::string &interface_name) const
Get the command interface handle.
Definition hardware_component_interface.hpp:775
rclcpp::Logger get_logger() const
Get the logger of the Interface.
Definition hardware_component_interface.hpp:884
T get_command(const std::string &interface_name) const
Get the value from a command interface.
Definition hardware_component_interface.hpp:873
virtual std::vector< CommandInterface > export_command_interfaces()
Exports all command interfaces for this hardware interface.
Definition hardware_component_interface.hpp:382
virtual std::vector< CommandInterface::SharedPtr > on_export_command_interfaces()
Definition hardware_component_interface.hpp:413
rclcpp::Clock::SharedPtr get_clock() const
Get the clock of the Interface.
Definition hardware_component_interface.hpp:890
const HardwareInfo & get_hardware_info() const
Get the hardware info of the Interface.
Definition hardware_component_interface.hpp:902
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:267
bool has_state(const std::string &interface_name) const
Does the state interface exist?
Definition hardware_component_interface.hpp:640
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:233
Definition actuator.hpp:22
std::vector< InterfaceDescription > parse_command_interface_descriptions(const std::vector< ComponentInfo > &component_info)
Definition component_parser.cpp:1109
std::vector< InterfaceDescription > parse_state_interface_descriptions(const std::vector< ComponentInfo > &component_info)
Definition component_parser.cpp:1076
std::string to_lower_case(const std::string &string)
Convert a string to lower case.
Definition lexical_casts.cpp:103
bool print_warnings
Whether to print warnings when the async thread doesn't meet its deadline.
Definition hardware_info.hpp:355
std::string scheduling_policy
Scheduling policy for the async worker thread.
Definition hardware_info.hpp:351
int thread_priority
Thread priority for the async worker thread.
Definition hardware_info.hpp:349
std::vector< int > cpu_affinity_cores
CPU affinity cores for the async worker thread.
Definition hardware_info.hpp:353
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:360
std::string type
Type of the hardware: actuator, sensor or system.
Definition hardware_info.hpp:364
HardwareAsyncParams async_params
Async Parameters.
Definition hardware_info.hpp:374
std::string group
Hardware group to which the hardware belongs.
Definition hardware_info.hpp:366
bool is_async
Component is async.
Definition hardware_info.hpp:370
std::vector< ComponentInfo > gpios
Definition hardware_info.hpp:397
std::vector< ComponentInfo > joints
Definition hardware_info.hpp:383
std::string name
Name of the hardware.
Definition hardware_info.hpp:362
std::vector< ComponentInfo > sensors
Definition hardware_info.hpp:392
unsigned int rw_rate
Component's read and write rates in Hz.
Definition hardware_info.hpp:368