ros2_control - rolling
Loading...
Searching...
No Matches
hardware_component_interface.hpp
1// Copyright 2025 ros2_control Development Team
2//
3// Licensed under the Apache License, Version 2.0 (the "License");
4// you may not use this file except in compliance with the License.
5// You may obtain a copy of the License at
6//
7// http://www.apache.org/licenses/LICENSE-2.0
8//
9// Unless required by applicable law or agreed to in writing, software
10// distributed under the License is distributed on an "AS IS" BASIS,
11// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12// See the License for the specific language governing permissions and
13// limitations under the License.
14
15#ifndef HARDWARE_INTERFACE__HARDWARE_COMPONENT_INTERFACE_HPP_
16#define HARDWARE_INTERFACE__HARDWARE_COMPONENT_INTERFACE_HPP_
17
18#include <fmt/compile.h>
19
20#include <limits>
21#include <memory>
22#include <string>
23#include <unordered_map>
24#include <utility>
25#include <vector>
26
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"
50
51namespace hardware_interface
52{
53
54static inline rclcpp::NodeOptions get_hardware_component_node_options()
55{
56 rclcpp::NodeOptions node_options;
57// \note The versions conditioning is added here to support the source-compatibility with Humble
58#if RCLCPP_VERSION_MAJOR >= 21
59 node_options.enable_logger_service(true);
60#endif
61 return node_options;
62}
63
64using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;
65
74class HardwareComponentInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface
75{
76public:
78 : lifecycle_state_(
79 rclcpp_lifecycle::State(
80 lifecycle_msgs::msg::State::PRIMARY_STATE_UNKNOWN, lifecycle_state_names::UNKNOWN)),
81 logger_(rclcpp::get_logger("hardware_component_interface"))
82 {
83 }
84
86
91
93
94 virtual ~HardwareComponentInterface() = default;
95
98
109 {
110 clock_ = params.clock;
111 logger_ = params.logger;
112 info_ = params.hardware_info;
113 if (params.hardware_info.is_async)
114 {
116 async_thread_params.thread_priority = info_.async_params.thread_priority;
117 async_thread_params.scheduling_policy =
119 async_thread_params.cpu_affinity_cores = info_.async_params.cpu_affinity_cores;
120 async_thread_params.clock = params.clock;
121 async_thread_params.logger = get_logger();
122 async_thread_params.exec_rate = params.hardware_info.rw_rate;
123 async_thread_params.print_warnings = info_.async_params.print_warnings;
124 RCLCPP_INFO(
125 get_logger(), "Starting async handler with scheduler priority: %d and policy : %s",
127 async_thread_params.scheduling_policy.to_string().c_str());
128 async_handler_ = std::make_unique<realtime_tools::AsyncFunctionHandler<return_type>>();
129 const bool is_sensor_type = (info_.type == "sensor");
130 async_handler_->init(
131 [this, is_sensor_type](const rclcpp::Time & time, const rclcpp::Duration & period)
132 {
133 const auto read_start_time = std::chrono::steady_clock::now();
134 const auto ret_read = read(time, period);
135 const auto read_end_time = std::chrono::steady_clock::now();
136 read_return_info_.store(ret_read, std::memory_order_release);
137 read_execution_time_.store(
138 std::chrono::duration_cast<std::chrono::nanoseconds>(read_end_time - read_start_time),
139 std::memory_order_release);
140 if (ret_read != return_type::OK)
141 {
142 return ret_read;
143 }
144 if (
145 !is_sensor_type && lifecycle_id_cache_.load(std::memory_order_acquire) ==
146 lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE)
147 {
148 const auto write_start_time = std::chrono::steady_clock::now();
149 const auto ret_write = write(time, period);
150 const auto write_end_time = std::chrono::steady_clock::now();
151 write_return_info_.store(ret_write, std::memory_order_release);
152 write_execution_time_.store(
153 std::chrono::duration_cast<std::chrono::nanoseconds>(
154 write_end_time - write_start_time),
155 std::memory_order_release);
156 return ret_write;
157 }
158 return return_type::OK;
159 },
160 async_thread_params);
161 async_handler_->start_thread();
162 }
163
164 if (auto locked_executor = params.executor.lock())
165 {
166 std::string node_name = hardware_interface::to_lower_case(params.hardware_info.name);
167 std::replace(node_name.begin(), node_name.end(), '/', '_');
168 hardware_component_node_ = std::make_shared<rclcpp::Node>(
169 node_name, params.node_namespace, get_hardware_component_node_options());
170 locked_executor->add_node(hardware_component_node_->get_node_base_interface());
171 }
172 else
173 {
174 RCLCPP_WARN(
175 params.logger,
176 "Executor is not available during hardware component initialization for '%s'. Skipping "
177 "node creation!",
178 params.hardware_info.name.c_str());
179 }
180
181 double publish_rate = 0.0;
182 auto it = info_.hardware_parameters.find("status_publish_rate");
183 if (it != info_.hardware_parameters.end())
184 {
185 try
186 {
187 publish_rate = hardware_interface::stod(it->second);
188 }
189 catch (const std::invalid_argument &)
190 {
191 RCLCPP_WARN(
192 get_logger(), "Invalid 'status_publish_rate' parameter. Using default %.1f Hz.",
193 publish_rate);
194 }
195 }
196
197 if (publish_rate == 0.0)
198 {
199 RCLCPP_INFO(
200 get_logger(),
201 "`status_publish_rate` is set to 0.0, hardware status publisher will not be created.");
202 }
203 else
204 {
205 control_msgs::msg::HardwareStatus status_msg_template;
206 if (init_hardware_status_message(status_msg_template) != CallbackReturn::SUCCESS)
207 {
208 RCLCPP_ERROR(get_logger(), "User-defined 'init_hardware_status_message' failed.");
209 return CallbackReturn::ERROR;
210 }
211
212 if (!status_msg_template.hardware_device_states.empty())
213 {
214 if (!hardware_component_node_)
215 {
216 RCLCPP_WARN(
217 get_logger(),
218 "Hardware status message was configured, but no node is available for the publisher. "
219 "Publisher will not be created.");
220 }
221 else
222 {
223 try
224 {
225 hardware_status_publisher_ =
226 hardware_component_node_->create_publisher<control_msgs::msg::HardwareStatus>(
227 "~/hardware_status", rclcpp::SystemDefaultsQoS());
228
229 hardware_status_timer_ = hardware_component_node_->create_wall_timer(
230 std::chrono::duration<double>(1.0 / publish_rate),
231 [this]()
232 {
233 std::optional<control_msgs::msg::HardwareStatus> msg_to_publish_opt;
234 hardware_status_box_.get(msg_to_publish_opt);
235
236 if (msg_to_publish_opt.has_value() && hardware_status_publisher_)
237 {
238 control_msgs::msg::HardwareStatus & msg = msg_to_publish_opt.value();
239 if (update_hardware_status_message(msg) != return_type::OK)
240 {
241 RCLCPP_WARN_THROTTLE(
242 get_logger(), *clock_, 1000,
243 "User's update_hardware_status_message() failed for '%s'.",
244 info_.name.c_str());
245 return;
246 }
247 msg.header.stamp = this->get_clock()->now();
248 hardware_status_publisher_->publish(msg);
249 }
250 });
251 hardware_status_box_.set(std::make_optional(status_msg_template));
252 }
253 catch (const std::exception & e)
254 {
255 RCLCPP_ERROR(
256 get_logger(), "Exception during publisher/timer setup for hardware status: %s",
257 e.what());
258 return CallbackReturn::ERROR;
259 }
260 }
261 }
262 else
263 {
264 RCLCPP_WARN(
265 get_logger(),
266 "`status_publish_rate` was set to a non-zero value, but no hardware status message was "
267 "configured. Publisher will not be created. Are you sure "
268 "init_hardware_status_message() is set up properly?");
269 }
270 }
271
273 interface_params.hardware_info = info_;
274 interface_params.executor = params.executor;
275 return on_init(interface_params);
276 };
277
279
288 virtual CallbackReturn init_hardware_status_message(
289 control_msgs::msg::HardwareStatus & /*msg_template*/)
290 {
291 // Default implementation does nothing, disabling the feature.
292 return CallbackReturn::SUCCESS;
293 }
294
296
304 virtual return_type update_hardware_status_message(control_msgs::msg::HardwareStatus & /*msg*/)
305 {
306 // Default implementation does nothing.
307 return return_type::OK;
308 }
309
311
320 virtual CallbackReturn on_init(
322 {
323 info_ = params.hardware_info;
324 if (info_.type == "actuator")
325 {
326 parse_state_interface_descriptions(info_.joints, joint_state_interfaces_);
327 parse_command_interface_descriptions(info_.joints, joint_command_interfaces_);
328 }
329 else if (info_.type == "sensor")
330 {
331 parse_state_interface_descriptions(info_.joints, joint_state_interfaces_);
332 parse_state_interface_descriptions(info_.sensors, sensor_state_interfaces_);
333 }
334 else if (info_.type == "system")
335 {
336 parse_state_interface_descriptions(info_.joints, joint_state_interfaces_);
337 parse_state_interface_descriptions(info_.sensors, sensor_state_interfaces_);
338 parse_state_interface_descriptions(info_.gpios, gpio_state_interfaces_);
339 parse_command_interface_descriptions(info_.joints, joint_command_interfaces_);
340 parse_command_interface_descriptions(info_.gpios, gpio_command_interfaces_);
341 }
342 return CallbackReturn::SUCCESS;
343 };
344
346
357 [[deprecated(
358 "Replaced by vector<StateInterface::ConstSharedPtr> on_export_state_interfaces() method. "
359 "Exporting is handled by the Framework.")]] virtual std::vector<StateInterface>
361 {
362 // return empty vector by default. For backward compatibility we try calling
363 // export_state_interfaces() and only when empty vector is returned call
364 // on_export_state_interfaces()
365 return {};
366 }
367
374 virtual std::vector<hardware_interface::InterfaceDescription>
376 {
377 // return empty vector by default.
378 return {};
379 }
380
388 virtual std::vector<StateInterface::ConstSharedPtr> on_export_state_interfaces()
389 {
390 // import the unlisted interfaces
391 std::vector<hardware_interface::InterfaceDescription> unlisted_interface_descriptions =
393
394 std::vector<StateInterface::ConstSharedPtr> state_interfaces;
395 state_interfaces.reserve(
396 unlisted_interface_descriptions.size() + joint_state_interfaces_.size() +
397 sensor_state_interfaces_.size() + gpio_state_interfaces_.size());
398
399 // add InterfaceDescriptions and create the StateInterfaces from the descriptions and add to
400 // maps.
401 for (const auto & description : unlisted_interface_descriptions)
402 {
403 auto name = description.get_name();
404 unlisted_state_interfaces_.insert(std::make_pair(name, description));
405 auto state_interface = std::make_shared<StateInterface>(description);
406 hardware_states_.insert(std::make_pair(name, state_interface));
407 unlisted_states_.push_back(state_interface);
408 state_interfaces.push_back(std::const_pointer_cast<const StateInterface>(state_interface));
409 }
410
411 for (const auto & [name, descr] : joint_state_interfaces_)
412 {
413 auto state_interface = std::make_shared<StateInterface>(descr);
414 hardware_states_.insert(std::make_pair(name, state_interface));
415 joint_states_.push_back(state_interface);
416 state_interfaces.push_back(std::const_pointer_cast<const StateInterface>(state_interface));
417 }
418 for (const auto & [name, descr] : sensor_state_interfaces_)
419 {
420 auto state_interface = std::make_shared<StateInterface>(descr);
421 hardware_states_.insert(std::make_pair(name, state_interface));
422 sensor_states_.push_back(state_interface);
423 state_interfaces.push_back(std::const_pointer_cast<const StateInterface>(state_interface));
424 }
425 for (const auto & [name, descr] : gpio_state_interfaces_)
426 {
427 auto state_interface = std::make_shared<StateInterface>(descr);
428 hardware_states_.insert(std::make_pair(name, state_interface));
429 gpio_states_.push_back(state_interface);
430 state_interfaces.push_back(std::const_pointer_cast<const StateInterface>(state_interface));
431 }
432 return state_interfaces;
433 }
434
436
447 [[deprecated(
448 "Replaced by vector<CommandInterface::SharedPtr> on_export_command_interfaces() method. "
449 "Exporting is handled by the Framework.")]] virtual std::vector<CommandInterface>
451 {
452 // return empty vector by default. For backward compatibility we try calling
453 // export_command_interfaces() and only when empty vector is returned call
454 // on_export_command_interfaces()
455 return {};
456 }
457
464 virtual std::vector<hardware_interface::InterfaceDescription>
466 {
467 // return empty vector by default.
468 return {};
469 }
470
481 virtual std::vector<CommandInterface::SharedPtr> on_export_command_interfaces()
482 {
483 // import the unlisted interfaces
484 std::vector<hardware_interface::InterfaceDescription> unlisted_interface_descriptions =
486
487 std::vector<CommandInterface::SharedPtr> command_interfaces;
488 command_interfaces.reserve(
489 unlisted_interface_descriptions.size() + joint_command_interfaces_.size() +
490 gpio_command_interfaces_.size());
491
492 // add InterfaceDescriptions and create the CommandInterfaces from the descriptions and add to
493 // maps.
494 for (const auto & description : unlisted_interface_descriptions)
495 {
496 auto name = description.get_name();
497 unlisted_command_interfaces_.insert(std::make_pair(name, description));
498 auto command_interface = std::make_shared<CommandInterface>(description);
499 hardware_commands_.insert(std::make_pair(name, command_interface));
500 unlisted_commands_.push_back(command_interface);
501 command_interfaces.push_back(command_interface);
502 }
503
504 for (const auto & [name, descr] : joint_command_interfaces_)
505 {
506 auto command_interface = std::make_shared<CommandInterface>(descr);
507 hardware_commands_.insert(std::make_pair(name, command_interface));
508 joint_commands_.push_back(command_interface);
509 command_interfaces.push_back(command_interface);
510 }
511
512 for (const auto & [name, descr] : gpio_command_interfaces_)
513 {
514 auto command_interface = std::make_shared<CommandInterface>(descr);
515 hardware_commands_.insert(std::make_pair(name, command_interface));
516 gpio_commands_.push_back(command_interface);
517 command_interfaces.push_back(command_interface);
518 }
519 return command_interfaces;
520 }
521
523
533 virtual return_type prepare_command_mode_switch(
534 const std::vector<std::string> & /*start_interfaces*/,
535 const std::vector<std::string> & /*stop_interfaces*/)
536 {
537 return return_type::OK;
538 }
539
540 // Perform switching to the new command interface.
550 virtual return_type perform_command_mode_switch(
551 const std::vector<std::string> & /*start_interfaces*/,
552 const std::vector<std::string> & /*stop_interfaces*/)
553 {
554 return return_type::OK;
555 }
556
558
569 const rclcpp::Time & time, const rclcpp::Duration & period)
570 {
572 status.result = return_type::ERROR;
573 if (info_.is_async)
574 {
575 status.result = read_return_info_.load(std::memory_order_acquire);
576 const auto read_exec_time = read_execution_time_.load(std::memory_order_acquire);
577 if (read_exec_time.count() > 0)
578 {
579 status.execution_time = read_exec_time;
580 }
581 const auto result = async_handler_->trigger_async_callback(time, period);
582 status.successful = result.first;
583 if (!status.successful)
584 {
585 RCLCPP_WARN_EXPRESSION(
587 "Trigger read/write called while the previous async trigger is still in progress for "
588 "hardware interface : '%s'. Failed to trigger read/write cycle!",
589 info_.name.c_str());
590 status.result = return_type::OK;
591 return status;
592 }
593 }
594 else
595 {
596 const auto start_time = std::chrono::steady_clock::now();
597 status.successful = true;
598 status.result = read(time, period);
599 status.execution_time = std::chrono::duration_cast<std::chrono::nanoseconds>(
600 std::chrono::steady_clock::now() - start_time);
601 }
602 return status;
603 }
604
606
615 virtual return_type read(const rclcpp::Time & time, const rclcpp::Duration & period) = 0;
616
618
628 const rclcpp::Time & time, const rclcpp::Duration & period)
629 {
631 status.result = return_type::ERROR;
632 if (info_.is_async)
633 {
634 status.successful = true;
635 const auto write_exec_time = write_execution_time_.load(std::memory_order_acquire);
636 if (write_exec_time.count() > 0)
637 {
638 status.execution_time = write_exec_time;
639 }
640 status.result = write_return_info_.load(std::memory_order_acquire);
641 }
642 else
643 {
644 const auto start_time = std::chrono::steady_clock::now();
645 status.successful = true;
646 status.result = write(time, period);
647 status.execution_time = std::chrono::duration_cast<std::chrono::nanoseconds>(
648 std::chrono::steady_clock::now() - start_time);
649 }
650 return status;
651 }
652
654
662 virtual return_type write(const rclcpp::Time & /*time*/, const rclcpp::Duration & /*period*/)
663 {
664 return return_type::OK;
665 }
666
668
671 const std::string & get_name() const { return info_.name; }
672
674
677 const std::string & get_group_name() const { return info_.group; }
678
680
686 const rclcpp_lifecycle::State & get_lifecycle_state() const { return lifecycle_state_; }
687
689
695 void set_lifecycle_state(const rclcpp_lifecycle::State & new_state)
696 {
697 lifecycle_state_ = new_state;
698 lifecycle_id_cache_.store(new_state.id(), std::memory_order_release);
699 }
700
701 uint8_t get_lifecycle_id() const { return lifecycle_id_cache_.load(std::memory_order_acquire); }
702
704
708 bool has_state(const std::string & interface_name) const
709 {
710 return hardware_states_.find(interface_name) != hardware_states_.end();
711 }
712
714
720 const StateInterface::SharedPtr & get_state_interface_handle(
721 const std::string & interface_name) const
722 {
723 auto it = hardware_states_.find(interface_name);
724 if (it == hardware_states_.end())
725 {
726 throw std::runtime_error(
727 fmt::format(
728 "The requested state interface not found: '{}' in hardware component: '{}'.",
729 interface_name, info_.name));
730 }
731 return it->second;
732 }
733
735
745 template <typename T>
747 const StateInterface::SharedPtr & interface_handle, const T & value, bool wait_until_set)
748 {
749 if (!interface_handle)
750 {
751 throw std::runtime_error(
752 fmt::format(
753 "State interface handle is null in hardware component: {}, while calling set_state "
754 "method. This should not happen.",
755 info_.name));
756 }
757 return interface_handle->set_value(value, wait_until_set);
758 }
759
761
769 template <typename T>
770 void set_state(const std::string & interface_name, const T & value)
771 {
772 std::ignore = set_state(get_state_interface_handle(interface_name), value, true);
773 }
774
785 template <typename T>
787 const StateInterface::SharedPtr & interface_handle, T & state, bool wait_until_get) const
788 {
789 if (!interface_handle)
790 {
791 throw std::runtime_error(
792 fmt::format(
793 "State interface handle is null in hardware component: {}, while calling get_state "
794 "method. This should not happen.",
795 info_.name));
796 }
797 const bool success = interface_handle->get_value(state, wait_until_get);
798 if (!success && wait_until_get)
799 {
800 throw std::runtime_error(
801 fmt::format(
802 "Failed to get state value from interface: {} in hardware component: {}. This should "
803 "not happen.",
804 interface_handle->get_name(), info_.name));
805 }
806 return success;
807 }
808
810
818 template <typename T = double>
819 T get_state(const std::string & interface_name) const
820 {
821 T state;
822 get_state<T>(get_state_interface_handle(interface_name), state, true);
823 return state;
824 }
825
827
831 bool has_command(const std::string & interface_name) const
832 {
833 return hardware_commands_.find(interface_name) != hardware_commands_.end();
834 }
835
837
843 const CommandInterface::SharedPtr & get_command_interface_handle(
844 const std::string & interface_name) const
845 {
846 auto it = hardware_commands_.find(interface_name);
847 if (it == hardware_commands_.end())
848 {
849 throw std::runtime_error(
850 fmt::format(
851 "The requested command interface not found: '{}' in hardware component: '{}'.",
852 interface_name, info_.name));
853 }
854 return it->second;
855 }
856
858
867 template <typename T>
869 const CommandInterface::SharedPtr & interface_handle, const T & value, bool wait_until_set)
870 {
871 if (!interface_handle)
872 {
873 throw std::runtime_error(
874 fmt::format(
875 "Command interface handle is null in hardware component: {}, while calling set_command "
876 "method. This should not happen.",
877 info_.name));
878 }
879 return interface_handle->set_value(value, wait_until_set);
880 }
881
883
891 template <typename T>
892 void set_command(const std::string & interface_name, const T & value)
893 {
894 std::ignore = set_command(get_command_interface_handle(interface_name), value, true);
895 }
896
907 template <typename T>
909 const CommandInterface::SharedPtr & interface_handle, T & command, bool wait_until_get) const
910 {
911 if (!interface_handle)
912 {
913 throw std::runtime_error(
914 fmt::format(
915 "Command interface handle is null in hardware component: {}, while calling get_command "
916 "method. This should not happen.",
917 info_.name));
918 }
919 const bool success = interface_handle->get_value(command, wait_until_get);
920 if (!success && wait_until_get)
921 {
922 throw std::runtime_error(
923 fmt::format(
924 "Failed to get command value from interface: {} in hardware component: {}. This should "
925 "not happen.",
926 interface_handle->get_name(), info_.name));
927 }
928 return success;
929 }
930
932
940 template <typename T = double>
941 T get_command(const std::string & interface_name) const
942 {
943 T command;
944 get_command<T>(get_command_interface_handle(interface_name), command, true);
945 return command;
946 }
947
949
952 rclcpp::Logger get_logger() const { return logger_; }
953
955
958 rclcpp::Clock::SharedPtr get_clock() const { return clock_; }
959
961
964 rclcpp::Node::SharedPtr get_node() const { return hardware_component_node_; }
965
967
970 const HardwareInfo & get_hardware_info() const { return info_; }
971
973
978 {
979 if (async_handler_)
980 {
981 async_handler_->pause_execution();
982 }
983 }
984
986
990 {
991 read_return_info_.store(return_type::OK, std::memory_order_release);
992 read_execution_time_.store(std::chrono::nanoseconds::zero(), std::memory_order_release);
993 write_return_info_.store(return_type::OK, std::memory_order_release);
994 write_execution_time_.store(std::chrono::nanoseconds::zero(), std::memory_order_release);
995 }
996
998
1001 void enable_introspection(bool enable)
1002 {
1003 if (enable)
1004 {
1005 stats_registrations_.enableAll();
1006 }
1007 else
1008 {
1009 stats_registrations_.disableAll();
1010 }
1011 }
1012
1013protected:
1014 HardwareInfo info_;
1015 // interface names to InterfaceDescription
1016 std::unordered_map<std::string, InterfaceDescription> joint_state_interfaces_;
1017 std::unordered_map<std::string, InterfaceDescription> joint_command_interfaces_;
1018
1019 std::unordered_map<std::string, InterfaceDescription> sensor_state_interfaces_;
1020
1021 std::unordered_map<std::string, InterfaceDescription> gpio_state_interfaces_;
1022 std::unordered_map<std::string, InterfaceDescription> gpio_command_interfaces_;
1023
1024 std::unordered_map<std::string, InterfaceDescription> unlisted_state_interfaces_;
1025 std::unordered_map<std::string, InterfaceDescription> unlisted_command_interfaces_;
1026
1027 rclcpp_lifecycle::State lifecycle_state_;
1028 std::atomic<uint8_t> lifecycle_id_cache_ = lifecycle_msgs::msg::State::PRIMARY_STATE_UNKNOWN;
1029 std::unique_ptr<realtime_tools::AsyncFunctionHandler<return_type>> async_handler_;
1030
1031 // Exported Command- and StateInterfaces in order they are listed in the hardware description.
1032 std::vector<StateInterface::SharedPtr> joint_states_;
1033 std::vector<CommandInterface::SharedPtr> joint_commands_;
1034
1035 std::vector<StateInterface::SharedPtr> sensor_states_;
1036
1037 std::vector<StateInterface::SharedPtr> gpio_states_;
1038 std::vector<CommandInterface::SharedPtr> gpio_commands_;
1039
1040 std::vector<StateInterface::SharedPtr> unlisted_states_;
1041 std::vector<CommandInterface::SharedPtr> unlisted_commands_;
1042
1043private:
1044 rclcpp::Clock::SharedPtr clock_;
1045 rclcpp::Logger logger_;
1046 rclcpp::Node::SharedPtr hardware_component_node_ = nullptr;
1047 // interface names to Handle accessed through getters/setters
1048 std::unordered_map<std::string, StateInterface::SharedPtr> hardware_states_;
1049 std::unordered_map<std::string, CommandInterface::SharedPtr> hardware_commands_;
1050 std::atomic<return_type> read_return_info_ = return_type::OK;
1051 std::atomic<std::chrono::nanoseconds> read_execution_time_ = std::chrono::nanoseconds::zero();
1052 std::atomic<return_type> write_return_info_ = return_type::OK;
1053 std::atomic<std::chrono::nanoseconds> write_execution_time_ = std::chrono::nanoseconds::zero();
1054
1055protected:
1056 pal_statistics::RegistrationsRAII stats_registrations_;
1057 std::shared_ptr<rclcpp::Publisher<control_msgs::msg::HardwareStatus>> hardware_status_publisher_;
1059 hardware_status_box_;
1060 rclcpp::TimerBase::SharedPtr hardware_status_timer_;
1061};
1062
1063} // namespace hardware_interface
1064#endif // HARDWARE_INTERFACE__HARDWARE_COMPONENT_INTERFACE_HPP_
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:671
void prepare_for_activation()
Prepare for the activation of the hardware.
Definition hardware_component_interface.hpp:989
T get_state(const std::string &interface_name) const
Get the value from a state interface.
Definition hardware_component_interface.hpp:819
bool get_state(const StateInterface::SharedPtr &interface_handle, T &state, bool wait_until_get) const
Definition hardware_component_interface.hpp:786
virtual std::vector< StateInterface > export_state_interfaces()
Exports all state interfaces for this hardware interface.
Definition hardware_component_interface.hpp:360
const rclcpp_lifecycle::State & get_lifecycle_state() const
Get life-cycle state of the hardware.
Definition hardware_component_interface.hpp:686
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:662
virtual std::vector< StateInterface::ConstSharedPtr > on_export_state_interfaces()
Definition hardware_component_interface.hpp:388
virtual std::vector< hardware_interface::InterfaceDescription > export_unlisted_command_interface_descriptions()
Definition hardware_component_interface.hpp:465
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:868
virtual std::vector< hardware_interface::InterfaceDescription > export_unlisted_state_interface_descriptions()
Definition hardware_component_interface.hpp:375
void set_state(const std::string &interface_name, const T &value)
Set the value of a state interface.
Definition hardware_component_interface.hpp:770
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:568
void set_lifecycle_state(const rclcpp_lifecycle::State &new_state)
Set life-cycle state of the hardware.
Definition hardware_component_interface.hpp:695
virtual return_type perform_command_mode_switch(const std::vector< std::string > &, const std::vector< std::string > &)
Definition hardware_component_interface.hpp:550
bool has_command(const std::string &interface_name) const
Does the command interface exist?
Definition hardware_component_interface.hpp:831
void pause_async_operations()
Pause any asynchronous operations.
Definition hardware_component_interface.hpp:977
const std::string & get_group_name() const
Get name of the hardware group to which it belongs to.
Definition hardware_component_interface.hpp:677
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:627
bool get_command(const CommandInterface::SharedPtr &interface_handle, T &command, bool wait_until_get) const
Definition hardware_component_interface.hpp:908
const StateInterface::SharedPtr & get_state_interface_handle(const std::string &interface_name) const
Get the state interface handle.
Definition hardware_component_interface.hpp:720
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:304
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:746
void set_command(const std::string &interface_name, const T &value)
Set the value of a command interface.
Definition hardware_component_interface.hpp:892
rclcpp::Node::SharedPtr get_node() const
Get the default node of the HardwareComponentInterface.
Definition hardware_component_interface.hpp:964
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:533
CallbackReturn init(const hardware_interface::HardwareComponentParams &params)
Definition hardware_component_interface.hpp:108
void enable_introspection(bool enable)
Enable or disable introspection of the hardware.
Definition hardware_component_interface.hpp:1001
const CommandInterface::SharedPtr & get_command_interface_handle(const std::string &interface_name) const
Get the command interface handle.
Definition hardware_component_interface.hpp:843
rclcpp::Logger get_logger() const
Get the logger of the HardwareComponentInterface.
Definition hardware_component_interface.hpp:952
T get_command(const std::string &interface_name) const
Get the value from a command interface.
Definition hardware_component_interface.hpp:941
virtual std::vector< CommandInterface > export_command_interfaces()
Exports all command interfaces for this hardware interface.
Definition hardware_component_interface.hpp:450
virtual std::vector< CommandInterface::SharedPtr > on_export_command_interfaces()
Definition hardware_component_interface.hpp:481
rclcpp::Clock::SharedPtr get_clock() const
Get the clock.
Definition hardware_component_interface.hpp:958
const HardwareInfo & get_hardware_info() const
Get the hardware info of the HardwareComponentInterface.
Definition hardware_component_interface.hpp:970
virtual CallbackReturn on_init(const hardware_interface::HardwareComponentInterfaceParams &params)
Initialization of the hardware interface from data parsed from the robot's URDF.
Definition hardware_component_interface.hpp:320
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:288
bool has_state(const std::string &interface_name) const
Does the state interface exist?
Definition hardware_component_interface.hpp:708
Enum class to define the scheduling policy for the async worker thread. SYNCHRONIZED: The async worke...
Definition async_function_handler.hpp:50
Definition realtime_thread_safe_box.hpp:68
std::enable_if_t<!is_ptr_or_smart_ptr< U >, void > set(const T &value)
Wait until the mutex can be locked and set the content (RealtimeThreadSafeBox behavior)
Definition realtime_thread_safe_box.hpp:199
std::enable_if_t<!is_ptr_or_smart_ptr< U >, U > get() const
Wait until the mutex could be locked and get the content (RealtimeThreadSafeBox behaviour)
Definition realtime_thread_safe_box.hpp:256
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:285
std::string scheduling_policy
Scheduling policy for the async worker thread.
Definition hardware_info.hpp:281
int thread_priority
Thread priority for the async worker thread.
Definition hardware_info.hpp:279
std::vector< int > cpu_affinity_cores
CPU affinity cores for the async worker thread.
Definition hardware_info.hpp:283
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:297
std::string type
Type of the hardware: actuator, sensor or system.
Definition hardware_info.hpp:301
HardwareAsyncParams async_params
Async Parameters.
Definition hardware_info.hpp:311
std::unordered_map< std::string, std::string > hardware_parameters
(Optional) Key-value pairs for hardware parameters.
Definition hardware_info.hpp:315
std::string group
Hardware group to which the hardware belongs.
Definition hardware_info.hpp:303
bool is_async
Component is async.
Definition hardware_info.hpp:307
std::vector< ComponentInfo > gpios
Definition hardware_info.hpp:334
std::vector< ComponentInfo > joints
Definition hardware_info.hpp:320
std::string name
Name of the hardware.
Definition hardware_info.hpp:299
std::vector< ComponentInfo > sensors
Definition hardware_info.hpp:329
unsigned int rw_rate
Component's read and write rates in Hz.
Definition hardware_info.hpp:305
The AsyncFunctionHandlerParams struct is used to configure the AsyncFunctionHandler....
Definition async_function_handler.hpp:127