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"))
106 "Replaced by CallbackReturn init(const hardware_interface::HardwareComponentParams & "
107 "params). Initialization is handled by the Framework.")]] CallbackReturn
108 init(
const HardwareInfo & hardware_info, rclcpp::Logger logger, rclcpp::Clock::SharedPtr clock)
112 params.
clock = clock;
131 clock_ = params.
clock;
138 async_thread_params.scheduling_policy =
141 async_thread_params.clock = params.
clock;
146 get_logger(),
"Starting async handler with scheduler priority: %d and policy : %s",
148 async_thread_params.scheduling_policy.to_string().c_str());
149 async_handler_ = std::make_unique<realtime_tools::AsyncFunctionHandler<return_type>>();
150 const bool is_sensor_type = (info_.
type ==
"sensor");
151 async_handler_->init(
152 [
this, is_sensor_type](
const rclcpp::Time & time,
const rclcpp::Duration & period)
154 const auto read_start_time = std::chrono::steady_clock::now();
155 const auto ret_read =
read(time, period);
156 const auto read_end_time = std::chrono::steady_clock::now();
157 read_return_info_.store(ret_read, std::memory_order_release);
158 read_execution_time_.store(
159 std::chrono::duration_cast<std::chrono::nanoseconds>(read_end_time - read_start_time),
160 std::memory_order_release);
161 if (ret_read != return_type::OK)
166 !is_sensor_type && lifecycle_id_cache_.load(std::memory_order_acquire) ==
167 lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE)
169 const auto write_start_time = std::chrono::steady_clock::now();
170 const auto ret_write =
write(time, period);
171 const auto write_end_time = std::chrono::steady_clock::now();
172 write_return_info_.store(ret_write, std::memory_order_release);
173 write_execution_time_.store(
174 std::chrono::duration_cast<std::chrono::nanoseconds>(
175 write_end_time - write_start_time),
176 std::memory_order_release);
179 return return_type::OK;
181 async_thread_params);
182 async_handler_->start_thread();
185 if (
auto locked_executor = params.
executor.lock())
188 std::replace(node_name.begin(), node_name.end(),
'/',
'_');
189 hardware_component_node_ = std::make_shared<rclcpp::Node>(
190 node_name, params.
node_namespace, get_hardware_component_node_options());
191 locked_executor->add_node(hardware_component_node_->get_node_base_interface());
197 "Executor is not available during hardware component initialization for '%s'. Skipping "
202 double publish_rate = 0.0;
210 catch (
const std::invalid_argument &)
213 get_logger(),
"Invalid 'status_publish_rate' parameter. Using default %.1f Hz.",
218 if (publish_rate == 0.0)
222 "`status_publish_rate` is set to 0.0, hardware status publisher will not be created.");
226 control_msgs::msg::HardwareStatus status_msg_template;
229 RCLCPP_ERROR(
get_logger(),
"User-defined 'init_hardware_status_message' failed.");
230 return CallbackReturn::ERROR;
233 if (!status_msg_template.hardware_device_states.empty())
235 if (!hardware_component_node_)
239 "Hardware status message was configured, but no node is available for the publisher. "
240 "Publisher will not be created.");
246 hardware_status_publisher_ =
247 hardware_component_node_->create_publisher<control_msgs::msg::HardwareStatus>(
248 "~/hardware_status", rclcpp::SystemDefaultsQoS());
250 hardware_status_timer_ = hardware_component_node_->create_wall_timer(
251 std::chrono::duration<double>(1.0 / publish_rate),
254 std::optional<control_msgs::msg::HardwareStatus> msg_to_publish_opt;
255 hardware_status_box_.
get(msg_to_publish_opt);
257 if (msg_to_publish_opt.has_value() && hardware_status_publisher_)
259 control_msgs::msg::HardwareStatus & msg = msg_to_publish_opt.value();
262 RCLCPP_WARN_THROTTLE(
264 "User's update_hardware_status_message() failed for '%s'.",
268 msg.header.stamp = this->
get_clock()->now();
269 hardware_status_publisher_->publish(msg);
272 hardware_status_box_.
set(std::make_optional(status_msg_template));
274 catch (
const std::exception & e)
277 get_logger(),
"Exception during publisher/timer setup for hardware status: %s",
279 return CallbackReturn::ERROR;
287 "`status_publish_rate` was set to a non-zero value, but no hardware status message was "
288 "configured. Publisher will not be created. Are you sure "
289 "init_hardware_status_message() is set up properly?");
296 return on_init(interface_params);
310 control_msgs::msg::HardwareStatus & )
313 return CallbackReturn::SUCCESS;
328 return return_type::OK;
338 "Use on_init(const HardwareComponentInterfaceParams & params) "
339 "instead.")]]
virtual CallbackReturn
342 info_ = hardware_info;
343 if (info_.
type ==
"actuator")
348 else if (info_.
type ==
"sensor")
353 else if (info_.
type ==
"system")
361 return CallbackReturn::SUCCESS;
378#pragma GCC diagnostic push
379#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
381#pragma GCC diagnostic pop
397 "Replaced by vector<StateInterface::ConstSharedPtr> on_export_state_interfaces() method. "
398 "Exporting is handled by the Framework.")]]
virtual std::vector<StateInterface>
413 virtual std::vector<hardware_interface::InterfaceDescription>
430 std::vector<hardware_interface::InterfaceDescription> unlisted_interface_descriptions =
433 std::vector<StateInterface::ConstSharedPtr> state_interfaces;
434 state_interfaces.reserve(
435 unlisted_interface_descriptions.size() + joint_state_interfaces_.size() +
436 sensor_state_interfaces_.size() + gpio_state_interfaces_.size());
440 for (
const auto & description : unlisted_interface_descriptions)
442 auto name = description.get_name();
443 unlisted_state_interfaces_.insert(std::make_pair(name, description));
444 auto state_interface = std::make_shared<StateInterface>(description);
445 hardware_states_.insert(std::make_pair(name, state_interface));
446 unlisted_states_.push_back(state_interface);
447 state_interfaces.push_back(std::const_pointer_cast<const StateInterface>(state_interface));
450 for (
const auto & [name, descr] : joint_state_interfaces_)
452 auto state_interface = std::make_shared<StateInterface>(descr);
453 hardware_states_.insert(std::make_pair(name, state_interface));
454 joint_states_.push_back(state_interface);
455 state_interfaces.push_back(std::const_pointer_cast<const StateInterface>(state_interface));
457 for (
const auto & [name, descr] : sensor_state_interfaces_)
459 auto state_interface = std::make_shared<StateInterface>(descr);
460 hardware_states_.insert(std::make_pair(name, state_interface));
461 sensor_states_.push_back(state_interface);
462 state_interfaces.push_back(std::const_pointer_cast<const StateInterface>(state_interface));
464 for (
const auto & [name, descr] : gpio_state_interfaces_)
466 auto state_interface = std::make_shared<StateInterface>(descr);
467 hardware_states_.insert(std::make_pair(name, state_interface));
468 gpio_states_.push_back(state_interface);
469 state_interfaces.push_back(std::const_pointer_cast<const StateInterface>(state_interface));
471 return state_interfaces;
487 "Replaced by vector<CommandInterface::SharedPtr> on_export_command_interfaces() method. "
488 "Exporting is handled by the Framework.")]]
virtual std::vector<CommandInterface>
503 virtual std::vector<hardware_interface::InterfaceDescription>
523 std::vector<hardware_interface::InterfaceDescription> unlisted_interface_descriptions =
526 std::vector<CommandInterface::SharedPtr> command_interfaces;
527 command_interfaces.reserve(
528 unlisted_interface_descriptions.size() + joint_command_interfaces_.size() +
529 gpio_command_interfaces_.size());
533 for (
const auto & description : unlisted_interface_descriptions)
535 auto name = description.get_name();
536 unlisted_command_interfaces_.insert(std::make_pair(name, description));
537 auto command_interface = std::make_shared<CommandInterface>(description);
538 hardware_commands_.insert(std::make_pair(name, command_interface));
539 unlisted_commands_.push_back(command_interface);
540 command_interfaces.push_back(command_interface);
543 for (
const auto & [name, descr] : joint_command_interfaces_)
545 auto command_interface = std::make_shared<CommandInterface>(descr);
546 hardware_commands_.insert(std::make_pair(name, command_interface));
547 joint_commands_.push_back(command_interface);
548 command_interfaces.push_back(command_interface);
551 for (
const auto & [name, descr] : gpio_command_interfaces_)
553 auto command_interface = std::make_shared<CommandInterface>(descr);
554 hardware_commands_.insert(std::make_pair(name, command_interface));
555 gpio_commands_.push_back(command_interface);
556 command_interfaces.push_back(command_interface);
558 return command_interfaces;
573 const std::vector<std::string> & ,
574 const std::vector<std::string> & )
576 return return_type::OK;
590 const std::vector<std::string> & ,
591 const std::vector<std::string> & )
593 return return_type::OK;
608 const rclcpp::Time & time,
const rclcpp::Duration & period)
611 status.result = return_type::ERROR;
614 status.result = read_return_info_.load(std::memory_order_acquire);
615 const auto read_exec_time = read_execution_time_.load(std::memory_order_acquire);
616 if (read_exec_time.count() > 0)
618 status.execution_time = read_exec_time;
620 const auto result = async_handler_->trigger_async_callback(time, period);
621 status.successful = result.first;
622 if (!status.successful)
624 RCLCPP_WARN_EXPRESSION(
626 "Trigger read/write called while the previous async trigger is still in progress for "
627 "hardware interface : '%s'. Failed to trigger read/write cycle!",
629 status.result = return_type::OK;
635 const auto start_time = std::chrono::steady_clock::now();
636 status.successful =
true;
637 status.result =
read(time, period);
638 status.execution_time = std::chrono::duration_cast<std::chrono::nanoseconds>(
639 std::chrono::steady_clock::now() - start_time);
654 virtual return_type
read(
const rclcpp::Time & time,
const rclcpp::Duration & period) = 0;
667 const rclcpp::Time & time,
const rclcpp::Duration & period)
670 status.result = return_type::ERROR;
673 status.successful =
true;
674 const auto write_exec_time = write_execution_time_.load(std::memory_order_acquire);
675 if (write_exec_time.count() > 0)
677 status.execution_time = write_exec_time;
679 status.result = write_return_info_.load(std::memory_order_acquire);
683 const auto start_time = std::chrono::steady_clock::now();
684 status.successful =
true;
685 status.result =
write(time, period);
686 status.execution_time = std::chrono::duration_cast<std::chrono::nanoseconds>(
687 std::chrono::steady_clock::now() - start_time);
701 virtual return_type
write(
const rclcpp::Time & ,
const rclcpp::Duration & )
703 return return_type::OK;
736 lifecycle_state_ = new_state;
737 lifecycle_id_cache_.store(new_state.id(), std::memory_order_release);
740 uint8_t get_lifecycle_id()
const {
return lifecycle_id_cache_.load(std::memory_order_acquire); }
747 bool has_state(
const std::string & interface_name)
const
749 return hardware_states_.find(interface_name) != hardware_states_.end();
760 const std::string & interface_name)
const
762 auto it = hardware_states_.find(interface_name);
763 if (it == hardware_states_.end())
765 throw std::runtime_error(
767 "The requested state interface not found: '{}' in hardware component: '{}'.",
768 interface_name, info_.
name));
784 template <
typename T>
786 const StateInterface::SharedPtr & interface_handle,
const T & value,
bool wait_until_set)
788 if (!interface_handle)
790 throw std::runtime_error(
792 "State interface handle is null in hardware component: {}, while calling set_state "
793 "method. This should not happen.",
796 return interface_handle->set_value(value, wait_until_set);
808 template <
typename T>
809 void set_state(
const std::string & interface_name,
const T & value)
824 template <
typename T>
826 const StateInterface::SharedPtr & interface_handle, T & state,
bool wait_until_get)
const
828 if (!interface_handle)
830 throw std::runtime_error(
832 "State interface handle is null in hardware component: {}, while calling get_state "
833 "method. This should not happen.",
836 const bool success = interface_handle->get_value(state, wait_until_get);
837 if (!success && wait_until_get)
839 throw std::runtime_error(
841 "Failed to get state value from interface: {} in hardware component: {}. This should "
843 interface_handle->get_name(), info_.
name));
857 template <
typename T =
double>
872 return hardware_commands_.find(interface_name) != hardware_commands_.end();
883 const std::string & interface_name)
const
885 auto it = hardware_commands_.find(interface_name);
886 if (it == hardware_commands_.end())
888 throw std::runtime_error(
890 "The requested command interface not found: '{}' in hardware component: '{}'.",
891 interface_name, info_.
name));
906 template <
typename T>
908 const CommandInterface::SharedPtr & interface_handle,
const T & value,
bool wait_until_set)
910 if (!interface_handle)
912 throw std::runtime_error(
914 "Command interface handle is null in hardware component: {}, while calling set_command "
915 "method. This should not happen.",
918 return interface_handle->set_value(value, wait_until_set);
930 template <
typename T>
931 void set_command(
const std::string & interface_name,
const T & value)
946 template <
typename T>
948 const CommandInterface::SharedPtr & interface_handle, T & command,
bool wait_until_get)
const
950 if (!interface_handle)
952 throw std::runtime_error(
954 "Command interface handle is null in hardware component: {}, while calling get_command "
955 "method. This should not happen.",
958 const bool success = interface_handle->get_value(command, wait_until_get);
959 if (!success && wait_until_get)
961 throw std::runtime_error(
963 "Failed to get command value from interface: {} in hardware component: {}. This should "
965 interface_handle->get_name(), info_.
name));
979 template <
typename T =
double>
997 rclcpp::Clock::SharedPtr
get_clock()
const {
return clock_; }
1003 rclcpp::Node::SharedPtr
get_node()
const {
return hardware_component_node_; }
1020 async_handler_->pause_execution();
1030 read_return_info_.store(return_type::OK, std::memory_order_release);
1031 read_execution_time_.store(std::chrono::nanoseconds::zero(), std::memory_order_release);
1032 write_return_info_.store(return_type::OK, std::memory_order_release);
1033 write_execution_time_.store(std::chrono::nanoseconds::zero(), std::memory_order_release);
1044 stats_registrations_.enableAll();
1048 stats_registrations_.disableAll();
1055 std::unordered_map<std::string, InterfaceDescription> joint_state_interfaces_;
1056 std::unordered_map<std::string, InterfaceDescription> joint_command_interfaces_;
1058 std::unordered_map<std::string, InterfaceDescription> sensor_state_interfaces_;
1060 std::unordered_map<std::string, InterfaceDescription> gpio_state_interfaces_;
1061 std::unordered_map<std::string, InterfaceDescription> gpio_command_interfaces_;
1063 std::unordered_map<std::string, InterfaceDescription> unlisted_state_interfaces_;
1064 std::unordered_map<std::string, InterfaceDescription> unlisted_command_interfaces_;
1066 rclcpp_lifecycle::State lifecycle_state_;
1067 std::atomic<uint8_t> lifecycle_id_cache_ = lifecycle_msgs::msg::State::PRIMARY_STATE_UNKNOWN;
1068 std::unique_ptr<realtime_tools::AsyncFunctionHandler<return_type>> async_handler_;
1071 std::vector<StateInterface::SharedPtr> joint_states_;
1072 std::vector<CommandInterface::SharedPtr> joint_commands_;
1074 std::vector<StateInterface::SharedPtr> sensor_states_;
1076 std::vector<StateInterface::SharedPtr> gpio_states_;
1077 std::vector<CommandInterface::SharedPtr> gpio_commands_;
1079 std::vector<StateInterface::SharedPtr> unlisted_states_;
1080 std::vector<CommandInterface::SharedPtr> unlisted_commands_;
1083 rclcpp::Clock::SharedPtr clock_;
1084 rclcpp::Logger logger_;
1085 rclcpp::Node::SharedPtr hardware_component_node_ =
nullptr;
1087 std::unordered_map<std::string, StateInterface::SharedPtr> hardware_states_;
1088 std::unordered_map<std::string, CommandInterface::SharedPtr> hardware_commands_;
1089 std::atomic<return_type> read_return_info_ = return_type::OK;
1090 std::atomic<std::chrono::nanoseconds> read_execution_time_ = std::chrono::nanoseconds::zero();
1091 std::atomic<return_type> write_return_info_ = return_type::OK;
1092 std::atomic<std::chrono::nanoseconds> write_execution_time_ = std::chrono::nanoseconds::zero();
1095 pal_statistics::RegistrationsRAII stats_registrations_;
1096 std::shared_ptr<rclcpp::Publisher<control_msgs::msg::HardwareStatus>> hardware_status_publisher_;
1098 hardware_status_box_;
1099 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:710
void prepare_for_activation()
Prepare for the activation of the hardware.
Definition hardware_component_interface.hpp:1028
T get_state(const std::string &interface_name) const
Get the value from a state interface.
Definition hardware_component_interface.hpp:858
bool get_state(const StateInterface::SharedPtr &interface_handle, T &state, bool wait_until_get) const
Definition hardware_component_interface.hpp:825
virtual std::vector< StateInterface > export_state_interfaces()
Exports all state interfaces for this hardware interface.
Definition hardware_component_interface.hpp:399
const rclcpp_lifecycle::State & get_lifecycle_state() const
Get life-cycle state of the hardware.
Definition hardware_component_interface.hpp:725
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:701
virtual std::vector< StateInterface::ConstSharedPtr > on_export_state_interfaces()
Definition hardware_component_interface.hpp:427
virtual std::vector< hardware_interface::InterfaceDescription > export_unlisted_command_interface_descriptions()
Definition hardware_component_interface.hpp:504
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:907
virtual std::vector< hardware_interface::InterfaceDescription > export_unlisted_state_interface_descriptions()
Definition hardware_component_interface.hpp:414
void set_state(const std::string &interface_name, const T &value)
Set the value of a state interface.
Definition hardware_component_interface.hpp:809
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:607
void set_lifecycle_state(const rclcpp_lifecycle::State &new_state)
Set life-cycle state of the hardware.
Definition hardware_component_interface.hpp:734
virtual return_type perform_command_mode_switch(const std::vector< std::string > &, const std::vector< std::string > &)
Definition hardware_component_interface.hpp:589
bool has_command(const std::string &interface_name) const
Does the command interface exist?
Definition hardware_component_interface.hpp:870
void pause_async_operations()
Pause any asynchronous operations.
Definition hardware_component_interface.hpp:1016
const std::string & get_group_name() const
Get name of the hardware group to which it belongs to.
Definition hardware_component_interface.hpp:716
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:666
bool get_command(const CommandInterface::SharedPtr &interface_handle, T &command, bool wait_until_get) const
Definition hardware_component_interface.hpp:947
const StateInterface::SharedPtr & get_state_interface_handle(const std::string &interface_name) const
Get the state interface handle.
Definition hardware_component_interface.hpp:759
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:325
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:785
void set_command(const std::string &interface_name, const T &value)
Set the value of a command interface.
Definition hardware_component_interface.hpp:931
rclcpp::Node::SharedPtr get_node() const
Get the default node of the HardwareComponentInterface.
Definition hardware_component_interface.hpp:1003
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:572
CallbackReturn init(const hardware_interface::HardwareComponentParams ¶ms)
Definition hardware_component_interface.hpp:129
CallbackReturn init(const HardwareInfo &hardware_info, rclcpp::Logger logger, rclcpp::Clock::SharedPtr clock)
Definition hardware_component_interface.hpp:108
void enable_introspection(bool enable)
Enable or disable introspection of the hardware.
Definition hardware_component_interface.hpp:1040
const CommandInterface::SharedPtr & get_command_interface_handle(const std::string &interface_name) const
Get the command interface handle.
Definition hardware_component_interface.hpp:882
rclcpp::Logger get_logger() const
Get the logger of the HardwareComponentInterface.
Definition hardware_component_interface.hpp:991
T get_command(const std::string &interface_name) const
Get the value from a command interface.
Definition hardware_component_interface.hpp:980
virtual std::vector< CommandInterface > export_command_interfaces()
Exports all command interfaces for this hardware interface.
Definition hardware_component_interface.hpp:489
virtual std::vector< CommandInterface::SharedPtr > on_export_command_interfaces()
Definition hardware_component_interface.hpp:520
rclcpp::Clock::SharedPtr get_clock() const
Get the clock.
Definition hardware_component_interface.hpp:997
const HardwareInfo & get_hardware_info() const
Get the hardware info of the HardwareComponentInterface.
Definition hardware_component_interface.hpp:1009
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:374
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:309
bool has_state(const std::string &interface_name) const
Does the state interface exist?
Definition hardware_component_interface.hpp:747
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:340
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
double stod(const std::string &s)
Helper function to convert a std::string to double in a locale-independent way.
Definition lexical_casts.cpp:85
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:376
std::unordered_map< std::string, std::string > hardware_parameters
(Optional) Key-value pairs for hardware parameters.
Definition hardware_info.hpp:380
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:399
std::vector< ComponentInfo > joints
Definition hardware_info.hpp:385
std::string name
Name of the hardware.
Definition hardware_info.hpp:362
std::vector< ComponentInfo > sensors
Definition hardware_info.hpp:394
unsigned int rw_rate
Component's read and write rates in Hz.
Definition hardware_info.hpp:368