ros2_control - rolling
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/types/hardware_interface_return_values.hpp"
29 #include "hardware_interface/types/hardware_interface_type_values.hpp"
30 #include "hardware_interface/types/lifecycle_state_names.hpp"
31 #include "lifecycle_msgs/msg/state.hpp"
32 #include "rclcpp/duration.hpp"
33 #include "rclcpp/logger.hpp"
34 #include "rclcpp/logging.hpp"
35 #include "rclcpp/node_interfaces/node_clock_interface.hpp"
36 #include "rclcpp/time.hpp"
37 #include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp"
38 #include "rclcpp_lifecycle/state.hpp"
39 #include "realtime_tools/async_function_handler.hpp"
40 
41 namespace hardware_interface
42 {
44 
79 using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;
80 
81 class SystemInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface
82 {
83 public:
85  : lifecycle_state_(rclcpp_lifecycle::State(
86  lifecycle_msgs::msg::State::PRIMARY_STATE_UNKNOWN, lifecycle_state_names::UNKNOWN)),
87  system_logger_(rclcpp::get_logger("system_interface"))
88  {
89  }
90 
92 
96  SystemInterface(const SystemInterface & other) = delete;
97 
98  SystemInterface(SystemInterface && other) = default;
99 
100  virtual ~SystemInterface() = default;
101 
104 
112  const HardwareInfo & hardware_info, rclcpp::Logger logger,
113  rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock_interface)
114  {
115  clock_interface_ = clock_interface;
116  system_logger_ = logger.get_child("hardware_component.system." + hardware_info.name);
117  info_ = hardware_info;
118  if (info_.is_async)
119  {
120  RCLCPP_INFO_STREAM(
121  get_logger(), "Starting async handler with scheduler priority: " << info_.thread_priority);
122  async_handler_ = std::make_unique<realtime_tools::AsyncFunctionHandler<return_type>>();
123  async_handler_->init(
124  [this](const rclcpp::Time & time, const rclcpp::Duration & period)
125  {
126  if (next_trigger_ == TriggerType::READ)
127  {
128  const auto ret = read(time, period);
129  next_trigger_ = TriggerType::WRITE;
130  return ret;
131  }
132  else
133  {
134  const auto ret = write(time, period);
135  next_trigger_ = TriggerType::READ;
136  return ret;
137  }
138  },
139  info_.thread_priority);
140  async_handler_->start_thread();
141  }
142  return on_init(hardware_info);
143  };
144 
146 
151  virtual CallbackReturn on_init(const HardwareInfo & hardware_info)
152  {
153  info_ = hardware_info;
154  parse_state_interface_descriptions(info_.joints, joint_state_interfaces_);
155  parse_state_interface_descriptions(info_.sensors, sensor_state_interfaces_);
156  parse_state_interface_descriptions(info_.gpios, gpio_state_interfaces_);
157  parse_command_interface_descriptions(info_.joints, joint_command_interfaces_);
158  parse_command_interface_descriptions(info_.gpios, gpio_command_interfaces_);
159  return CallbackReturn::SUCCESS;
160  };
161 
163 
174  [[deprecated(
175  "Replaced by vector<StateInterface::ConstSharedPtr> on_export_state_interfaces() method. "
176  "Exporting is handled "
177  "by the Framework.")]] virtual std::vector<StateInterface>
179  {
180  // return empty vector by default. For backward compatibility we try calling
181  // export_state_interfaces() and only when empty vector is returned call
182  // on_export_state_interfaces()
183  return {};
184  }
185 
192  virtual std::vector<hardware_interface::InterfaceDescription>
194  {
195  // return empty vector by default.
196  return {};
197  }
198 
206  virtual std::vector<StateInterface::ConstSharedPtr> on_export_state_interfaces()
207  {
208  // import the unlisted interfaces
209  std::vector<hardware_interface::InterfaceDescription> unlisted_interface_descriptions =
211 
212  std::vector<StateInterface::ConstSharedPtr> state_interfaces;
213  state_interfaces.reserve(
214  unlisted_interface_descriptions.size() + joint_state_interfaces_.size() +
215  sensor_state_interfaces_.size() + gpio_state_interfaces_.size());
216 
217  // add InterfaceDescriptions and create the StateInterfaces from the descriptions and add to
218  // maps.
219  for (const auto & description : unlisted_interface_descriptions)
220  {
221  auto name = description.get_name();
222  unlisted_state_interfaces_.insert(std::make_pair(name, description));
223  auto state_interface = std::make_shared<StateInterface>(description);
224  system_states_.insert(std::make_pair(name, state_interface));
225  unlisted_states_.push_back(state_interface);
226  state_interfaces.push_back(std::const_pointer_cast<const StateInterface>(state_interface));
227  }
228 
229  for (const auto & [name, descr] : joint_state_interfaces_)
230  {
231  auto state_interface = std::make_shared<StateInterface>(descr);
232  system_states_.insert(std::make_pair(name, state_interface));
233  joint_states_.push_back(state_interface);
234  state_interfaces.push_back(std::const_pointer_cast<const StateInterface>(state_interface));
235  }
236  for (const auto & [name, descr] : sensor_state_interfaces_)
237  {
238  auto state_interface = std::make_shared<StateInterface>(descr);
239  system_states_.insert(std::make_pair(name, state_interface));
240  sensor_states_.push_back(state_interface);
241  state_interfaces.push_back(std::const_pointer_cast<const StateInterface>(state_interface));
242  }
243  for (const auto & [name, descr] : gpio_state_interfaces_)
244  {
245  auto state_interface = std::make_shared<StateInterface>(descr);
246  system_states_.insert(std::make_pair(name, state_interface));
247  gpio_states_.push_back(state_interface);
248  state_interfaces.push_back(std::const_pointer_cast<const StateInterface>(state_interface));
249  }
250  return state_interfaces;
251  }
252 
254 
265  [[deprecated(
266  "Replaced by vector<CommandInterface::SharedPtr> on_export_command_interfaces() method. "
267  "Exporting is "
268  "handled "
269  "by the Framework.")]] virtual std::vector<CommandInterface>
271  {
272  // return empty vector by default. For backward compatibility we try calling
273  // export_command_interfaces() and only when empty vector is returned call
274  // on_export_command_interfaces()
275  return {};
276  }
277 
284  virtual std::vector<hardware_interface::InterfaceDescription>
286  {
287  // return empty vector by default.
288  return {};
289  }
290 
298  virtual std::vector<CommandInterface::SharedPtr> on_export_command_interfaces()
299  {
300  // import the unlisted interfaces
301  std::vector<hardware_interface::InterfaceDescription> unlisted_interface_descriptions =
303 
304  std::vector<CommandInterface::SharedPtr> command_interfaces;
305  command_interfaces.reserve(
306  unlisted_interface_descriptions.size() + joint_command_interfaces_.size() +
307  gpio_command_interfaces_.size());
308 
309  // add InterfaceDescriptions and create the CommandInterfaces from the descriptions and add to
310  // maps.
311  for (const auto & description : unlisted_interface_descriptions)
312  {
313  auto name = description.get_name();
314  unlisted_command_interfaces_.insert(std::make_pair(name, description));
315  auto command_interface = std::make_shared<CommandInterface>(description);
316  system_commands_.insert(std::make_pair(name, command_interface));
317  unlisted_commands_.push_back(command_interface);
318  command_interfaces.push_back(command_interface);
319  }
320 
321  for (const auto & [name, descr] : joint_command_interfaces_)
322  {
323  auto command_interface = std::make_shared<CommandInterface>(descr);
324  system_commands_.insert(std::make_pair(name, command_interface));
325  joint_commands_.push_back(command_interface);
326  command_interfaces.push_back(command_interface);
327  }
328 
329  for (const auto & [name, descr] : gpio_command_interfaces_)
330  {
331  auto command_interface = std::make_shared<CommandInterface>(descr);
332  system_commands_.insert(std::make_pair(name, command_interface));
333  gpio_commands_.push_back(command_interface);
334  command_interfaces.push_back(command_interface);
335  }
336  return command_interfaces;
337  }
338 
340 
352  virtual return_type prepare_command_mode_switch(
353  const std::vector<std::string> & /*start_interfaces*/,
354  const std::vector<std::string> & /*stop_interfaces*/)
355  {
356  return return_type::OK;
357  }
358 
359  // Perform switching to the new command interface.
371  virtual return_type perform_command_mode_switch(
372  const std::vector<std::string> & /*start_interfaces*/,
373  const std::vector<std::string> & /*stop_interfaces*/)
374  {
375  return return_type::OK;
376  }
377 
379 
389  return_type trigger_read(const rclcpp::Time & time, const rclcpp::Duration & period)
390  {
391  return_type result = return_type::ERROR;
392  if (info_.is_async)
393  {
394  bool trigger_status = true;
395  if (next_trigger_ == TriggerType::WRITE)
396  {
397  RCLCPP_WARN(
398  get_logger(),
399  "Trigger read called while write async handler call is still pending for hardware "
400  "interface : '%s'. Skipping read cycle and will wait for a write cycle!",
401  info_.name.c_str());
402  return return_type::OK;
403  }
404  std::tie(trigger_status, result) = async_handler_->trigger_async_callback(time, period);
405  if (!trigger_status)
406  {
407  RCLCPP_WARN(
408  get_logger(),
409  "Trigger read called while write async trigger is still in progress for hardware "
410  "interface : '%s'. Failed to trigger read cycle!",
411  info_.name.c_str());
412  return return_type::OK;
413  }
414  }
415  else
416  {
417  result = read(time, period);
418  }
419  return result;
420  }
421 
423 
432  virtual return_type read(const rclcpp::Time & time, const rclcpp::Duration & period) = 0;
433 
435 
444  return_type trigger_write(const rclcpp::Time & time, const rclcpp::Duration & period)
445  {
446  return_type result = return_type::ERROR;
447  if (info_.is_async)
448  {
449  bool trigger_status = true;
450  if (next_trigger_ == TriggerType::READ)
451  {
452  RCLCPP_WARN(
453  get_logger(),
454  "Trigger write called while read async handler call is still pending for hardware "
455  "interface : '%s'. Skipping write cycle and will wait for a read cycle!",
456  info_.name.c_str());
457  return return_type::OK;
458  }
459  std::tie(trigger_status, result) = async_handler_->trigger_async_callback(time, period);
460  if (!trigger_status)
461  {
462  RCLCPP_WARN(
463  get_logger(),
464  "Trigger write called while read async trigger is still in progress for hardware "
465  "interface : '%s'. Failed to trigger write cycle!",
466  info_.name.c_str());
467  return return_type::OK;
468  }
469  }
470  else
471  {
472  result = write(time, period);
473  }
474  return result;
475  }
476 
478 
486  virtual return_type write(const rclcpp::Time & time, const rclcpp::Duration & period) = 0;
487 
489 
492  virtual std::string get_name() const { return info_.name; }
493 
495 
498  virtual std::string get_group_name() const { return info_.group; }
499 
501 
504  const rclcpp_lifecycle::State & get_lifecycle_state() const { return lifecycle_state_; }
505 
507 
510  void set_lifecycle_state(const rclcpp_lifecycle::State & new_state)
511  {
512  lifecycle_state_ = new_state;
513  }
514 
515  void set_state(const std::string & interface_name, const double & value)
516  {
517  system_states_.at(interface_name)->set_value(value);
518  }
519 
520  double get_state(const std::string & interface_name) const
521  {
522  return system_states_.at(interface_name)->get_value();
523  }
524 
525  void set_command(const std::string & interface_name, const double & value)
526  {
527  system_commands_.at(interface_name)->set_value(value);
528  }
529 
530  double get_command(const std::string & interface_name) const
531  {
532  return system_commands_.at(interface_name)->get_value();
533  }
534 
536 
539  rclcpp::Logger get_logger() const { return system_logger_; }
540 
542 
545  rclcpp::Clock::SharedPtr get_clock() const { return clock_interface_->get_clock(); }
546 
548 
551  const HardwareInfo & get_hardware_info() const { return info_; }
552 
553 protected:
554  HardwareInfo info_;
555  // interface names to InterfaceDescription
556  std::unordered_map<std::string, InterfaceDescription> joint_state_interfaces_;
557  std::unordered_map<std::string, InterfaceDescription> joint_command_interfaces_;
558 
559  std::unordered_map<std::string, InterfaceDescription> sensor_state_interfaces_;
560 
561  std::unordered_map<std::string, InterfaceDescription> gpio_state_interfaces_;
562  std::unordered_map<std::string, InterfaceDescription> gpio_command_interfaces_;
563 
564  std::unordered_map<std::string, InterfaceDescription> unlisted_state_interfaces_;
565  std::unordered_map<std::string, InterfaceDescription> unlisted_command_interfaces_;
566 
567  rclcpp_lifecycle::State lifecycle_state_;
568  std::unique_ptr<realtime_tools::AsyncFunctionHandler<return_type>> async_handler_;
569 
570  // Exported Command- and StateInterfaces in order they are listed in the hardware description.
571  std::vector<StateInterface::SharedPtr> joint_states_;
572  std::vector<CommandInterface::SharedPtr> joint_commands_;
573 
574  std::vector<StateInterface::SharedPtr> sensor_states_;
575 
576  std::vector<StateInterface::SharedPtr> gpio_states_;
577  std::vector<CommandInterface::SharedPtr> gpio_commands_;
578 
579  std::vector<StateInterface::SharedPtr> unlisted_states_;
580  std::vector<CommandInterface::SharedPtr> unlisted_commands_;
581 
582 private:
583  rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock_interface_;
584  rclcpp::Logger system_logger_;
585  // interface names to Handle accessed through getters/setters
586  std::unordered_map<std::string, StateInterface::SharedPtr> system_states_;
587  std::unordered_map<std::string, CommandInterface::SharedPtr> system_commands_;
588  enum class TriggerType
589  {
590  READ,
591  WRITE
592  };
593  std::atomic<TriggerType> next_trigger_ = TriggerType::READ;
594 };
595 
596 } // namespace hardware_interface
597 #endif // HARDWARE_INTERFACE__SYSTEM_INTERFACE_HPP_
Definition: system_interface.hpp:82
virtual std::vector< hardware_interface::InterfaceDescription > export_unlisted_state_interface_descriptions()
Definition: system_interface.hpp:193
virtual std::vector< CommandInterface > export_command_interfaces()
Exports all command interfaces for this hardware interface.
Definition: system_interface.hpp:270
return_type 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:389
virtual return_type perform_command_mode_switch(const std::vector< std::string > &, const std::vector< std::string > &)
Definition: system_interface.hpp:371
virtual std::vector< CommandInterface::SharedPtr > on_export_command_interfaces()
Definition: system_interface.hpp:298
virtual std::string get_group_name() const
Get name of the actuator hardware group to which it belongs to.
Definition: system_interface.hpp:498
virtual std::string get_name() const
Get name of the actuator hardware.
Definition: system_interface.hpp:492
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:151
rclcpp::Logger get_logger() const
Get the logger of the SystemInterface.
Definition: system_interface.hpp:539
return_type 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:444
void set_lifecycle_state(const rclcpp_lifecycle::State &new_state)
Set life-cycle state of the actuator hardware.
Definition: system_interface.hpp:510
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:352
const HardwareInfo & get_hardware_info() const
Get the hardware info of the SystemInterface.
Definition: system_interface.hpp:551
rclcpp::Clock::SharedPtr get_clock() const
Get the clock of the SystemInterface.
Definition: system_interface.hpp:545
CallbackReturn init(const HardwareInfo &hardware_info, rclcpp::Logger logger, rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock_interface)
Definition: system_interface.hpp:111
virtual std::vector< StateInterface::ConstSharedPtr > on_export_state_interfaces()
Definition: system_interface.hpp:206
virtual std::vector< StateInterface > export_state_interfaces()
Exports all state interfaces for this hardware interface.
Definition: system_interface.hpp:178
const rclcpp_lifecycle::State & get_lifecycle_state() const
Get life-cycle state of the actuator hardware.
Definition: system_interface.hpp:504
virtual return_type read(const rclcpp::Time &time, const rclcpp::Duration &period)=0
Read the current state values from the actuator.
virtual std::vector< hardware_interface::InterfaceDescription > export_unlisted_command_interface_descriptions()
Definition: system_interface.hpp:285
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
HARDWARE_INTERFACE_PUBLIC std::vector< InterfaceDescription > parse_command_interface_descriptions(const std::vector< ComponentInfo > &component_info)
Definition: component_parser.cpp:1031
HARDWARE_INTERFACE_PUBLIC std::vector< InterfaceDescription > parse_state_interface_descriptions(const std::vector< ComponentInfo > &component_info)
Definition: component_parser.cpp:998
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn CallbackReturn
Virtual Class to implement when integrating a 1 DoF actuator into ros2_control.
Definition: actuator_interface.hpp:76
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