ros2_control - rolling
Loading...
Searching...
No Matches
system_interface.hpp
1// Copyright 2020 - 2021 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__SYSTEM_INTERFACE_HPP_
16#define HARDWARE_INTERFACE__SYSTEM_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 "hardware_interface/component_parser.hpp"
28#include "hardware_interface/handle.hpp"
29#include "hardware_interface/hardware_info.hpp"
30#include "hardware_interface/introspection.hpp"
31#include "hardware_interface/types/hardware_interface_return_values.hpp"
32#include "hardware_interface/types/hardware_interface_type_values.hpp"
33#include "hardware_interface/types/lifecycle_state_names.hpp"
34#include "hardware_interface/types/trigger_type.hpp"
35#include "lifecycle_msgs/msg/state.hpp"
36#include "rclcpp/duration.hpp"
37#include "rclcpp/logger.hpp"
38#include "rclcpp/logging.hpp"
39#include "rclcpp/node_interfaces/node_clock_interface.hpp"
40#include "rclcpp/time.hpp"
41#include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp"
42#include "rclcpp_lifecycle/state.hpp"
43#include "realtime_tools/async_function_handler.hpp"
44
45namespace hardware_interface
46{
47
48using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;
49
97class SystemInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface
98{
99public:
101 : lifecycle_state_(
102 rclcpp_lifecycle::State(
103 lifecycle_msgs::msg::State::PRIMARY_STATE_UNKNOWN, lifecycle_state_names::UNKNOWN)),
104 system_logger_(rclcpp::get_logger("system_interface"))
105 {
106 }
107
109
113 SystemInterface(const SystemInterface & other) = delete;
114
115 SystemInterface(SystemInterface && other) = delete;
116
117 virtual ~SystemInterface() = default;
118
121
128 [[deprecated("Use init(HardwareInfo, rclcpp::Logger, rclcpp::Clock::SharedPtr) instead.")]]
129 CallbackReturn init(
130 const HardwareInfo & hardware_info, rclcpp::Logger logger,
131 rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock_interface)
132 {
133 return this->init(hardware_info, logger, clock_interface->get_clock());
134 }
135
138
145 CallbackReturn init(
146 const HardwareInfo & hardware_info, rclcpp::Logger logger, rclcpp::Clock::SharedPtr clock)
147 {
148 system_clock_ = clock;
149 system_logger_ = logger.get_child("hardware_component.system." + hardware_info.name);
150 info_ = hardware_info;
151 if (info_.is_async)
152 {
153 RCLCPP_INFO_STREAM(
154 get_logger(), "Starting async handler with scheduler priority: " << info_.thread_priority);
155 async_handler_ = std::make_unique<realtime_tools::AsyncFunctionHandler<return_type>>();
156 async_handler_->init(
157 [this](const rclcpp::Time & time, const rclcpp::Duration & period)
158 {
159 const auto read_start_time = std::chrono::steady_clock::now();
160 const auto ret_read = read(time, period);
161 const auto read_end_time = std::chrono::steady_clock::now();
162 read_return_info_.store(ret_read, std::memory_order_release);
163 read_execution_time_.store(
164 std::chrono::duration_cast<std::chrono::nanoseconds>(read_end_time - read_start_time),
165 std::memory_order_release);
166 if (ret_read != return_type::OK)
167 {
168 return ret_read;
169 }
170 const auto write_start_time = std::chrono::steady_clock::now();
171 const auto ret_write = write(time, period);
172 const auto write_end_time = std::chrono::steady_clock::now();
173 write_return_info_.store(ret_write, std::memory_order_release);
174 write_execution_time_.store(
175 std::chrono::duration_cast<std::chrono::nanoseconds>(write_end_time - write_start_time),
176 std::memory_order_release);
177 return ret_write;
178 },
179 info_.thread_priority);
180 async_handler_->start_thread();
181 }
182 return on_init(hardware_info);
183 };
184
186
191 virtual CallbackReturn on_init(const HardwareInfo & hardware_info)
192 {
193 info_ = hardware_info;
194 parse_state_interface_descriptions(info_.joints, joint_state_interfaces_);
195 parse_state_interface_descriptions(info_.sensors, sensor_state_interfaces_);
196 parse_state_interface_descriptions(info_.gpios, gpio_state_interfaces_);
197 parse_command_interface_descriptions(info_.joints, joint_command_interfaces_);
198 parse_command_interface_descriptions(info_.gpios, gpio_command_interfaces_);
199 return CallbackReturn::SUCCESS;
200 };
201
203
214 [[deprecated(
215 "Replaced by vector<StateInterface::ConstSharedPtr> on_export_state_interfaces() method. "
216 "Exporting is handled "
217 "by the Framework.")]] virtual std::vector<StateInterface>
219 {
220 // return empty vector by default. For backward compatibility we try calling
221 // export_state_interfaces() and only when empty vector is returned call
222 // on_export_state_interfaces()
223 return {};
224 }
225
232 virtual std::vector<hardware_interface::InterfaceDescription>
234 {
235 // return empty vector by default.
236 return {};
237 }
238
246 virtual std::vector<StateInterface::ConstSharedPtr> on_export_state_interfaces()
247 {
248 // import the unlisted interfaces
249 std::vector<hardware_interface::InterfaceDescription> unlisted_interface_descriptions =
251
252 std::vector<StateInterface::ConstSharedPtr> state_interfaces;
253 state_interfaces.reserve(
254 unlisted_interface_descriptions.size() + joint_state_interfaces_.size() +
255 sensor_state_interfaces_.size() + gpio_state_interfaces_.size());
256
257 // add InterfaceDescriptions and create the StateInterfaces from the descriptions and add to
258 // maps.
259 for (const auto & description : unlisted_interface_descriptions)
260 {
261 auto name = description.get_name();
262 unlisted_state_interfaces_.insert(std::make_pair(name, description));
263 auto state_interface = std::make_shared<StateInterface>(description);
264 system_states_.insert(std::make_pair(name, state_interface));
265 unlisted_states_.push_back(state_interface);
266 state_interfaces.push_back(std::const_pointer_cast<const StateInterface>(state_interface));
267 }
268
269 for (const auto & [name, descr] : joint_state_interfaces_)
270 {
271 auto state_interface = std::make_shared<StateInterface>(descr);
272 system_states_.insert(std::make_pair(name, state_interface));
273 joint_states_.push_back(state_interface);
274 state_interfaces.push_back(std::const_pointer_cast<const StateInterface>(state_interface));
275 }
276 for (const auto & [name, descr] : sensor_state_interfaces_)
277 {
278 auto state_interface = std::make_shared<StateInterface>(descr);
279 system_states_.insert(std::make_pair(name, state_interface));
280 sensor_states_.push_back(state_interface);
281 state_interfaces.push_back(std::const_pointer_cast<const StateInterface>(state_interface));
282 }
283 for (const auto & [name, descr] : gpio_state_interfaces_)
284 {
285 auto state_interface = std::make_shared<StateInterface>(descr);
286 system_states_.insert(std::make_pair(name, state_interface));
287 gpio_states_.push_back(state_interface);
288 state_interfaces.push_back(std::const_pointer_cast<const StateInterface>(state_interface));
289 }
290 return state_interfaces;
291 }
292
294
305 [[deprecated(
306 "Replaced by vector<CommandInterface::SharedPtr> on_export_command_interfaces() method. "
307 "Exporting is "
308 "handled "
309 "by the Framework.")]] virtual std::vector<CommandInterface>
311 {
312 // return empty vector by default. For backward compatibility we try calling
313 // export_command_interfaces() and only when empty vector is returned call
314 // on_export_command_interfaces()
315 return {};
316 }
317
324 virtual std::vector<hardware_interface::InterfaceDescription>
326 {
327 // return empty vector by default.
328 return {};
329 }
330
338 virtual std::vector<CommandInterface::SharedPtr> on_export_command_interfaces()
339 {
340 // import the unlisted interfaces
341 std::vector<hardware_interface::InterfaceDescription> unlisted_interface_descriptions =
343
344 std::vector<CommandInterface::SharedPtr> command_interfaces;
345 command_interfaces.reserve(
346 unlisted_interface_descriptions.size() + joint_command_interfaces_.size() +
347 gpio_command_interfaces_.size());
348
349 // add InterfaceDescriptions and create the CommandInterfaces from the descriptions and add to
350 // maps.
351 for (const auto & description : unlisted_interface_descriptions)
352 {
353 auto name = description.get_name();
354 unlisted_command_interfaces_.insert(std::make_pair(name, description));
355 auto command_interface = std::make_shared<CommandInterface>(description);
356 system_commands_.insert(std::make_pair(name, command_interface));
357 unlisted_commands_.push_back(command_interface);
358 command_interfaces.push_back(command_interface);
359 }
360
361 for (const auto & [name, descr] : joint_command_interfaces_)
362 {
363 auto command_interface = std::make_shared<CommandInterface>(descr);
364 system_commands_.insert(std::make_pair(name, command_interface));
365 joint_commands_.push_back(command_interface);
366 command_interfaces.push_back(command_interface);
367 }
368
369 for (const auto & [name, descr] : gpio_command_interfaces_)
370 {
371 auto command_interface = std::make_shared<CommandInterface>(descr);
372 system_commands_.insert(std::make_pair(name, command_interface));
373 gpio_commands_.push_back(command_interface);
374 command_interfaces.push_back(command_interface);
375 }
376 return command_interfaces;
377 }
378
380
392 virtual return_type prepare_command_mode_switch(
393 const std::vector<std::string> & /*start_interfaces*/,
394 const std::vector<std::string> & /*stop_interfaces*/)
395 {
396 return return_type::OK;
397 }
398
399 // Perform switching to the new command interface.
411 virtual return_type perform_command_mode_switch(
412 const std::vector<std::string> & /*start_interfaces*/,
413 const std::vector<std::string> & /*stop_interfaces*/)
414 {
415 return return_type::OK;
416 }
417
419
430 const rclcpp::Time & time, const rclcpp::Duration & period)
431 {
433 status.result = return_type::ERROR;
434 if (info_.is_async)
435 {
436 status.result = read_return_info_.load(std::memory_order_acquire);
437 const auto read_exec_time = read_execution_time_.load(std::memory_order_acquire);
438 if (read_exec_time.count() > 0)
439 {
440 status.execution_time = read_exec_time;
441 }
442 const auto result = async_handler_->trigger_async_callback(time, period);
443 status.successful = result.first;
444 if (!status.successful)
445 {
446 RCLCPP_WARN(
447 get_logger(),
448 "Trigger read/write called while the previous async trigger is still in progress for "
449 "hardware interface : '%s'. Failed to trigger read/write cycle!",
450 info_.name.c_str());
451 status.result = return_type::OK;
452 return status;
453 }
454 }
455 else
456 {
457 const auto start_time = std::chrono::steady_clock::now();
458 status.successful = true;
459 status.result = read(time, period);
460 status.execution_time = std::chrono::duration_cast<std::chrono::nanoseconds>(
461 std::chrono::steady_clock::now() - start_time);
462 }
463 return status;
464 }
465
467
476 virtual return_type read(const rclcpp::Time & time, const rclcpp::Duration & period) = 0;
477
479
489 const rclcpp::Time & time, const rclcpp::Duration & period)
490 {
492 status.result = return_type::ERROR;
493 if (info_.is_async)
494 {
495 status.successful = true;
496 const auto write_exec_time = write_execution_time_.load(std::memory_order_acquire);
497 if (write_exec_time.count() > 0)
498 {
499 status.execution_time = write_exec_time;
500 }
501 status.result = write_return_info_.load(std::memory_order_acquire);
502 }
503 else
504 {
505 const auto start_time = std::chrono::steady_clock::now();
506 status.successful = true;
507 status.result = write(time, period);
508 status.execution_time = std::chrono::duration_cast<std::chrono::nanoseconds>(
509 std::chrono::steady_clock::now() - start_time);
510 }
511 return status;
512 }
513
515
523 virtual return_type write(const rclcpp::Time & time, const rclcpp::Duration & period) = 0;
524
526
529 const std::string & get_name() const { return info_.name; }
530
532
535 const std::string & get_group_name() const { return info_.group; }
536
538
541 const rclcpp_lifecycle::State & get_lifecycle_state() const { return lifecycle_state_; }
542
544
547 void set_lifecycle_state(const rclcpp_lifecycle::State & new_state)
548 {
549 lifecycle_state_ = new_state;
550 }
551
552 template <typename T>
553 void set_state(const std::string & interface_name, const T & value)
554 {
555 auto it = system_states_.find(interface_name);
556 if (it == system_states_.end())
557 {
558 throw std::runtime_error(
559 fmt::format(
560 FMT_COMPILE(
561 "State interface not found: {} in system hardware component: {}. "
562 "This should not happen."),
563 interface_name, info_.name));
564 }
565 auto & handle = it->second;
566 std::unique_lock<std::shared_mutex> lock(handle->get_mutex());
567 std::ignore = handle->set_value(lock, value);
568 }
569
570 template <typename T = double>
571 T get_state(const std::string & interface_name) const
572 {
573 auto it = system_states_.find(interface_name);
574 if (it == system_states_.end())
575 {
576 throw std::runtime_error(
577 fmt::format(
578 FMT_COMPILE(
579 "State interface not found: {} in system hardware component: {}. "
580 "This should not happen."),
581 interface_name, info_.name));
582 }
583 auto & handle = it->second;
584 std::shared_lock<std::shared_mutex> lock(handle->get_mutex());
585 const auto opt_value = handle->get_optional<T>(lock);
586 if (!opt_value)
587 {
588 throw std::runtime_error(
589 fmt::format(
590 FMT_COMPILE("Failed to get state value from interface: {}. This should not happen."),
591 interface_name));
592 }
593 return opt_value.value();
594 }
595
596 void set_command(const std::string & interface_name, const double & value)
597 {
598 auto it = system_commands_.find(interface_name);
599 if (it == system_commands_.end())
600 {
601 throw std::runtime_error(
602 fmt::format(
603 FMT_COMPILE(
604 "Command interface not found: {} in system hardware component: {}. "
605 "This should not happen."),
606 interface_name, info_.name));
607 }
608 auto & handle = it->second;
609 std::unique_lock<std::shared_mutex> lock(handle->get_mutex());
610 std::ignore = handle->set_value(lock, value);
611 }
612
613 template <typename T = double>
614 T get_command(const std::string & interface_name) const
615 {
616 auto it = system_commands_.find(interface_name);
617 if (it == system_commands_.end())
618 {
619 throw std::runtime_error(
620 fmt::format(
621 FMT_COMPILE(
622 "Command interface not found: {} in system hardware component: {}. "
623 "This should not happen."),
624 interface_name, info_.name));
625 }
626 auto & handle = it->second;
627 std::shared_lock<std::shared_mutex> lock(handle->get_mutex());
628 const auto opt_value = handle->get_optional<double>(lock);
629 if (!opt_value)
630 {
631 throw std::runtime_error(
632 fmt::format(
633 FMT_COMPILE("Failed to get command value from interface: {}. This should not happen."),
634 interface_name));
635 }
636 return opt_value.value();
637 }
638
640
643 rclcpp::Logger get_logger() const { return system_logger_; }
644
646
649 rclcpp::Clock::SharedPtr get_clock() const { return system_clock_; }
650
652
655 const HardwareInfo & get_hardware_info() const { return info_; }
656
658
662 {
663 read_return_info_.store(return_type::OK, std::memory_order_release);
664 read_execution_time_.store(std::chrono::nanoseconds::zero(), std::memory_order_release);
665 write_return_info_.store(return_type::OK, std::memory_order_release);
666 write_execution_time_.store(std::chrono::nanoseconds::zero(), std::memory_order_release);
667 }
668
670
673 void enable_introspection(bool enable)
674 {
675 if (enable)
676 {
677 stats_registrations_.enableAll();
678 }
679 else
680 {
681 stats_registrations_.disableAll();
682 }
683 }
684
685protected:
686 HardwareInfo info_;
687 // interface names to InterfaceDescription
688 std::unordered_map<std::string, InterfaceDescription> joint_state_interfaces_;
689 std::unordered_map<std::string, InterfaceDescription> joint_command_interfaces_;
690
691 std::unordered_map<std::string, InterfaceDescription> sensor_state_interfaces_;
692
693 std::unordered_map<std::string, InterfaceDescription> gpio_state_interfaces_;
694 std::unordered_map<std::string, InterfaceDescription> gpio_command_interfaces_;
695
696 std::unordered_map<std::string, InterfaceDescription> unlisted_state_interfaces_;
697 std::unordered_map<std::string, InterfaceDescription> unlisted_command_interfaces_;
698
699 rclcpp_lifecycle::State lifecycle_state_;
700 std::unique_ptr<realtime_tools::AsyncFunctionHandler<return_type>> async_handler_;
701
702 // Exported Command- and StateInterfaces in order they are listed in the hardware description.
703 std::vector<StateInterface::SharedPtr> joint_states_;
704 std::vector<CommandInterface::SharedPtr> joint_commands_;
705
706 std::vector<StateInterface::SharedPtr> sensor_states_;
707
708 std::vector<StateInterface::SharedPtr> gpio_states_;
709 std::vector<CommandInterface::SharedPtr> gpio_commands_;
710
711 std::vector<StateInterface::SharedPtr> unlisted_states_;
712 std::vector<CommandInterface::SharedPtr> unlisted_commands_;
713
714private:
715 rclcpp::Clock::SharedPtr system_clock_;
716 rclcpp::Logger system_logger_;
717 // interface names to Handle accessed through getters/setters
718 std::unordered_map<std::string, StateInterface::SharedPtr> system_states_;
719 std::unordered_map<std::string, CommandInterface::SharedPtr> system_commands_;
720 std::atomic<return_type> read_return_info_ = return_type::OK;
721 std::atomic<std::chrono::nanoseconds> read_execution_time_ = std::chrono::nanoseconds::zero();
722 std::atomic<return_type> write_return_info_ = return_type::OK;
723 std::atomic<std::chrono::nanoseconds> write_execution_time_ = std::chrono::nanoseconds::zero();
724
725protected:
726 pal_statistics::RegistrationsRAII stats_registrations_;
727};
728
729} // namespace hardware_interface
730#endif // HARDWARE_INTERFACE__SYSTEM_INTERFACE_HPP_
Virtual Class to implement when integrating a complex system into ros2_control.
Definition system_interface.hpp:98
void prepare_for_activation()
Prepare for the activation of the hardware.
Definition system_interface.hpp:661
virtual std::vector< CommandInterface::SharedPtr > on_export_command_interfaces()
Definition system_interface.hpp:338
virtual return_type perform_command_mode_switch(const std::vector< std::string > &, const std::vector< std::string > &)
Definition system_interface.hpp:411
HardwareComponentCycleStatus trigger_read(const rclcpp::Time &time, const rclcpp::Duration &period)
Triggers the read method synchronously or asynchronously depending on the HardwareInfo.
Definition system_interface.hpp:429
virtual std::vector< hardware_interface::InterfaceDescription > export_unlisted_command_interface_descriptions()
Definition system_interface.hpp:325
virtual std::vector< CommandInterface > export_command_interfaces()
Exports all command interfaces for this hardware interface.
Definition system_interface.hpp:310
virtual std::vector< StateInterface > export_state_interfaces()
Exports all state interfaces for this hardware interface.
Definition system_interface.hpp:218
virtual std::vector< hardware_interface::InterfaceDescription > export_unlisted_state_interface_descriptions()
Definition system_interface.hpp:233
const HardwareInfo & get_hardware_info() const
Get the hardware info of the SystemInterface.
Definition system_interface.hpp:655
virtual CallbackReturn on_init(const HardwareInfo &hardware_info)
Initialization of the hardware interface from data parsed from the robot's URDF.
Definition system_interface.hpp:191
rclcpp::Logger get_logger() const
Get the logger of the SystemInterface.
Definition system_interface.hpp:643
const std::string & get_group_name() const
Get name of the actuator hardware group to which it belongs to.
Definition system_interface.hpp:535
void set_lifecycle_state(const rclcpp_lifecycle::State &new_state)
Set life-cycle state of the actuator hardware.
Definition system_interface.hpp:547
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 system_interface.hpp:392
rclcpp::Clock::SharedPtr get_clock() const
Get the clock of the SystemInterface.
Definition system_interface.hpp:649
CallbackReturn init(const HardwareInfo &hardware_info, rclcpp::Logger logger, rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock_interface)
Definition system_interface.hpp:129
const rclcpp_lifecycle::State & get_lifecycle_state() const
Get life-cycle state of the actuator hardware.
Definition system_interface.hpp:541
const std::string & get_name() const
Get name of the actuator hardware.
Definition system_interface.hpp:529
HardwareComponentCycleStatus trigger_write(const rclcpp::Time &time, const rclcpp::Duration &period)
Triggers the write method synchronously or asynchronously depending on the HardwareInfo.
Definition system_interface.hpp:488
CallbackReturn init(const HardwareInfo &hardware_info, rclcpp::Logger logger, rclcpp::Clock::SharedPtr clock)
Definition system_interface.hpp:145
virtual return_type read(const rclcpp::Time &time, const rclcpp::Duration &period)=0
Read the current state values from the actuator.
virtual std::vector< StateInterface::ConstSharedPtr > on_export_state_interfaces()
Definition system_interface.hpp:246
void enable_introspection(bool enable)
Enable or disable introspection of the hardware.
Definition system_interface.hpp:673
SystemInterface(const SystemInterface &other)=delete
SystemInterface copy constructor is actively deleted.
virtual return_type write(const rclcpp::Time &time, const rclcpp::Duration &period)=0
Write the current command values to the actuator.
Definition actuator.hpp:34
std::vector< InterfaceDescription > parse_command_interface_descriptions(const std::vector< ComponentInfo > &component_info)
Definition component_parser.cpp:1071
std::vector< InterfaceDescription > parse_state_interface_descriptions(const std::vector< ComponentInfo > &component_info)
Definition component_parser.cpp:1038
Definition hardware_interface_return_values.hpp:41
This structure stores information about hardware defined in a robot's URDF.
Definition hardware_info.hpp:232
int thread_priority
Async thread priority.
Definition hardware_info.hpp:244
std::string group
Hardware group to which the hardware belongs.
Definition hardware_info.hpp:238
bool is_async
Component is async.
Definition hardware_info.hpp:242
std::vector< ComponentInfo > gpios
Definition hardware_info.hpp:267
std::vector< ComponentInfo > joints
Definition hardware_info.hpp:253
std::string name
Name of the hardware.
Definition hardware_info.hpp:234
std::vector< ComponentInfo > sensors
Definition hardware_info.hpp:262