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
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 = params.hardware_info.name;
190 std::transform(
191 node_name.begin(), node_name.end(), node_name.begin(),
192 [](unsigned char c) { return std::tolower(c); });
193 std::replace(node_name.begin(), node_name.end(), '/', '_');
194 hardware_component_node_ =
195 std::make_shared<rclcpp::Node>(node_name, get_hardware_component_node_options());
196 locked_executor->add_node(hardware_component_node_->get_node_base_interface());
197 }
198 else
199 {
200 RCLCPP_WARN(
201 params.logger,
202 "Executor is not available during hardware component initialization for '%s'. Skipping "
203 "node creation!",
204 params.hardware_info.name.c_str());
205 }
206
207 double publish_rate = 0.0;
208 auto it = info_.hardware_parameters.find("status_publish_rate");
209 if (it != info_.hardware_parameters.end())
210 {
211 try
212 {
213 publish_rate = hardware_interface::stod(it->second);
214 }
215 catch (const std::invalid_argument &)
216 {
217 RCLCPP_WARN(
218 get_logger(), "Invalid 'status_publish_rate' parameter. Using default %.1f Hz.",
219 publish_rate);
220 }
221 }
222
223 if (publish_rate == 0.0)
224 {
225 RCLCPP_INFO(
226 get_logger(),
227 "`status_publish_rate` is set to 0.0, hardware status publisher will not be created.");
228 }
229 else
230 {
231 control_msgs::msg::HardwareStatus status_msg_template;
232 if (init_hardware_status_message(status_msg_template) != CallbackReturn::SUCCESS)
233 {
234 RCLCPP_ERROR(get_logger(), "User-defined 'init_hardware_status_message' failed.");
235 return CallbackReturn::ERROR;
236 }
237
238 if (!status_msg_template.hardware_device_states.empty())
239 {
240 if (!hardware_component_node_)
241 {
242 RCLCPP_WARN(
243 get_logger(),
244 "Hardware status message was configured, but no node is available for the publisher. "
245 "Publisher will not be created.");
246 }
247 else
248 {
249 try
250 {
251 hardware_status_publisher_ =
252 hardware_component_node_->create_publisher<control_msgs::msg::HardwareStatus>(
253 "~/hardware_status", rclcpp::SystemDefaultsQoS());
254
255 hardware_status_timer_ = hardware_component_node_->create_wall_timer(
256 std::chrono::duration<double>(1.0 / publish_rate),
257 [this]()
258 {
259 std::optional<control_msgs::msg::HardwareStatus> msg_to_publish_opt;
260 hardware_status_box_.get(msg_to_publish_opt);
261
262 if (msg_to_publish_opt.has_value() && hardware_status_publisher_)
263 {
264 control_msgs::msg::HardwareStatus & msg = msg_to_publish_opt.value();
265 if (update_hardware_status_message(msg) != return_type::OK)
266 {
267 RCLCPP_WARN_THROTTLE(
268 get_logger(), *clock_, 1000,
269 "User's update_hardware_status_message() failed for '%s'.",
270 info_.name.c_str());
271 return;
272 }
273 msg.header.stamp = this->get_clock()->now();
274 hardware_status_publisher_->publish(msg);
275 }
276 });
277 hardware_status_box_.set(std::make_optional(status_msg_template));
278 }
279 catch (const std::exception & e)
280 {
281 RCLCPP_ERROR(
282 get_logger(), "Exception during publisher/timer setup for hardware status: %s",
283 e.what());
284 return CallbackReturn::ERROR;
285 }
286 }
287 }
288 else
289 {
290 RCLCPP_WARN(
291 get_logger(),
292 "`status_publish_rate` was set to a non-zero value, but no hardware status message was "
293 "configured. Publisher will not be created. Are you sure "
294 "init_hardware_status_message() is set up properly?");
295 }
296 }
297
299 interface_params.hardware_info = info_;
300 interface_params.executor = params.executor;
301 return on_init(interface_params);
302 };
303
305
314 virtual CallbackReturn init_hardware_status_message(
315 control_msgs::msg::HardwareStatus & /*msg_template*/)
316 {
317 // Default implementation does nothing, disabling the feature.
318 return CallbackReturn::SUCCESS;
319 }
320
322
330 virtual return_type update_hardware_status_message(control_msgs::msg::HardwareStatus & /*msg*/)
331 {
332 // Default implementation does nothing.
333 return return_type::OK;
334 }
335
337
342 [[deprecated(
343 "Use on_init(const HardwareComponentInterfaceParams & params) "
344 "instead.")]] virtual CallbackReturn
345 on_init(const HardwareInfo & hardware_info)
346 {
347 info_ = hardware_info;
348 if (info_.type == "actuator")
349 {
350 parse_state_interface_descriptions(info_.joints, joint_state_interfaces_);
351 parse_command_interface_descriptions(info_.joints, joint_command_interfaces_);
352 }
353 else if (info_.type == "sensor")
354 {
355 parse_state_interface_descriptions(info_.joints, joint_state_interfaces_);
356 parse_state_interface_descriptions(info_.sensors, sensor_state_interfaces_);
357 }
358 else if (info_.type == "system")
359 {
360 parse_state_interface_descriptions(info_.joints, joint_state_interfaces_);
361 parse_state_interface_descriptions(info_.sensors, sensor_state_interfaces_);
362 parse_state_interface_descriptions(info_.gpios, gpio_state_interfaces_);
363 parse_command_interface_descriptions(info_.joints, joint_command_interfaces_);
364 parse_command_interface_descriptions(info_.gpios, gpio_command_interfaces_);
365 }
366 return CallbackReturn::SUCCESS;
367 };
368
370
379 virtual CallbackReturn on_init(
381 {
382 // This is done for backward compatibility with the old on_init method.
383#pragma GCC diagnostic push
384#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
385 return on_init(params.hardware_info);
386#pragma GCC diagnostic pop
387 };
388
390
401 [[deprecated(
402 "Replaced by vector<StateInterface::ConstSharedPtr> on_export_state_interfaces() method. "
403 "Exporting is handled by the Framework.")]] virtual std::vector<StateInterface>
405 {
406 // return empty vector by default. For backward compatibility we try calling
407 // export_state_interfaces() and only when empty vector is returned call
408 // on_export_state_interfaces()
409 return {};
410 }
411
418 virtual std::vector<hardware_interface::InterfaceDescription>
420 {
421 // return empty vector by default.
422 return {};
423 }
424
432 virtual std::vector<StateInterface::ConstSharedPtr> on_export_state_interfaces()
433 {
434 // import the unlisted interfaces
435 std::vector<hardware_interface::InterfaceDescription> unlisted_interface_descriptions =
437
438 std::vector<StateInterface::ConstSharedPtr> state_interfaces;
439 state_interfaces.reserve(
440 unlisted_interface_descriptions.size() + joint_state_interfaces_.size() +
441 sensor_state_interfaces_.size() + gpio_state_interfaces_.size());
442
443 // add InterfaceDescriptions and create the StateInterfaces from the descriptions and add to
444 // maps.
445 for (const auto & description : unlisted_interface_descriptions)
446 {
447 auto name = description.get_name();
448 unlisted_state_interfaces_.insert(std::make_pair(name, description));
449 auto state_interface = std::make_shared<StateInterface>(description);
450 hardware_states_.insert(std::make_pair(name, state_interface));
451 unlisted_states_.push_back(state_interface);
452 state_interfaces.push_back(std::const_pointer_cast<const StateInterface>(state_interface));
453 }
454
455 for (const auto & [name, descr] : joint_state_interfaces_)
456 {
457 auto state_interface = std::make_shared<StateInterface>(descr);
458 hardware_states_.insert(std::make_pair(name, state_interface));
459 joint_states_.push_back(state_interface);
460 state_interfaces.push_back(std::const_pointer_cast<const StateInterface>(state_interface));
461 }
462 for (const auto & [name, descr] : sensor_state_interfaces_)
463 {
464 auto state_interface = std::make_shared<StateInterface>(descr);
465 hardware_states_.insert(std::make_pair(name, state_interface));
466 sensor_states_.push_back(state_interface);
467 state_interfaces.push_back(std::const_pointer_cast<const StateInterface>(state_interface));
468 }
469 for (const auto & [name, descr] : gpio_state_interfaces_)
470 {
471 auto state_interface = std::make_shared<StateInterface>(descr);
472 hardware_states_.insert(std::make_pair(name, state_interface));
473 gpio_states_.push_back(state_interface);
474 state_interfaces.push_back(std::const_pointer_cast<const StateInterface>(state_interface));
475 }
476 return state_interfaces;
477 }
478
480
491 [[deprecated(
492 "Replaced by vector<CommandInterface::SharedPtr> on_export_command_interfaces() method. "
493 "Exporting is handled by the Framework.")]] virtual std::vector<CommandInterface>
495 {
496 // return empty vector by default. For backward compatibility we try calling
497 // export_command_interfaces() and only when empty vector is returned call
498 // on_export_command_interfaces()
499 return {};
500 }
501
508 virtual std::vector<hardware_interface::InterfaceDescription>
510 {
511 // return empty vector by default.
512 return {};
513 }
514
525 virtual std::vector<CommandInterface::SharedPtr> on_export_command_interfaces()
526 {
527 // import the unlisted interfaces
528 std::vector<hardware_interface::InterfaceDescription> unlisted_interface_descriptions =
530
531 std::vector<CommandInterface::SharedPtr> command_interfaces;
532 command_interfaces.reserve(
533 unlisted_interface_descriptions.size() + joint_command_interfaces_.size() +
534 gpio_command_interfaces_.size());
535
536 // add InterfaceDescriptions and create the CommandInterfaces from the descriptions and add to
537 // maps.
538 for (const auto & description : unlisted_interface_descriptions)
539 {
540 auto name = description.get_name();
541 unlisted_command_interfaces_.insert(std::make_pair(name, description));
542 auto command_interface = std::make_shared<CommandInterface>(description);
543 hardware_commands_.insert(std::make_pair(name, command_interface));
544 unlisted_commands_.push_back(command_interface);
545 command_interfaces.push_back(command_interface);
546 }
547
548 for (const auto & [name, descr] : joint_command_interfaces_)
549 {
550 auto command_interface = std::make_shared<CommandInterface>(descr);
551 hardware_commands_.insert(std::make_pair(name, command_interface));
552 joint_commands_.push_back(command_interface);
553 command_interfaces.push_back(command_interface);
554 }
555
556 for (const auto & [name, descr] : gpio_command_interfaces_)
557 {
558 auto command_interface = std::make_shared<CommandInterface>(descr);
559 hardware_commands_.insert(std::make_pair(name, command_interface));
560 gpio_commands_.push_back(command_interface);
561 command_interfaces.push_back(command_interface);
562 }
563 return command_interfaces;
564 }
565
567
577 virtual return_type prepare_command_mode_switch(
578 const std::vector<std::string> & /*start_interfaces*/,
579 const std::vector<std::string> & /*stop_interfaces*/)
580 {
581 return return_type::OK;
582 }
583
584 // Perform switching to the new command interface.
594 virtual return_type perform_command_mode_switch(
595 const std::vector<std::string> & /*start_interfaces*/,
596 const std::vector<std::string> & /*stop_interfaces*/)
597 {
598 return return_type::OK;
599 }
600
602
613 const rclcpp::Time & time, const rclcpp::Duration & period)
614 {
616 status.result = return_type::ERROR;
617 if (info_.is_async)
618 {
619 status.result = read_return_info_.load(std::memory_order_acquire);
620 const auto read_exec_time = read_execution_time_.load(std::memory_order_acquire);
621 if (read_exec_time.count() > 0)
622 {
623 status.execution_time = read_exec_time;
624 }
625 const auto result = async_handler_->trigger_async_callback(time, period);
626 status.successful = result.first;
627 if (!status.successful)
628 {
629 RCLCPP_WARN_EXPRESSION(
631 "Trigger read/write called while the previous async trigger is still in progress for "
632 "hardware interface : '%s'. Failed to trigger read/write cycle!",
633 info_.name.c_str());
634 status.result = return_type::OK;
635 return status;
636 }
637 }
638 else
639 {
640 const auto start_time = std::chrono::steady_clock::now();
641 status.successful = true;
642 status.result = read(time, period);
643 status.execution_time = std::chrono::duration_cast<std::chrono::nanoseconds>(
644 std::chrono::steady_clock::now() - start_time);
645 }
646 return status;
647 }
648
650
659 virtual return_type read(const rclcpp::Time & time, const rclcpp::Duration & period) = 0;
660
662
672 const rclcpp::Time & time, const rclcpp::Duration & period)
673 {
675 status.result = return_type::ERROR;
676 if (info_.is_async)
677 {
678 status.successful = true;
679 const auto write_exec_time = write_execution_time_.load(std::memory_order_acquire);
680 if (write_exec_time.count() > 0)
681 {
682 status.execution_time = write_exec_time;
683 }
684 status.result = write_return_info_.load(std::memory_order_acquire);
685 }
686 else
687 {
688 const auto start_time = std::chrono::steady_clock::now();
689 status.successful = true;
690 status.result = write(time, period);
691 status.execution_time = std::chrono::duration_cast<std::chrono::nanoseconds>(
692 std::chrono::steady_clock::now() - start_time);
693 }
694 return status;
695 }
696
698
706 virtual return_type write(const rclcpp::Time & /*time*/, const rclcpp::Duration & /*period*/)
707 {
708 return return_type::OK;
709 }
710
712
715 const std::string & get_name() const { return info_.name; }
716
718
721 const std::string & get_group_name() const { return info_.group; }
722
724
727 const rclcpp_lifecycle::State & get_lifecycle_state() const { return lifecycle_state_; }
728
730
733 void set_lifecycle_state(const rclcpp_lifecycle::State & new_state)
734 {
735 lifecycle_state_ = new_state;
736 }
737
739
746 template <typename T>
747 void set_state(const std::string & interface_name, const T & value)
748 {
749 auto it = hardware_states_.find(interface_name);
750 if (it == hardware_states_.end())
751 {
752 throw std::runtime_error(
753 fmt::format(
754 FMT_COMPILE(
755 "State interface not found: {} in hardware component: {}. "
756 "This should not happen."),
757 interface_name, info_.name));
758 }
759 auto & handle = it->second;
760 std::unique_lock<std::shared_mutex> lock(handle->get_mutex());
761 std::ignore = handle->set_value(lock, value);
762 }
763
765
772 template <typename T = double>
773 T get_state(const std::string & interface_name) const
774 {
775 auto it = hardware_states_.find(interface_name);
776 if (it == hardware_states_.end())
777 {
778 throw std::runtime_error(
779 fmt::format(
780 FMT_COMPILE(
781 "State interface not found: {} in hardware component: {}. "
782 "This should not happen."),
783 interface_name, info_.name));
784 }
785 auto & handle = it->second;
786 std::shared_lock<std::shared_mutex> lock(handle->get_mutex());
787 const auto opt_value = handle->get_optional<T>(lock);
788 if (!opt_value)
789 {
790 throw std::runtime_error(
791 fmt::format(
792 FMT_COMPILE("Failed to get state value from interface: {}. This should not happen."),
793 interface_name));
794 }
795 return opt_value.value();
796 }
797
799
807 template <typename T>
808 void set_command(const std::string & interface_name, const T & value)
809 {
810 auto it = hardware_commands_.find(interface_name);
811 if (it == hardware_commands_.end())
812 {
813 throw std::runtime_error(
814 fmt::format(
815 FMT_COMPILE(
816 "Command interface not found: {} in hardware component: {}. "
817 "This should not happen."),
818 interface_name, info_.name));
819 }
820 auto & handle = it->second;
821 std::unique_lock<std::shared_mutex> lock(handle->get_mutex());
822 std::ignore = handle->set_value(lock, value);
823 }
824
826
833 template <typename T = double>
834 T get_command(const std::string & interface_name) const
835 {
836 auto it = hardware_commands_.find(interface_name);
837 if (it == hardware_commands_.end())
838 {
839 throw std::runtime_error(
840 fmt::format(
841 FMT_COMPILE(
842 "Command interface not found: {} in hardware component: {}. "
843 "This should not happen."),
844 interface_name, info_.name));
845 }
846 auto & handle = it->second;
847 std::shared_lock<std::shared_mutex> lock(handle->get_mutex());
848 const auto opt_value = handle->get_optional<T>(lock);
849 if (!opt_value)
850 {
851 throw std::runtime_error(
852 fmt::format(
853 FMT_COMPILE("Failed to get command value from interface: {}. This should not happen."),
854 interface_name));
855 }
856 return opt_value.value();
857 }
858
860
863 rclcpp::Logger get_logger() const { return logger_; }
864
866
869 rclcpp::Clock::SharedPtr get_clock() const { return clock_; }
870
872
875 rclcpp::Node::SharedPtr get_node() const { return hardware_component_node_; }
876
878
881 const HardwareInfo & get_hardware_info() const { return info_; }
882
884
889 {
890 if (async_handler_)
891 {
892 async_handler_->pause_execution();
893 }
894 }
895
897
901 {
902 read_return_info_.store(return_type::OK, std::memory_order_release);
903 read_execution_time_.store(std::chrono::nanoseconds::zero(), std::memory_order_release);
904 write_return_info_.store(return_type::OK, std::memory_order_release);
905 write_execution_time_.store(std::chrono::nanoseconds::zero(), std::memory_order_release);
906 }
907
909
912 void enable_introspection(bool enable)
913 {
914 if (enable)
915 {
916 stats_registrations_.enableAll();
917 }
918 else
919 {
920 stats_registrations_.disableAll();
921 }
922 }
923
924protected:
925 HardwareInfo info_;
926 // interface names to InterfaceDescription
927 std::unordered_map<std::string, InterfaceDescription> joint_state_interfaces_;
928 std::unordered_map<std::string, InterfaceDescription> joint_command_interfaces_;
929
930 std::unordered_map<std::string, InterfaceDescription> sensor_state_interfaces_;
931
932 std::unordered_map<std::string, InterfaceDescription> gpio_state_interfaces_;
933 std::unordered_map<std::string, InterfaceDescription> gpio_command_interfaces_;
934
935 std::unordered_map<std::string, InterfaceDescription> unlisted_state_interfaces_;
936 std::unordered_map<std::string, InterfaceDescription> unlisted_command_interfaces_;
937
938 rclcpp_lifecycle::State lifecycle_state_;
939 std::unique_ptr<realtime_tools::AsyncFunctionHandler<return_type>> async_handler_;
940
941 // Exported Command- and StateInterfaces in order they are listed in the hardware description.
942 std::vector<StateInterface::SharedPtr> joint_states_;
943 std::vector<CommandInterface::SharedPtr> joint_commands_;
944
945 std::vector<StateInterface::SharedPtr> sensor_states_;
946
947 std::vector<StateInterface::SharedPtr> gpio_states_;
948 std::vector<CommandInterface::SharedPtr> gpio_commands_;
949
950 std::vector<StateInterface::SharedPtr> unlisted_states_;
951 std::vector<CommandInterface::SharedPtr> unlisted_commands_;
952
953private:
954 rclcpp::Clock::SharedPtr clock_;
955 rclcpp::Logger logger_;
956 rclcpp::Node::SharedPtr hardware_component_node_ = nullptr;
957 // interface names to Handle accessed through getters/setters
958 std::unordered_map<std::string, StateInterface::SharedPtr> hardware_states_;
959 std::unordered_map<std::string, CommandInterface::SharedPtr> hardware_commands_;
960 std::atomic<return_type> read_return_info_ = return_type::OK;
961 std::atomic<std::chrono::nanoseconds> read_execution_time_ = std::chrono::nanoseconds::zero();
962 std::atomic<return_type> write_return_info_ = return_type::OK;
963 std::atomic<std::chrono::nanoseconds> write_execution_time_ = std::chrono::nanoseconds::zero();
964
965protected:
966 pal_statistics::RegistrationsRAII stats_registrations_;
967 std::shared_ptr<rclcpp::Publisher<control_msgs::msg::HardwareStatus>> hardware_status_publisher_;
969 hardware_status_box_;
970 rclcpp::TimerBase::SharedPtr hardware_status_timer_;
971};
972
973} // namespace hardware_interface
974#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:715
void prepare_for_activation()
Prepare for the activation of the hardware.
Definition hardware_component_interface.hpp:900
T get_state(const std::string &interface_name) const
Get the value from a state interface.
Definition hardware_component_interface.hpp:773
virtual std::vector< StateInterface > export_state_interfaces()
Exports all state interfaces for this hardware interface.
Definition hardware_component_interface.hpp:404
const rclcpp_lifecycle::State & get_lifecycle_state() const
Get life-cycle state of the hardware.
Definition hardware_component_interface.hpp:727
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:706
virtual std::vector< StateInterface::ConstSharedPtr > on_export_state_interfaces()
Definition hardware_component_interface.hpp:432
virtual std::vector< hardware_interface::InterfaceDescription > export_unlisted_command_interface_descriptions()
Definition hardware_component_interface.hpp:509
virtual std::vector< hardware_interface::InterfaceDescription > export_unlisted_state_interface_descriptions()
Definition hardware_component_interface.hpp:419
void set_state(const std::string &interface_name, const T &value)
Set the value of a state interface.
Definition hardware_component_interface.hpp:747
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:612
void set_lifecycle_state(const rclcpp_lifecycle::State &new_state)
Set life-cycle state of the hardware.
Definition hardware_component_interface.hpp:733
virtual return_type perform_command_mode_switch(const std::vector< std::string > &, const std::vector< std::string > &)
Definition hardware_component_interface.hpp:594
void pause_async_operations()
Pause any asynchronous operations.
Definition hardware_component_interface.hpp:888
const std::string & get_group_name() const
Get name of the hardware group to which it belongs to.
Definition hardware_component_interface.hpp:721
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:671
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:330
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:808
rclcpp::Node::SharedPtr get_node() const
Get the default node of the HardwareComponentInterface.
Definition hardware_component_interface.hpp:875
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:577
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:912
rclcpp::Logger get_logger() const
Get the logger of the HardwareComponentInterface.
Definition hardware_component_interface.hpp:863
T get_command(const std::string &interface_name) const
Get the value from a command interface.
Definition hardware_component_interface.hpp:834
virtual std::vector< CommandInterface > export_command_interfaces()
Exports all command interfaces for this hardware interface.
Definition hardware_component_interface.hpp:494
virtual std::vector< CommandInterface::SharedPtr > on_export_command_interfaces()
Definition hardware_component_interface.hpp:525
rclcpp::Clock::SharedPtr get_clock() const
Get the clock.
Definition hardware_component_interface.hpp:869
const HardwareInfo & get_hardware_info() const
Get the hardware info of the HardwareComponentInterface.
Definition hardware_component_interface.hpp:881
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:379
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:314
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:345
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
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:32
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:57
rclcpp::Logger logger
A logger instance taken from resource manager.
Definition hardware_component_params.hpp:44
rclcpp::Clock::SharedPtr clock
Shared pointer to the rclcpp::Clock to be used by this hardware component. Typically,...
Definition hardware_component_params.hpp:50
hardware_interface::HardwareInfo hardware_info
Reference to the HardwareInfo struct for this specific component, parsed from the URDF....
Definition hardware_component_params.hpp:39
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