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 <limits>
19#include <memory>
20#include <string>
21#include <unordered_map>
22#include <utility>
23#include <vector>
24
25#include "hardware_interface/component_parser.hpp"
26#include "hardware_interface/handle.hpp"
27#include "hardware_interface/hardware_info.hpp"
28#include "hardware_interface/introspection.hpp"
29#include "hardware_interface/types/hardware_interface_return_values.hpp"
30#include "hardware_interface/types/hardware_interface_type_values.hpp"
31#include "hardware_interface/types/lifecycle_state_names.hpp"
32#include "hardware_interface/types/trigger_type.hpp"
33#include "lifecycle_msgs/msg/state.hpp"
34#include "rclcpp/duration.hpp"
35#include "rclcpp/logger.hpp"
36#include "rclcpp/logging.hpp"
37#include "rclcpp/node_interfaces/node_clock_interface.hpp"
38#include "rclcpp/time.hpp"
39#include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp"
40#include "rclcpp_lifecycle/state.hpp"
41#include "realtime_tools/async_function_handler.hpp"
42
43namespace hardware_interface
44{
45
46using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;
47
95class SystemInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface
96{
97public:
99 : lifecycle_state_(rclcpp_lifecycle::State(
100 lifecycle_msgs::msg::State::PRIMARY_STATE_UNKNOWN, lifecycle_state_names::UNKNOWN)),
101 system_logger_(rclcpp::get_logger("system_interface"))
102 {
103 }
104
106
110 SystemInterface(const SystemInterface & other) = delete;
111
112 SystemInterface(SystemInterface && other) = delete;
113
114 virtual ~SystemInterface() = default;
115
118
125 CallbackReturn init(
126 const HardwareInfo & hardware_info, rclcpp::Logger logger,
127 rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock_interface)
128 {
129 clock_interface_ = clock_interface;
130 system_logger_ = logger.get_child("hardware_component.system." + hardware_info.name);
131 info_ = hardware_info;
132 if (info_.is_async)
133 {
134 RCLCPP_INFO_STREAM(
135 get_logger(), "Starting async handler with scheduler priority: " << info_.thread_priority);
136 async_handler_ = std::make_unique<realtime_tools::AsyncFunctionHandler<return_type>>();
137 async_handler_->init(
138 [this](const rclcpp::Time & time, const rclcpp::Duration & period)
139 {
140 const auto read_start_time = std::chrono::steady_clock::now();
141 const auto ret_read = read(time, period);
142 const auto read_end_time = std::chrono::steady_clock::now();
143 read_return_info_.store(ret_read, std::memory_order_release);
144 read_execution_time_.store(
145 std::chrono::duration_cast<std::chrono::nanoseconds>(read_end_time - read_start_time),
146 std::memory_order_release);
147 if (ret_read != return_type::OK)
148 {
149 return ret_read;
150 }
151 const auto write_start_time = std::chrono::steady_clock::now();
152 const auto ret_write = write(time, period);
153 const auto write_end_time = std::chrono::steady_clock::now();
154 write_return_info_.store(ret_write, std::memory_order_release);
155 write_execution_time_.store(
156 std::chrono::duration_cast<std::chrono::nanoseconds>(write_end_time - write_start_time),
157 std::memory_order_release);
158 return ret_write;
159 },
160 info_.thread_priority);
161 async_handler_->start_thread();
162 }
163 return on_init(hardware_info);
164 };
165
167
172 virtual CallbackReturn on_init(const HardwareInfo & hardware_info)
173 {
174 info_ = hardware_info;
175 parse_state_interface_descriptions(info_.joints, joint_state_interfaces_);
176 parse_state_interface_descriptions(info_.sensors, sensor_state_interfaces_);
177 parse_state_interface_descriptions(info_.gpios, gpio_state_interfaces_);
178 parse_command_interface_descriptions(info_.joints, joint_command_interfaces_);
179 parse_command_interface_descriptions(info_.gpios, gpio_command_interfaces_);
180 return CallbackReturn::SUCCESS;
181 };
182
184
195 [[deprecated(
196 "Replaced by vector<StateInterface::ConstSharedPtr> on_export_state_interfaces() method. "
197 "Exporting is handled "
198 "by the Framework.")]] virtual std::vector<StateInterface>
200 {
201 // return empty vector by default. For backward compatibility we try calling
202 // export_state_interfaces() and only when empty vector is returned call
203 // on_export_state_interfaces()
204 return {};
205 }
206
213 virtual std::vector<hardware_interface::InterfaceDescription>
215 {
216 // return empty vector by default.
217 return {};
218 }
219
227 virtual std::vector<StateInterface::ConstSharedPtr> on_export_state_interfaces()
228 {
229 // import the unlisted interfaces
230 std::vector<hardware_interface::InterfaceDescription> unlisted_interface_descriptions =
232
233 std::vector<StateInterface::ConstSharedPtr> state_interfaces;
234 state_interfaces.reserve(
235 unlisted_interface_descriptions.size() + joint_state_interfaces_.size() +
236 sensor_state_interfaces_.size() + gpio_state_interfaces_.size());
237
238 // add InterfaceDescriptions and create the StateInterfaces from the descriptions and add to
239 // maps.
240 for (const auto & description : unlisted_interface_descriptions)
241 {
242 auto name = description.get_name();
243 unlisted_state_interfaces_.insert(std::make_pair(name, description));
244 auto state_interface = std::make_shared<StateInterface>(description);
245 system_states_.insert(std::make_pair(name, state_interface));
246 unlisted_states_.push_back(state_interface);
247 state_interfaces.push_back(std::const_pointer_cast<const StateInterface>(state_interface));
248 }
249
250 for (const auto & [name, descr] : joint_state_interfaces_)
251 {
252 auto state_interface = std::make_shared<StateInterface>(descr);
253 system_states_.insert(std::make_pair(name, state_interface));
254 joint_states_.push_back(state_interface);
255 state_interfaces.push_back(std::const_pointer_cast<const StateInterface>(state_interface));
256 }
257 for (const auto & [name, descr] : sensor_state_interfaces_)
258 {
259 auto state_interface = std::make_shared<StateInterface>(descr);
260 system_states_.insert(std::make_pair(name, state_interface));
261 sensor_states_.push_back(state_interface);
262 state_interfaces.push_back(std::const_pointer_cast<const StateInterface>(state_interface));
263 }
264 for (const auto & [name, descr] : gpio_state_interfaces_)
265 {
266 auto state_interface = std::make_shared<StateInterface>(descr);
267 system_states_.insert(std::make_pair(name, state_interface));
268 gpio_states_.push_back(state_interface);
269 state_interfaces.push_back(std::const_pointer_cast<const StateInterface>(state_interface));
270 }
271 return state_interfaces;
272 }
273
275
286 [[deprecated(
287 "Replaced by vector<CommandInterface::SharedPtr> on_export_command_interfaces() method. "
288 "Exporting is "
289 "handled "
290 "by the Framework.")]] virtual std::vector<CommandInterface>
292 {
293 // return empty vector by default. For backward compatibility we try calling
294 // export_command_interfaces() and only when empty vector is returned call
295 // on_export_command_interfaces()
296 return {};
297 }
298
305 virtual std::vector<hardware_interface::InterfaceDescription>
307 {
308 // return empty vector by default.
309 return {};
310 }
311
319 virtual std::vector<CommandInterface::SharedPtr> on_export_command_interfaces()
320 {
321 // import the unlisted interfaces
322 std::vector<hardware_interface::InterfaceDescription> unlisted_interface_descriptions =
324
325 std::vector<CommandInterface::SharedPtr> command_interfaces;
326 command_interfaces.reserve(
327 unlisted_interface_descriptions.size() + joint_command_interfaces_.size() +
328 gpio_command_interfaces_.size());
329
330 // add InterfaceDescriptions and create the CommandInterfaces from the descriptions and add to
331 // maps.
332 for (const auto & description : unlisted_interface_descriptions)
333 {
334 auto name = description.get_name();
335 unlisted_command_interfaces_.insert(std::make_pair(name, description));
336 auto command_interface = std::make_shared<CommandInterface>(description);
337 system_commands_.insert(std::make_pair(name, command_interface));
338 unlisted_commands_.push_back(command_interface);
339 command_interfaces.push_back(command_interface);
340 }
341
342 for (const auto & [name, descr] : joint_command_interfaces_)
343 {
344 auto command_interface = std::make_shared<CommandInterface>(descr);
345 system_commands_.insert(std::make_pair(name, command_interface));
346 joint_commands_.push_back(command_interface);
347 command_interfaces.push_back(command_interface);
348 }
349
350 for (const auto & [name, descr] : gpio_command_interfaces_)
351 {
352 auto command_interface = std::make_shared<CommandInterface>(descr);
353 system_commands_.insert(std::make_pair(name, command_interface));
354 gpio_commands_.push_back(command_interface);
355 command_interfaces.push_back(command_interface);
356 }
357 return command_interfaces;
358 }
359
361
373 virtual return_type prepare_command_mode_switch(
374 const std::vector<std::string> & /*start_interfaces*/,
375 const std::vector<std::string> & /*stop_interfaces*/)
376 {
377 return return_type::OK;
378 }
379
380 // Perform switching to the new command interface.
392 virtual return_type perform_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
400
411 const rclcpp::Time & time, const rclcpp::Duration & period)
412 {
414 status.result = return_type::ERROR;
415 if (info_.is_async)
416 {
417 status.result = read_return_info_.load(std::memory_order_acquire);
418 const auto read_exec_time = read_execution_time_.load(std::memory_order_acquire);
419 if (read_exec_time.count() > 0)
420 {
421 status.execution_time = read_exec_time;
422 }
423 const auto result = async_handler_->trigger_async_callback(time, period);
424 status.successful = result.first;
425 if (!status.successful)
426 {
427 RCLCPP_WARN(
428 get_logger(),
429 "Trigger read/write called while the previous async trigger is still in progress for "
430 "hardware interface : '%s'. Failed to trigger read/write cycle!",
431 info_.name.c_str());
432 status.result = return_type::OK;
433 return status;
434 }
435 }
436 else
437 {
438 const auto start_time = std::chrono::steady_clock::now();
439 status.successful = true;
440 status.result = read(time, period);
441 status.execution_time = std::chrono::duration_cast<std::chrono::nanoseconds>(
442 std::chrono::steady_clock::now() - start_time);
443 }
444 return status;
445 }
446
448
457 virtual return_type read(const rclcpp::Time & time, const rclcpp::Duration & period) = 0;
458
460
470 const rclcpp::Time & time, const rclcpp::Duration & period)
471 {
473 status.result = return_type::ERROR;
474 if (info_.is_async)
475 {
476 status.successful = true;
477 const auto write_exec_time = write_execution_time_.load(std::memory_order_acquire);
478 if (write_exec_time.count() > 0)
479 {
480 status.execution_time = write_exec_time;
481 }
482 status.result = write_return_info_.load(std::memory_order_acquire);
483 }
484 else
485 {
486 const auto start_time = std::chrono::steady_clock::now();
487 status.successful = true;
488 status.result = write(time, period);
489 status.execution_time = std::chrono::duration_cast<std::chrono::nanoseconds>(
490 std::chrono::steady_clock::now() - start_time);
491 }
492 return status;
493 }
494
496
504 virtual return_type write(const rclcpp::Time & time, const rclcpp::Duration & period) = 0;
505
507
510 const std::string & get_name() const { return info_.name; }
511
513
516 const std::string & get_group_name() const { return info_.group; }
517
519
522 const rclcpp_lifecycle::State & get_lifecycle_state() const { return lifecycle_state_; }
523
525
528 void set_lifecycle_state(const rclcpp_lifecycle::State & new_state)
529 {
530 lifecycle_state_ = new_state;
531 }
532
533 void set_state(const std::string & interface_name, const double & value)
534 {
535 system_states_.at(interface_name)->set_value(value);
536 }
537
538 double get_state(const std::string & interface_name) const
539 {
540 return system_states_.at(interface_name)->get_value();
541 }
542
543 void set_command(const std::string & interface_name, const double & value)
544 {
545 system_commands_.at(interface_name)->set_value(value);
546 }
547
548 double get_command(const std::string & interface_name) const
549 {
550 return system_commands_.at(interface_name)->get_value();
551 }
552
554
557 rclcpp::Logger get_logger() const { return system_logger_; }
558
560
563 rclcpp::Clock::SharedPtr get_clock() const { return clock_interface_->get_clock(); }
564
566
569 const HardwareInfo & get_hardware_info() const { return info_; }
570
572
576 {
577 read_return_info_.store(return_type::OK, std::memory_order_release);
578 read_execution_time_.store(std::chrono::nanoseconds::zero(), std::memory_order_release);
579 write_return_info_.store(return_type::OK, std::memory_order_release);
580 write_execution_time_.store(std::chrono::nanoseconds::zero(), std::memory_order_release);
581 }
582
584
587 void enable_introspection(bool enable)
588 {
589 if (enable)
590 {
591 stats_registrations_.enableAll();
592 }
593 else
594 {
595 stats_registrations_.disableAll();
596 }
597 }
598
599protected:
600 HardwareInfo info_;
601 // interface names to InterfaceDescription
602 std::unordered_map<std::string, InterfaceDescription> joint_state_interfaces_;
603 std::unordered_map<std::string, InterfaceDescription> joint_command_interfaces_;
604
605 std::unordered_map<std::string, InterfaceDescription> sensor_state_interfaces_;
606
607 std::unordered_map<std::string, InterfaceDescription> gpio_state_interfaces_;
608 std::unordered_map<std::string, InterfaceDescription> gpio_command_interfaces_;
609
610 std::unordered_map<std::string, InterfaceDescription> unlisted_state_interfaces_;
611 std::unordered_map<std::string, InterfaceDescription> unlisted_command_interfaces_;
612
613 rclcpp_lifecycle::State lifecycle_state_;
614 std::unique_ptr<realtime_tools::AsyncFunctionHandler<return_type>> async_handler_;
615
616 // Exported Command- and StateInterfaces in order they are listed in the hardware description.
617 std::vector<StateInterface::SharedPtr> joint_states_;
618 std::vector<CommandInterface::SharedPtr> joint_commands_;
619
620 std::vector<StateInterface::SharedPtr> sensor_states_;
621
622 std::vector<StateInterface::SharedPtr> gpio_states_;
623 std::vector<CommandInterface::SharedPtr> gpio_commands_;
624
625 std::vector<StateInterface::SharedPtr> unlisted_states_;
626 std::vector<CommandInterface::SharedPtr> unlisted_commands_;
627
628private:
629 rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock_interface_;
630 rclcpp::Logger system_logger_;
631 // interface names to Handle accessed through getters/setters
632 std::unordered_map<std::string, StateInterface::SharedPtr> system_states_;
633 std::unordered_map<std::string, CommandInterface::SharedPtr> system_commands_;
634 std::atomic<return_type> read_return_info_ = return_type::OK;
635 std::atomic<std::chrono::nanoseconds> read_execution_time_ = std::chrono::nanoseconds::zero();
636 std::atomic<return_type> write_return_info_ = return_type::OK;
637 std::atomic<std::chrono::nanoseconds> write_execution_time_ = std::chrono::nanoseconds::zero();
638
639protected:
640 pal_statistics::RegistrationsRAII stats_registrations_;
641};
642
643} // namespace hardware_interface
644#endif // HARDWARE_INTERFACE__SYSTEM_INTERFACE_HPP_
Virtual Class to implement when integrating a complex system into ros2_control.
Definition system_interface.hpp:96
void prepare_for_activation()
Prepare for the activation of the hardware.
Definition system_interface.hpp:575
virtual std::vector< CommandInterface::SharedPtr > on_export_command_interfaces()
Definition system_interface.hpp:319
virtual return_type perform_command_mode_switch(const std::vector< std::string > &, const std::vector< std::string > &)
Definition system_interface.hpp:392
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:410
virtual std::vector< hardware_interface::InterfaceDescription > export_unlisted_command_interface_descriptions()
Definition system_interface.hpp:306
virtual std::vector< CommandInterface > export_command_interfaces()
Exports all command interfaces for this hardware interface.
Definition system_interface.hpp:291
virtual std::vector< StateInterface > export_state_interfaces()
Exports all state interfaces for this hardware interface.
Definition system_interface.hpp:199
virtual std::vector< hardware_interface::InterfaceDescription > export_unlisted_state_interface_descriptions()
Definition system_interface.hpp:214
const HardwareInfo & get_hardware_info() const
Get the hardware info of the SystemInterface.
Definition system_interface.hpp:569
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:172
rclcpp::Logger get_logger() const
Get the logger of the SystemInterface.
Definition system_interface.hpp:557
const std::string & get_group_name() const
Get name of the actuator hardware group to which it belongs to.
Definition system_interface.hpp:516
void set_lifecycle_state(const rclcpp_lifecycle::State &new_state)
Set life-cycle state of the actuator hardware.
Definition system_interface.hpp:528
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:373
rclcpp::Clock::SharedPtr get_clock() const
Get the clock of the SystemInterface.
Definition system_interface.hpp:563
CallbackReturn init(const HardwareInfo &hardware_info, rclcpp::Logger logger, rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock_interface)
Definition system_interface.hpp:125
const rclcpp_lifecycle::State & get_lifecycle_state() const
Get life-cycle state of the actuator hardware.
Definition system_interface.hpp:522
const std::string & get_name() const
Get name of the actuator hardware.
Definition system_interface.hpp:510
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:469
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:227
void enable_introspection(bool enable)
Enable or disable introspection of the hardware.
Definition system_interface.hpp:587
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:33
std::vector< InterfaceDescription > parse_command_interface_descriptions(const std::vector< ComponentInfo > &component_info)
Definition component_parser.cpp:1036
std::vector< InterfaceDescription > parse_state_interface_descriptions(const std::vector< ComponentInfo > &component_info)
Definition component_parser.cpp:1003
Definition hardware_interface_return_values.hpp:41
This structure stores information about hardware defined in a robot's URDF.
Definition hardware_info.hpp:170
int thread_priority
Async thread priority.
Definition hardware_info.hpp:182
std::string group
Hardware group to which the hardware belongs.
Definition hardware_info.hpp:176
bool is_async
Component is async.
Definition hardware_info.hpp:180
std::vector< ComponentInfo > gpios
Definition hardware_info.hpp:205
std::vector< ComponentInfo > joints
Definition hardware_info.hpp:191
std::string name
Name of the hardware.
Definition hardware_info.hpp:172
std::vector< ComponentInfo > sensors
Definition hardware_info.hpp:200