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 auto logger_copy = params.logger;
133 logger_ = logger_copy.get_child(
134 "hardware_component." + params.hardware_info.type + "." + params.hardware_info.name);
135 info_ = params.hardware_info;
136 if (params.hardware_info.is_async)
137 {
139 async_thread_params.thread_priority = info_.async_params.thread_priority;
140 async_thread_params.scheduling_policy =
142 async_thread_params.cpu_affinity_cores = info_.async_params.cpu_affinity_cores;
143 async_thread_params.clock = params.clock;
144 async_thread_params.logger = params.logger;
145 async_thread_params.exec_rate = params.hardware_info.rw_rate;
146 async_thread_params.print_warnings = info_.async_params.print_warnings;
147 RCLCPP_INFO(
148 get_logger(), "Starting async handler with scheduler priority: %d and policy : %s",
150 async_thread_params.scheduling_policy.to_string().c_str());
151 async_handler_ = std::make_unique<realtime_tools::AsyncFunctionHandler<return_type>>();
152 const bool is_sensor_type = (info_.type == "sensor");
153 async_handler_->init(
154 [this, is_sensor_type](const rclcpp::Time & time, const rclcpp::Duration & period)
155 {
156 const auto read_start_time = std::chrono::steady_clock::now();
157 const auto ret_read = read(time, period);
158 const auto read_end_time = std::chrono::steady_clock::now();
159 read_return_info_.store(ret_read, std::memory_order_release);
160 read_execution_time_.store(
161 std::chrono::duration_cast<std::chrono::nanoseconds>(read_end_time - read_start_time),
162 std::memory_order_release);
163 if (ret_read != return_type::OK)
164 {
165 return ret_read;
166 }
167 if (
168 !is_sensor_type &&
169 this->get_lifecycle_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE)
170 {
171 const auto write_start_time = std::chrono::steady_clock::now();
172 const auto ret_write = write(time, period);
173 const auto write_end_time = std::chrono::steady_clock::now();
174 write_return_info_.store(ret_write, std::memory_order_release);
175 write_execution_time_.store(
176 std::chrono::duration_cast<std::chrono::nanoseconds>(
177 write_end_time - write_start_time),
178 std::memory_order_release);
179 return ret_write;
180 }
181 return return_type::OK;
182 },
183 async_thread_params);
184 async_handler_->start_thread();
185 }
186
187 if (auto locked_executor = params.executor.lock())
188 {
189 std::string node_name = hardware_interface::to_lower_case(params.hardware_info.name);
190 std::replace(node_name.begin(), node_name.end(), '/', '_');
191 hardware_component_node_ = std::make_shared<rclcpp::Node>(
192 node_name, params.node_namespace, get_hardware_component_node_options());
193 locked_executor->add_node(hardware_component_node_->get_node_base_interface());
194 }
195 else
196 {
197 RCLCPP_WARN(
198 params.logger,
199 "Executor is not available during hardware component initialization for '%s'. Skipping "
200 "node creation!",
201 params.hardware_info.name.c_str());
202 }
203
204 double publish_rate = 0.0;
205 auto it = info_.hardware_parameters.find("status_publish_rate");
206 if (it != info_.hardware_parameters.end())
207 {
208 try
209 {
210 publish_rate = hardware_interface::stod(it->second);
211 }
212 catch (const std::invalid_argument &)
213 {
214 RCLCPP_WARN(
215 get_logger(), "Invalid 'status_publish_rate' parameter. Using default %.1f Hz.",
216 publish_rate);
217 }
218 }
219
220 if (publish_rate == 0.0)
221 {
222 RCLCPP_INFO(
223 get_logger(),
224 "`status_publish_rate` is set to 0.0, hardware status publisher will not be created.");
225 }
226 else
227 {
228 control_msgs::msg::HardwareStatus status_msg_template;
229 if (init_hardware_status_message(status_msg_template) != CallbackReturn::SUCCESS)
230 {
231 RCLCPP_ERROR(get_logger(), "User-defined 'init_hardware_status_message' failed.");
232 return CallbackReturn::ERROR;
233 }
234
235 if (!status_msg_template.hardware_device_states.empty())
236 {
237 if (!hardware_component_node_)
238 {
239 RCLCPP_WARN(
240 get_logger(),
241 "Hardware status message was configured, but no node is available for the publisher. "
242 "Publisher will not be created.");
243 }
244 else
245 {
246 try
247 {
248 hardware_status_publisher_ =
249 hardware_component_node_->create_publisher<control_msgs::msg::HardwareStatus>(
250 "~/hardware_status", rclcpp::SystemDefaultsQoS());
251
252 hardware_status_timer_ = hardware_component_node_->create_wall_timer(
253 std::chrono::duration<double>(1.0 / publish_rate),
254 [this]()
255 {
256 std::optional<control_msgs::msg::HardwareStatus> msg_to_publish_opt;
257 hardware_status_box_.get(msg_to_publish_opt);
258
259 if (msg_to_publish_opt.has_value() && hardware_status_publisher_)
260 {
261 control_msgs::msg::HardwareStatus & msg = msg_to_publish_opt.value();
262 if (update_hardware_status_message(msg) != return_type::OK)
263 {
264 RCLCPP_WARN_THROTTLE(
265 get_logger(), *clock_, 1000,
266 "User's update_hardware_status_message() failed for '%s'.",
267 info_.name.c_str());
268 return;
269 }
270 msg.header.stamp = this->get_clock()->now();
271 hardware_status_publisher_->publish(msg);
272 }
273 });
274 hardware_status_box_.set(std::make_optional(status_msg_template));
275 }
276 catch (const std::exception & e)
277 {
278 RCLCPP_ERROR(
279 get_logger(), "Exception during publisher/timer setup for hardware status: %s",
280 e.what());
281 return CallbackReturn::ERROR;
282 }
283 }
284 }
285 else
286 {
287 RCLCPP_WARN(
288 get_logger(),
289 "`status_publish_rate` was set to a non-zero value, but no hardware status message was "
290 "configured. Publisher will not be created. Are you sure "
291 "init_hardware_status_message() is set up properly?");
292 }
293 }
294
296 interface_params.hardware_info = info_;
297 interface_params.executor = params.executor;
298 return on_init(interface_params);
299 };
300
302
311 virtual CallbackReturn init_hardware_status_message(
312 control_msgs::msg::HardwareStatus & /*msg_template*/)
313 {
314 // Default implementation does nothing, disabling the feature.
315 return CallbackReturn::SUCCESS;
316 }
317
319
327 virtual return_type update_hardware_status_message(control_msgs::msg::HardwareStatus & /*msg*/)
328 {
329 // Default implementation does nothing.
330 return return_type::OK;
331 }
332
334
339 [[deprecated(
340 "Use on_init(const HardwareComponentInterfaceParams & params) "
341 "instead.")]] virtual CallbackReturn
342 on_init(const HardwareInfo & hardware_info)
343 {
344 info_ = hardware_info;
345 if (info_.type == "actuator")
346 {
347 parse_state_interface_descriptions(info_.joints, joint_state_interfaces_);
348 parse_command_interface_descriptions(info_.joints, joint_command_interfaces_);
349 }
350 else if (info_.type == "sensor")
351 {
352 parse_state_interface_descriptions(info_.joints, joint_state_interfaces_);
353 parse_state_interface_descriptions(info_.sensors, sensor_state_interfaces_);
354 }
355 else if (info_.type == "system")
356 {
357 parse_state_interface_descriptions(info_.joints, joint_state_interfaces_);
358 parse_state_interface_descriptions(info_.sensors, sensor_state_interfaces_);
359 parse_state_interface_descriptions(info_.gpios, gpio_state_interfaces_);
360 parse_command_interface_descriptions(info_.joints, joint_command_interfaces_);
361 parse_command_interface_descriptions(info_.gpios, gpio_command_interfaces_);
362 }
363 return CallbackReturn::SUCCESS;
364 };
365
367
376 virtual CallbackReturn on_init(
378 {
379 // This is done for backward compatibility with the old on_init method.
380#pragma GCC diagnostic push
381#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
382 return on_init(params.hardware_info);
383#pragma GCC diagnostic pop
384 };
385
387
398 [[deprecated(
399 "Replaced by vector<StateInterface::ConstSharedPtr> on_export_state_interfaces() method. "
400 "Exporting is handled by the Framework.")]] virtual std::vector<StateInterface>
402 {
403 // return empty vector by default. For backward compatibility we try calling
404 // export_state_interfaces() and only when empty vector is returned call
405 // on_export_state_interfaces()
406 return {};
407 }
408
415 virtual std::vector<hardware_interface::InterfaceDescription>
417 {
418 // return empty vector by default.
419 return {};
420 }
421
429 virtual std::vector<StateInterface::ConstSharedPtr> on_export_state_interfaces()
430 {
431 // import the unlisted interfaces
432 std::vector<hardware_interface::InterfaceDescription> unlisted_interface_descriptions =
434
435 std::vector<StateInterface::ConstSharedPtr> state_interfaces;
436 state_interfaces.reserve(
437 unlisted_interface_descriptions.size() + joint_state_interfaces_.size() +
438 sensor_state_interfaces_.size() + gpio_state_interfaces_.size());
439
440 // add InterfaceDescriptions and create the StateInterfaces from the descriptions and add to
441 // maps.
442 for (const auto & description : unlisted_interface_descriptions)
443 {
444 auto name = description.get_name();
445 unlisted_state_interfaces_.insert(std::make_pair(name, description));
446 auto state_interface = std::make_shared<StateInterface>(description);
447 hardware_states_.insert(std::make_pair(name, state_interface));
448 unlisted_states_.push_back(state_interface);
449 state_interfaces.push_back(std::const_pointer_cast<const StateInterface>(state_interface));
450 }
451
452 for (const auto & [name, descr] : joint_state_interfaces_)
453 {
454 auto state_interface = std::make_shared<StateInterface>(descr);
455 hardware_states_.insert(std::make_pair(name, state_interface));
456 joint_states_.push_back(state_interface);
457 state_interfaces.push_back(std::const_pointer_cast<const StateInterface>(state_interface));
458 }
459 for (const auto & [name, descr] : sensor_state_interfaces_)
460 {
461 auto state_interface = std::make_shared<StateInterface>(descr);
462 hardware_states_.insert(std::make_pair(name, state_interface));
463 sensor_states_.push_back(state_interface);
464 state_interfaces.push_back(std::const_pointer_cast<const StateInterface>(state_interface));
465 }
466 for (const auto & [name, descr] : gpio_state_interfaces_)
467 {
468 auto state_interface = std::make_shared<StateInterface>(descr);
469 hardware_states_.insert(std::make_pair(name, state_interface));
470 gpio_states_.push_back(state_interface);
471 state_interfaces.push_back(std::const_pointer_cast<const StateInterface>(state_interface));
472 }
473 return state_interfaces;
474 }
475
477
488 [[deprecated(
489 "Replaced by vector<CommandInterface::SharedPtr> on_export_command_interfaces() method. "
490 "Exporting is handled by the Framework.")]] virtual std::vector<CommandInterface>
492 {
493 // return empty vector by default. For backward compatibility we try calling
494 // export_command_interfaces() and only when empty vector is returned call
495 // on_export_command_interfaces()
496 return {};
497 }
498
505 virtual std::vector<hardware_interface::InterfaceDescription>
507 {
508 // return empty vector by default.
509 return {};
510 }
511
522 virtual std::vector<CommandInterface::SharedPtr> on_export_command_interfaces()
523 {
524 // import the unlisted interfaces
525 std::vector<hardware_interface::InterfaceDescription> unlisted_interface_descriptions =
527
528 std::vector<CommandInterface::SharedPtr> command_interfaces;
529 command_interfaces.reserve(
530 unlisted_interface_descriptions.size() + joint_command_interfaces_.size() +
531 gpio_command_interfaces_.size());
532
533 // add InterfaceDescriptions and create the CommandInterfaces from the descriptions and add to
534 // maps.
535 for (const auto & description : unlisted_interface_descriptions)
536 {
537 auto name = description.get_name();
538 unlisted_command_interfaces_.insert(std::make_pair(name, description));
539 auto command_interface = std::make_shared<CommandInterface>(description);
540 hardware_commands_.insert(std::make_pair(name, command_interface));
541 unlisted_commands_.push_back(command_interface);
542 command_interfaces.push_back(command_interface);
543 }
544
545 for (const auto & [name, descr] : joint_command_interfaces_)
546 {
547 auto command_interface = std::make_shared<CommandInterface>(descr);
548 hardware_commands_.insert(std::make_pair(name, command_interface));
549 joint_commands_.push_back(command_interface);
550 command_interfaces.push_back(command_interface);
551 }
552
553 for (const auto & [name, descr] : gpio_command_interfaces_)
554 {
555 auto command_interface = std::make_shared<CommandInterface>(descr);
556 hardware_commands_.insert(std::make_pair(name, command_interface));
557 gpio_commands_.push_back(command_interface);
558 command_interfaces.push_back(command_interface);
559 }
560 return command_interfaces;
561 }
562
564
574 virtual return_type prepare_command_mode_switch(
575 const std::vector<std::string> & /*start_interfaces*/,
576 const std::vector<std::string> & /*stop_interfaces*/)
577 {
578 return return_type::OK;
579 }
580
581 // Perform switching to the new command interface.
591 virtual return_type perform_command_mode_switch(
592 const std::vector<std::string> & /*start_interfaces*/,
593 const std::vector<std::string> & /*stop_interfaces*/)
594 {
595 return return_type::OK;
596 }
597
599
610 const rclcpp::Time & time, const rclcpp::Duration & period)
611 {
613 status.result = return_type::ERROR;
614 if (info_.is_async)
615 {
616 status.result = read_return_info_.load(std::memory_order_acquire);
617 const auto read_exec_time = read_execution_time_.load(std::memory_order_acquire);
618 if (read_exec_time.count() > 0)
619 {
620 status.execution_time = read_exec_time;
621 }
622 const auto result = async_handler_->trigger_async_callback(time, period);
623 status.successful = result.first;
624 if (!status.successful)
625 {
626 RCLCPP_WARN_EXPRESSION(
628 "Trigger read/write called while the previous async trigger is still in progress for "
629 "hardware interface : '%s'. Failed to trigger read/write cycle!",
630 info_.name.c_str());
631 status.result = return_type::OK;
632 return status;
633 }
634 }
635 else
636 {
637 const auto start_time = std::chrono::steady_clock::now();
638 status.successful = true;
639 status.result = read(time, period);
640 status.execution_time = std::chrono::duration_cast<std::chrono::nanoseconds>(
641 std::chrono::steady_clock::now() - start_time);
642 }
643 return status;
644 }
645
647
656 virtual return_type read(const rclcpp::Time & time, const rclcpp::Duration & period) = 0;
657
659
669 const rclcpp::Time & time, const rclcpp::Duration & period)
670 {
672 status.result = return_type::ERROR;
673 if (info_.is_async)
674 {
675 status.successful = true;
676 const auto write_exec_time = write_execution_time_.load(std::memory_order_acquire);
677 if (write_exec_time.count() > 0)
678 {
679 status.execution_time = write_exec_time;
680 }
681 status.result = write_return_info_.load(std::memory_order_acquire);
682 }
683 else
684 {
685 const auto start_time = std::chrono::steady_clock::now();
686 status.successful = true;
687 status.result = write(time, period);
688 status.execution_time = std::chrono::duration_cast<std::chrono::nanoseconds>(
689 std::chrono::steady_clock::now() - start_time);
690 }
691 return status;
692 }
693
695
703 virtual return_type write(const rclcpp::Time & /*time*/, const rclcpp::Duration & /*period*/)
704 {
705 return return_type::OK;
706 }
707
709
712 const std::string & get_name() const { return info_.name; }
713
715
718 const std::string & get_group_name() const { return info_.group; }
719
721
724 const rclcpp_lifecycle::State & get_lifecycle_state() const { return lifecycle_state_; }
725
727
730 void set_lifecycle_state(const rclcpp_lifecycle::State & new_state)
731 {
732 lifecycle_state_ = new_state;
733 }
734
736
740 bool has_state(const std::string & interface_name) const
741 {
742 return hardware_states_.find(interface_name) != hardware_states_.end();
743 }
744
746
753 template <typename T>
754 void set_state(const std::string & interface_name, const T & value)
755 {
756 auto it = hardware_states_.find(interface_name);
757 if (it == hardware_states_.end())
758 {
759 throw std::runtime_error(
760 fmt::format(
761 FMT_COMPILE(
762 "State interface not found: {} in hardware component: {}. "
763 "This should not happen."),
764 interface_name, info_.name));
765 }
766 auto & handle = it->second;
767 std::unique_lock<std::shared_mutex> lock(handle->get_mutex());
768 std::ignore = handle->set_value(lock, value);
769 }
770
772
779 template <typename T = double>
780 T get_state(const std::string & interface_name) const
781 {
782 auto it = hardware_states_.find(interface_name);
783 if (it == hardware_states_.end())
784 {
785 throw std::runtime_error(
786 fmt::format(
787 FMT_COMPILE(
788 "State interface not found: {} in hardware component: {}. "
789 "This should not happen."),
790 interface_name, info_.name));
791 }
792 auto & handle = it->second;
793 std::shared_lock<std::shared_mutex> lock(handle->get_mutex());
794 const auto opt_value = handle->get_optional<T>(lock);
795 if (!opt_value)
796 {
797 throw std::runtime_error(
798 fmt::format(
799 FMT_COMPILE("Failed to get state value from interface: {}. This should not happen."),
800 interface_name));
801 }
802 return opt_value.value();
803 }
804
806
810 bool has_command(const std::string & interface_name) const
811 {
812 return hardware_commands_.find(interface_name) != hardware_commands_.end();
813 }
814
816
824 template <typename T>
825 void set_command(const std::string & interface_name, const T & value)
826 {
827 auto it = hardware_commands_.find(interface_name);
828 if (it == hardware_commands_.end())
829 {
830 throw std::runtime_error(
831 fmt::format(
832 FMT_COMPILE(
833 "Command interface not found: {} in hardware component: {}. "
834 "This should not happen."),
835 interface_name, info_.name));
836 }
837 auto & handle = it->second;
838 std::unique_lock<std::shared_mutex> lock(handle->get_mutex());
839 std::ignore = handle->set_value(lock, value);
840 }
841
843
850 template <typename T = double>
851 T get_command(const std::string & interface_name) const
852 {
853 auto it = hardware_commands_.find(interface_name);
854 if (it == hardware_commands_.end())
855 {
856 throw std::runtime_error(
857 fmt::format(
858 FMT_COMPILE(
859 "Command interface not found: {} in hardware component: {}. "
860 "This should not happen."),
861 interface_name, info_.name));
862 }
863 auto & handle = it->second;
864 std::shared_lock<std::shared_mutex> lock(handle->get_mutex());
865 const auto opt_value = handle->get_optional<T>(lock);
866 if (!opt_value)
867 {
868 throw std::runtime_error(
869 fmt::format(
870 FMT_COMPILE("Failed to get command value from interface: {}. This should not happen."),
871 interface_name));
872 }
873 return opt_value.value();
874 }
875
877
880 rclcpp::Logger get_logger() const { return logger_; }
881
883
886 rclcpp::Clock::SharedPtr get_clock() const { return clock_; }
887
889
892 rclcpp::Node::SharedPtr get_node() const { return hardware_component_node_; }
893
895
898 const HardwareInfo & get_hardware_info() const { return info_; }
899
901
906 {
907 if (async_handler_)
908 {
909 async_handler_->pause_execution();
910 }
911 }
912
914
918 {
919 read_return_info_.store(return_type::OK, std::memory_order_release);
920 read_execution_time_.store(std::chrono::nanoseconds::zero(), std::memory_order_release);
921 write_return_info_.store(return_type::OK, std::memory_order_release);
922 write_execution_time_.store(std::chrono::nanoseconds::zero(), std::memory_order_release);
923 }
924
926
929 void enable_introspection(bool enable)
930 {
931 if (enable)
932 {
933 stats_registrations_.enableAll();
934 }
935 else
936 {
937 stats_registrations_.disableAll();
938 }
939 }
940
941protected:
942 HardwareInfo info_;
943 // interface names to InterfaceDescription
944 std::unordered_map<std::string, InterfaceDescription> joint_state_interfaces_;
945 std::unordered_map<std::string, InterfaceDescription> joint_command_interfaces_;
946
947 std::unordered_map<std::string, InterfaceDescription> sensor_state_interfaces_;
948
949 std::unordered_map<std::string, InterfaceDescription> gpio_state_interfaces_;
950 std::unordered_map<std::string, InterfaceDescription> gpio_command_interfaces_;
951
952 std::unordered_map<std::string, InterfaceDescription> unlisted_state_interfaces_;
953 std::unordered_map<std::string, InterfaceDescription> unlisted_command_interfaces_;
954
955 rclcpp_lifecycle::State lifecycle_state_;
956 std::unique_ptr<realtime_tools::AsyncFunctionHandler<return_type>> async_handler_;
957
958 // Exported Command- and StateInterfaces in order they are listed in the hardware description.
959 std::vector<StateInterface::SharedPtr> joint_states_;
960 std::vector<CommandInterface::SharedPtr> joint_commands_;
961
962 std::vector<StateInterface::SharedPtr> sensor_states_;
963
964 std::vector<StateInterface::SharedPtr> gpio_states_;
965 std::vector<CommandInterface::SharedPtr> gpio_commands_;
966
967 std::vector<StateInterface::SharedPtr> unlisted_states_;
968 std::vector<CommandInterface::SharedPtr> unlisted_commands_;
969
970private:
971 rclcpp::Clock::SharedPtr clock_;
972 rclcpp::Logger logger_;
973 rclcpp::Node::SharedPtr hardware_component_node_ = nullptr;
974 // interface names to Handle accessed through getters/setters
975 std::unordered_map<std::string, StateInterface::SharedPtr> hardware_states_;
976 std::unordered_map<std::string, CommandInterface::SharedPtr> hardware_commands_;
977 std::atomic<return_type> read_return_info_ = return_type::OK;
978 std::atomic<std::chrono::nanoseconds> read_execution_time_ = std::chrono::nanoseconds::zero();
979 std::atomic<return_type> write_return_info_ = return_type::OK;
980 std::atomic<std::chrono::nanoseconds> write_execution_time_ = std::chrono::nanoseconds::zero();
981
982protected:
983 pal_statistics::RegistrationsRAII stats_registrations_;
984 std::shared_ptr<rclcpp::Publisher<control_msgs::msg::HardwareStatus>> hardware_status_publisher_;
986 hardware_status_box_;
987 rclcpp::TimerBase::SharedPtr hardware_status_timer_;
988};
989
990} // namespace hardware_interface
991#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:712
void prepare_for_activation()
Prepare for the activation of the hardware.
Definition hardware_component_interface.hpp:917
T get_state(const std::string &interface_name) const
Get the value from a state interface.
Definition hardware_component_interface.hpp:780
virtual std::vector< StateInterface > export_state_interfaces()
Exports all state interfaces for this hardware interface.
Definition hardware_component_interface.hpp:401
const rclcpp_lifecycle::State & get_lifecycle_state() const
Get life-cycle state of the hardware.
Definition hardware_component_interface.hpp:724
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:703
virtual std::vector< StateInterface::ConstSharedPtr > on_export_state_interfaces()
Definition hardware_component_interface.hpp:429
virtual std::vector< hardware_interface::InterfaceDescription > export_unlisted_command_interface_descriptions()
Definition hardware_component_interface.hpp:506
virtual std::vector< hardware_interface::InterfaceDescription > export_unlisted_state_interface_descriptions()
Definition hardware_component_interface.hpp:416
void set_state(const std::string &interface_name, const T &value)
Set the value of a state interface.
Definition hardware_component_interface.hpp:754
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:609
void set_lifecycle_state(const rclcpp_lifecycle::State &new_state)
Set life-cycle state of the hardware.
Definition hardware_component_interface.hpp:730
virtual return_type perform_command_mode_switch(const std::vector< std::string > &, const std::vector< std::string > &)
Definition hardware_component_interface.hpp:591
bool has_command(const std::string &interface_name) const
Does the command interface exist?
Definition hardware_component_interface.hpp:810
void pause_async_operations()
Pause any asynchronous operations.
Definition hardware_component_interface.hpp:905
const std::string & get_group_name() const
Get name of the hardware group to which it belongs to.
Definition hardware_component_interface.hpp:718
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:668
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:327
HardwareComponentInterface(const HardwareComponentInterface &other)=delete
HardwareComponentInterface copy constructor is actively deleted.
void set_command(const std::string &interface_name, const T &value)
Set the value of a command interface.
Definition hardware_component_interface.hpp:825
rclcpp::Node::SharedPtr get_node() const
Get the default node of the HardwareComponentInterface.
Definition hardware_component_interface.hpp:892
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:574
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:929
rclcpp::Logger get_logger() const
Get the logger of the HardwareComponentInterface.
Definition hardware_component_interface.hpp:880
T get_command(const std::string &interface_name) const
Get the value from a command interface.
Definition hardware_component_interface.hpp:851
virtual std::vector< CommandInterface > export_command_interfaces()
Exports all command interfaces for this hardware interface.
Definition hardware_component_interface.hpp:491
virtual std::vector< CommandInterface::SharedPtr > on_export_command_interfaces()
Definition hardware_component_interface.hpp:522
rclcpp::Clock::SharedPtr get_clock() const
Get the clock.
Definition hardware_component_interface.hpp:886
const HardwareInfo & get_hardware_info() const
Get the hardware info of the HardwareComponentInterface.
Definition hardware_component_interface.hpp:898
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:376
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:311
bool has_state(const std::string &interface_name) const
Does the state interface exist?
Definition hardware_component_interface.hpp:740
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:342
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:65
double stod(const std::string &s)
Helper function to convert a std::string to double in a locale-independent way.
Definition lexical_casts.cpp:56
bool print_warnings
Whether to print warnings when the async thread doesn't meet its deadline.
Definition hardware_info.hpp:259
std::string scheduling_policy
Scheduling policy for the async worker thread.
Definition hardware_info.hpp:255
int thread_priority
Thread priority for the async worker thread.
Definition hardware_info.hpp:253
std::vector< int > cpu_affinity_cores
CPU affinity cores for the async worker thread.
Definition hardware_info.hpp:257
Definition hardware_interface_return_values.hpp:41
Parameters required for the initialization of a specific hardware component plugin....
Definition hardware_component_interface_params.hpp:32
rclcpp::Executor::WeakPtr executor
Weak pointer to the rclcpp::Executor instance. Hardware components can use this (after locking) to ad...
Definition hardware_component_interface_params.hpp:46
hardware_interface::HardwareInfo hardware_info
Reference to the HardwareInfo struct for this specific component, parsed from the URDF....
Definition hardware_component_interface_params.hpp:39
Parameters required for the initialization of a specific hardware component plugin....
Definition hardware_component_params.hpp:33
rclcpp::Executor::WeakPtr executor
Weak pointer to the rclcpp::Executor instance. Hardware components can use this (after locking) to ad...
Definition hardware_component_params.hpp:64
std::string node_namespace
The namespace used by the hardware component's internal node. This is typically same as the controlle...
Definition hardware_component_params.hpp:57
rclcpp::Logger logger
A logger instance taken from resource manager.
Definition hardware_component_params.hpp:45
rclcpp::Clock::SharedPtr clock
Shared pointer to the rclcpp::Clock to be used by this hardware component. Typically,...
Definition hardware_component_params.hpp:51
hardware_interface::HardwareInfo hardware_info
Reference to the HardwareInfo struct for this specific component, parsed from the URDF....
Definition hardware_component_params.hpp:40
This structure stores information about hardware defined in a robot's URDF.
Definition hardware_info.hpp:264
std::string type
Type of the hardware: actuator, sensor or system.
Definition hardware_info.hpp:268
HardwareAsyncParams async_params
Async Parameters.
Definition hardware_info.hpp:280
std::unordered_map< std::string, std::string > hardware_parameters
(Optional) Key-value pairs for hardware parameters.
Definition hardware_info.hpp:284
std::string group
Hardware group to which the hardware belongs.
Definition hardware_info.hpp:270
bool is_async
Component is async.
Definition hardware_info.hpp:274
std::vector< ComponentInfo > gpios
Definition hardware_info.hpp:303
std::vector< ComponentInfo > joints
Definition hardware_info.hpp:289
std::string name
Name of the hardware.
Definition hardware_info.hpp:266
std::vector< ComponentInfo > sensors
Definition hardware_info.hpp:298
unsigned int rw_rate
Component's read and write rates in Hz.
Definition hardware_info.hpp:272
The AsyncFunctionHandlerParams struct is used to configure the AsyncFunctionHandler....
Definition async_function_handler.hpp:127