ros2_control - kilted
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
105 [[deprecated(
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)
109 {
111 params.hardware_info = hardware_info;
112 params.clock = clock;
113 params.logger = logger;
114 return init(params);
115 };
116
119
130 {
131 clock_ = params.clock;
132 logger_ = params.logger;
133 info_ = params.hardware_info;
134 if (params.hardware_info.is_async)
135 {
137 async_thread_params.thread_priority = info_.async_params.thread_priority;
138 async_thread_params.scheduling_policy =
140 async_thread_params.cpu_affinity_cores = info_.async_params.cpu_affinity_cores;
141 async_thread_params.clock = params.clock;
142 async_thread_params.logger = get_logger();
143 async_thread_params.exec_rate = params.hardware_info.rw_rate;
144 async_thread_params.print_warnings = info_.async_params.print_warnings;
145 RCLCPP_INFO(
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)
153 {
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)
162 {
163 return ret_read;
164 }
165 if (
166 !is_sensor_type && lifecycle_id_cache_.load(std::memory_order_acquire) ==
167 lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE)
168 {
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);
177 return ret_write;
178 }
179 return return_type::OK;
180 },
181 async_thread_params);
182 async_handler_->start_thread();
183 }
184
185 if (auto locked_executor = params.executor.lock())
186 {
187 std::string node_name = hardware_interface::to_lower_case(params.hardware_info.name);
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());
192 }
193 else
194 {
195 RCLCPP_WARN(
196 params.logger,
197 "Executor is not available during hardware component initialization for '%s'. Skipping "
198 "node creation!",
199 params.hardware_info.name.c_str());
200 }
201
202 double publish_rate = 0.0;
203 auto it = info_.hardware_parameters.find("status_publish_rate");
204 if (it != info_.hardware_parameters.end())
205 {
206 try
207 {
208 publish_rate = hardware_interface::stod(it->second);
209 }
210 catch (const std::invalid_argument &)
211 {
212 RCLCPP_WARN(
213 get_logger(), "Invalid 'status_publish_rate' parameter. Using default %.1f Hz.",
214 publish_rate);
215 }
216 }
217
218 if (publish_rate == 0.0)
219 {
220 RCLCPP_INFO(
221 get_logger(),
222 "`status_publish_rate` is set to 0.0, hardware status publisher will not be created.");
223 }
224 else
225 {
226 control_msgs::msg::HardwareStatus status_msg_template;
227 if (init_hardware_status_message(status_msg_template) != CallbackReturn::SUCCESS)
228 {
229 RCLCPP_ERROR(get_logger(), "User-defined 'init_hardware_status_message' failed.");
230 return CallbackReturn::ERROR;
231 }
232
233 if (!status_msg_template.hardware_device_states.empty())
234 {
235 if (!hardware_component_node_)
236 {
237 RCLCPP_WARN(
238 get_logger(),
239 "Hardware status message was configured, but no node is available for the publisher. "
240 "Publisher will not be created.");
241 }
242 else
243 {
244 try
245 {
246 hardware_status_publisher_ =
247 hardware_component_node_->create_publisher<control_msgs::msg::HardwareStatus>(
248 "~/hardware_status", rclcpp::SystemDefaultsQoS());
249
250 hardware_status_timer_ = hardware_component_node_->create_wall_timer(
251 std::chrono::duration<double>(1.0 / publish_rate),
252 [this]()
253 {
254 std::optional<control_msgs::msg::HardwareStatus> msg_to_publish_opt;
255 hardware_status_box_.get(msg_to_publish_opt);
256
257 if (msg_to_publish_opt.has_value() && hardware_status_publisher_)
258 {
259 control_msgs::msg::HardwareStatus & msg = msg_to_publish_opt.value();
260 if (update_hardware_status_message(msg) != return_type::OK)
261 {
262 RCLCPP_WARN_THROTTLE(
263 get_logger(), *clock_, 1000,
264 "User's update_hardware_status_message() failed for '%s'.",
265 info_.name.c_str());
266 return;
267 }
268 msg.header.stamp = this->get_clock()->now();
269 hardware_status_publisher_->publish(msg);
270 }
271 });
272 hardware_status_box_.set(std::make_optional(status_msg_template));
273 }
274 catch (const std::exception & e)
275 {
276 RCLCPP_ERROR(
277 get_logger(), "Exception during publisher/timer setup for hardware status: %s",
278 e.what());
279 return CallbackReturn::ERROR;
280 }
281 }
282 }
283 else
284 {
285 RCLCPP_WARN(
286 get_logger(),
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?");
290 }
291 }
292
294 interface_params.hardware_info = info_;
295 interface_params.executor = params.executor;
296 return on_init(interface_params);
297 };
298
300
309 virtual CallbackReturn init_hardware_status_message(
310 control_msgs::msg::HardwareStatus & /*msg_template*/)
311 {
312 // Default implementation does nothing, disabling the feature.
313 return CallbackReturn::SUCCESS;
314 }
315
317
325 virtual return_type update_hardware_status_message(control_msgs::msg::HardwareStatus & /*msg*/)
326 {
327 // Default implementation does nothing.
328 return return_type::OK;
329 }
330
332
337 [[deprecated(
338 "Use on_init(const HardwareComponentInterfaceParams & params) "
339 "instead.")]] virtual CallbackReturn
340 on_init(const HardwareInfo & hardware_info)
341 {
342 info_ = hardware_info;
343 if (info_.type == "actuator")
344 {
345 parse_state_interface_descriptions(info_.joints, joint_state_interfaces_);
346 parse_command_interface_descriptions(info_.joints, joint_command_interfaces_);
347 }
348 else if (info_.type == "sensor")
349 {
350 parse_state_interface_descriptions(info_.joints, joint_state_interfaces_);
351 parse_state_interface_descriptions(info_.sensors, sensor_state_interfaces_);
352 }
353 else if (info_.type == "system")
354 {
355 parse_state_interface_descriptions(info_.joints, joint_state_interfaces_);
356 parse_state_interface_descriptions(info_.sensors, sensor_state_interfaces_);
357 parse_state_interface_descriptions(info_.gpios, gpio_state_interfaces_);
358 parse_command_interface_descriptions(info_.joints, joint_command_interfaces_);
359 parse_command_interface_descriptions(info_.gpios, gpio_command_interfaces_);
360 }
361 return CallbackReturn::SUCCESS;
362 };
363
365
374 virtual CallbackReturn on_init(
376 {
377 // This is done for backward compatibility with the old on_init method.
378#pragma GCC diagnostic push
379#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
380 return on_init(params.hardware_info);
381#pragma GCC diagnostic pop
382 };
383
385
396 [[deprecated(
397 "Replaced by vector<StateInterface::ConstSharedPtr> on_export_state_interfaces() method. "
398 "Exporting is handled by the Framework.")]] virtual std::vector<StateInterface>
400 {
401 // return empty vector by default. For backward compatibility we try calling
402 // export_state_interfaces() and only when empty vector is returned call
403 // on_export_state_interfaces()
404 return {};
405 }
406
413 virtual std::vector<hardware_interface::InterfaceDescription>
415 {
416 // return empty vector by default.
417 return {};
418 }
419
427 virtual std::vector<StateInterface::ConstSharedPtr> on_export_state_interfaces()
428 {
429 // import the unlisted interfaces
430 std::vector<hardware_interface::InterfaceDescription> unlisted_interface_descriptions =
432
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());
437
438 // add InterfaceDescriptions and create the StateInterfaces from the descriptions and add to
439 // maps.
440 for (const auto & description : unlisted_interface_descriptions)
441 {
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));
448 }
449
450 for (const auto & [name, descr] : joint_state_interfaces_)
451 {
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));
456 }
457 for (const auto & [name, descr] : sensor_state_interfaces_)
458 {
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));
463 }
464 for (const auto & [name, descr] : gpio_state_interfaces_)
465 {
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));
470 }
471 return state_interfaces;
472 }
473
475
486 [[deprecated(
487 "Replaced by vector<CommandInterface::SharedPtr> on_export_command_interfaces() method. "
488 "Exporting is handled by the Framework.")]] virtual std::vector<CommandInterface>
490 {
491 // return empty vector by default. For backward compatibility we try calling
492 // export_command_interfaces() and only when empty vector is returned call
493 // on_export_command_interfaces()
494 return {};
495 }
496
503 virtual std::vector<hardware_interface::InterfaceDescription>
505 {
506 // return empty vector by default.
507 return {};
508 }
509
520 virtual std::vector<CommandInterface::SharedPtr> on_export_command_interfaces()
521 {
522 // import the unlisted interfaces
523 std::vector<hardware_interface::InterfaceDescription> unlisted_interface_descriptions =
525
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());
530
531 // add InterfaceDescriptions and create the CommandInterfaces from the descriptions and add to
532 // maps.
533 for (const auto & description : unlisted_interface_descriptions)
534 {
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);
541 }
542
543 for (const auto & [name, descr] : joint_command_interfaces_)
544 {
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);
549 }
550
551 for (const auto & [name, descr] : gpio_command_interfaces_)
552 {
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);
557 }
558 return command_interfaces;
559 }
560
562
572 virtual return_type prepare_command_mode_switch(
573 const std::vector<std::string> & /*start_interfaces*/,
574 const std::vector<std::string> & /*stop_interfaces*/)
575 {
576 return return_type::OK;
577 }
578
579 // Perform switching to the new command interface.
589 virtual return_type perform_command_mode_switch(
590 const std::vector<std::string> & /*start_interfaces*/,
591 const std::vector<std::string> & /*stop_interfaces*/)
592 {
593 return return_type::OK;
594 }
595
597
608 const rclcpp::Time & time, const rclcpp::Duration & period)
609 {
611 status.result = return_type::ERROR;
612 if (info_.is_async)
613 {
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)
617 {
618 status.execution_time = read_exec_time;
619 }
620 const auto result = async_handler_->trigger_async_callback(time, period);
621 status.successful = result.first;
622 if (!status.successful)
623 {
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!",
628 info_.name.c_str());
629 status.result = return_type::OK;
630 return status;
631 }
632 }
633 else
634 {
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);
640 }
641 return status;
642 }
643
645
654 virtual return_type read(const rclcpp::Time & time, const rclcpp::Duration & period) = 0;
655
657
667 const rclcpp::Time & time, const rclcpp::Duration & period)
668 {
670 status.result = return_type::ERROR;
671 if (info_.is_async)
672 {
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)
676 {
677 status.execution_time = write_exec_time;
678 }
679 status.result = write_return_info_.load(std::memory_order_acquire);
680 }
681 else
682 {
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);
688 }
689 return status;
690 }
691
693
701 virtual return_type write(const rclcpp::Time & /*time*/, const rclcpp::Duration & /*period*/)
702 {
703 return return_type::OK;
704 }
705
707
710 const std::string & get_name() const { return info_.name; }
711
713
716 const std::string & get_group_name() const { return info_.group; }
717
719
725 const rclcpp_lifecycle::State & get_lifecycle_state() const { return lifecycle_state_; }
726
728
734 void set_lifecycle_state(const rclcpp_lifecycle::State & new_state)
735 {
736 lifecycle_state_ = new_state;
737 lifecycle_id_cache_.store(new_state.id(), std::memory_order_release);
738 }
739
740 uint8_t get_lifecycle_id() const { return lifecycle_id_cache_.load(std::memory_order_acquire); }
741
743
747 bool has_state(const std::string & interface_name) const
748 {
749 return hardware_states_.find(interface_name) != hardware_states_.end();
750 }
751
753
759 const StateInterface::SharedPtr & get_state_interface_handle(
760 const std::string & interface_name) const
761 {
762 auto it = hardware_states_.find(interface_name);
763 if (it == hardware_states_.end())
764 {
765 throw std::runtime_error(
766 fmt::format(
767 "The requested state interface not found: '{}' in hardware component: '{}'.",
768 interface_name, info_.name));
769 }
770 return it->second;
771 }
772
774
784 template <typename T>
786 const StateInterface::SharedPtr & interface_handle, const T & value, bool wait_until_set)
787 {
788 if (!interface_handle)
789 {
790 throw std::runtime_error(
791 fmt::format(
792 "State interface handle is null in hardware component: {}, while calling set_state "
793 "method. This should not happen.",
794 info_.name));
795 }
796 return interface_handle->set_value(value, wait_until_set);
797 }
798
800
808 template <typename T>
809 void set_state(const std::string & interface_name, const T & value)
810 {
811 std::ignore = set_state(get_state_interface_handle(interface_name), value, true);
812 }
813
824 template <typename T>
826 const StateInterface::SharedPtr & interface_handle, T & state, bool wait_until_get) const
827 {
828 if (!interface_handle)
829 {
830 throw std::runtime_error(
831 fmt::format(
832 "State interface handle is null in hardware component: {}, while calling get_state "
833 "method. This should not happen.",
834 info_.name));
835 }
836 const bool success = interface_handle->get_value(state, wait_until_get);
837 if (!success && wait_until_get)
838 {
839 throw std::runtime_error(
840 fmt::format(
841 "Failed to get state value from interface: {} in hardware component: {}. This should "
842 "not happen.",
843 interface_handle->get_name(), info_.name));
844 }
845 return success;
846 }
847
849
857 template <typename T = double>
858 T get_state(const std::string & interface_name) const
859 {
860 T state;
861 get_state<T>(get_state_interface_handle(interface_name), state, true);
862 return state;
863 }
864
866
870 bool has_command(const std::string & interface_name) const
871 {
872 return hardware_commands_.find(interface_name) != hardware_commands_.end();
873 }
874
876
882 const CommandInterface::SharedPtr & get_command_interface_handle(
883 const std::string & interface_name) const
884 {
885 auto it = hardware_commands_.find(interface_name);
886 if (it == hardware_commands_.end())
887 {
888 throw std::runtime_error(
889 fmt::format(
890 "The requested command interface not found: '{}' in hardware component: '{}'.",
891 interface_name, info_.name));
892 }
893 return it->second;
894 }
895
897
906 template <typename T>
908 const CommandInterface::SharedPtr & interface_handle, const T & value, bool wait_until_set)
909 {
910 if (!interface_handle)
911 {
912 throw std::runtime_error(
913 fmt::format(
914 "Command interface handle is null in hardware component: {}, while calling set_command "
915 "method. This should not happen.",
916 info_.name));
917 }
918 return interface_handle->set_value(value, wait_until_set);
919 }
920
922
930 template <typename T>
931 void set_command(const std::string & interface_name, const T & value)
932 {
933 std::ignore = set_command(get_command_interface_handle(interface_name), value, true);
934 }
935
946 template <typename T>
948 const CommandInterface::SharedPtr & interface_handle, T & command, bool wait_until_get) const
949 {
950 if (!interface_handle)
951 {
952 throw std::runtime_error(
953 fmt::format(
954 "Command interface handle is null in hardware component: {}, while calling get_command "
955 "method. This should not happen.",
956 info_.name));
957 }
958 const bool success = interface_handle->get_value(command, wait_until_get);
959 if (!success && wait_until_get)
960 {
961 throw std::runtime_error(
962 fmt::format(
963 "Failed to get command value from interface: {} in hardware component: {}. This should "
964 "not happen.",
965 interface_handle->get_name(), info_.name));
966 }
967 return success;
968 }
969
971
979 template <typename T = double>
980 T get_command(const std::string & interface_name) const
981 {
982 T command;
983 get_command<T>(get_command_interface_handle(interface_name), command, true);
984 return command;
985 }
986
988
991 rclcpp::Logger get_logger() const { return logger_; }
992
994
997 rclcpp::Clock::SharedPtr get_clock() const { return clock_; }
998
1000
1003 rclcpp::Node::SharedPtr get_node() const { return hardware_component_node_; }
1004
1006
1009 const HardwareInfo & get_hardware_info() const { return info_; }
1010
1012
1017 {
1018 if (async_handler_)
1019 {
1020 async_handler_->pause_execution();
1021 }
1022 }
1023
1025
1029 {
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);
1034 }
1035
1037
1040 void enable_introspection(bool enable)
1041 {
1042 if (enable)
1043 {
1044 stats_registrations_.enableAll();
1045 }
1046 else
1047 {
1048 stats_registrations_.disableAll();
1049 }
1050 }
1051
1052protected:
1053 HardwareInfo info_;
1054 // interface names to InterfaceDescription
1055 std::unordered_map<std::string, InterfaceDescription> joint_state_interfaces_;
1056 std::unordered_map<std::string, InterfaceDescription> joint_command_interfaces_;
1057
1058 std::unordered_map<std::string, InterfaceDescription> sensor_state_interfaces_;
1059
1060 std::unordered_map<std::string, InterfaceDescription> gpio_state_interfaces_;
1061 std::unordered_map<std::string, InterfaceDescription> gpio_command_interfaces_;
1062
1063 std::unordered_map<std::string, InterfaceDescription> unlisted_state_interfaces_;
1064 std::unordered_map<std::string, InterfaceDescription> unlisted_command_interfaces_;
1065
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_;
1069
1070 // Exported Command- and StateInterfaces in order they are listed in the hardware description.
1071 std::vector<StateInterface::SharedPtr> joint_states_;
1072 std::vector<CommandInterface::SharedPtr> joint_commands_;
1073
1074 std::vector<StateInterface::SharedPtr> sensor_states_;
1075
1076 std::vector<StateInterface::SharedPtr> gpio_states_;
1077 std::vector<CommandInterface::SharedPtr> gpio_commands_;
1078
1079 std::vector<StateInterface::SharedPtr> unlisted_states_;
1080 std::vector<CommandInterface::SharedPtr> unlisted_commands_;
1081
1082private:
1083 rclcpp::Clock::SharedPtr clock_;
1084 rclcpp::Logger logger_;
1085 rclcpp::Node::SharedPtr hardware_component_node_ = nullptr;
1086 // interface names to Handle accessed through getters/setters
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();
1093
1094protected:
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_;
1100};
1101
1102} // namespace hardware_interface
1103#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: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 &params)
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 &params)
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
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: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
The AsyncFunctionHandlerParams struct is used to configure the AsyncFunctionHandler....
Definition async_function_handler.hpp:127