ros2_control - rolling
resource_manager.hpp
1 // Copyright 2020 Open Source Robotics Foundation, Inc.
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__RESOURCE_MANAGER_HPP_
16 #define HARDWARE_INTERFACE__RESOURCE_MANAGER_HPP_
17 
18 #include <memory>
19 #include <string>
20 #include <unordered_map>
21 #include <vector>
22 
23 #include "hardware_interface/actuator.hpp"
24 #include "hardware_interface/hardware_component_info.hpp"
25 #include "hardware_interface/hardware_info.hpp"
26 #include "hardware_interface/loaned_command_interface.hpp"
27 #include "hardware_interface/loaned_state_interface.hpp"
28 #include "hardware_interface/sensor.hpp"
29 #include "hardware_interface/system.hpp"
30 #include "hardware_interface/system_interface.hpp"
31 #include "hardware_interface/types/hardware_interface_return_values.hpp"
32 #include "rclcpp/duration.hpp"
33 #include "rclcpp/node_interfaces/node_logging_interface.hpp"
34 #include "rclcpp/time.hpp"
35 
36 namespace hardware_interface
37 {
38 class ResourceStorage;
39 class ControllerManager;
40 
42 {
43  bool ok;
44  std::vector<std::string> failed_hardware_names;
45 };
46 
47 class HARDWARE_INTERFACE_PUBLIC ResourceManager
48 {
49 public:
51  explicit ResourceManager(
52  rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock_interface,
53  rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr logger_interface);
54 
56 
69  explicit ResourceManager(
70  const std::string & urdf,
71  rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock_interface,
72  rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr logger_interface,
73  bool activate_all = false, const unsigned int update_rate = 100);
74 
75  ResourceManager(const ResourceManager &) = delete;
76 
77  virtual ~ResourceManager();
78 
80 
89  virtual bool load_and_initialize_components(
90  const std::string & urdf, const unsigned int update_rate = 100);
91 
100  bool are_components_initialized() const;
101 
103 
111  LoanedStateInterface claim_state_interface(const std::string & key);
112 
114 
118  std::vector<std::string> state_interface_keys() const;
119 
121 
125  std::vector<std::string> available_state_interfaces() const;
126 
128 
131  bool state_interface_is_available(const std::string & name) const;
132 
134 
143  void import_controller_exported_state_interfaces(
144  const std::string & controller_name, std::vector<StateInterface::ConstSharedPtr> & interfaces);
145 
147 
153  std::vector<std::string> get_controller_exported_state_interface_names(
154  const std::string & controller_name);
155 
157 
165  void make_controller_exported_state_interfaces_available(const std::string & controller_name);
166 
168 
175  void make_controller_exported_state_interfaces_unavailable(const std::string & controller_name);
176 
178 
184  void remove_controller_exported_state_interfaces(const std::string & controller_name);
185 
187 
196  void import_controller_reference_interfaces(
197  const std::string & controller_name,
198  const std::vector<hardware_interface::CommandInterface::SharedPtr> & interfaces);
199 
201 
207  std::vector<std::string> get_controller_reference_interface_names(
208  const std::string & controller_name);
209 
211 
218  void make_controller_reference_interfaces_available(const std::string & controller_name);
219 
221 
228  void make_controller_reference_interfaces_unavailable(const std::string & controller_name);
229 
231 
237  void remove_controller_reference_interfaces(const std::string & controller_name);
238 
240 
247  void cache_controller_to_hardware(
248  const std::string & controller_name, const std::vector<std::string> & interfaces);
249 
251 
258  std::vector<std::string> get_cached_controllers_to_hardware(const std::string & hardware_name);
259 
261 
269  bool command_interface_is_claimed(const std::string & key) const;
270 
272 
280  LoanedCommandInterface claim_command_interface(const std::string & key);
281 
283 
287  std::vector<std::string> command_interface_keys() const;
288 
290 
294  std::vector<std::string> available_command_interfaces() const;
295 
297 
301  bool command_interface_is_available(const std::string & interface) const;
302 
304 
307  size_t actuator_components_size() const;
308 
310 
313  size_t sensor_components_size() const;
314 
316 
319  size_t system_components_size() const;
320 
322 
334  void import_component(
335  std::unique_ptr<ActuatorInterface> actuator, const HardwareInfo & hardware_info);
336 
338 
350  void import_component(
351  std::unique_ptr<SensorInterface> sensor, const HardwareInfo & hardware_info);
352 
354 
366  void import_component(
367  std::unique_ptr<SystemInterface> system, const HardwareInfo & hardware_info);
368 
370 
373  std::unordered_map<std::string, HardwareComponentInfo> get_components_status();
374 
376 
392  bool prepare_command_mode_switch(
393  const std::vector<std::string> & start_interfaces,
394  const std::vector<std::string> & stop_interfaces);
395 
397 
409  bool perform_command_mode_switch(
410  const std::vector<std::string> & start_interfaces,
411  const std::vector<std::string> & stop_interfaces);
412 
414 
426  return_type set_component_state(
427  const std::string & component_name, rclcpp_lifecycle::State & target_state);
428 
430 
436  HardwareReadWriteStatus read(const rclcpp::Time & time, const rclcpp::Duration & period);
437 
439 
445  HardwareReadWriteStatus write(const rclcpp::Time & time, const rclcpp::Duration & period);
446 
448 
452  bool command_interface_exists(const std::string & key) const;
453 
455 
458  bool state_interface_exists(const std::string & key) const;
459 
460 protected:
462 
465  rclcpp::Logger get_logger() const;
466 
468 
471  rclcpp::Clock::SharedPtr get_clock() const;
472 
473  bool components_are_loaded_and_initialized_ = false;
474 
475  mutable std::recursive_mutex resource_interfaces_lock_;
476  mutable std::recursive_mutex claimed_command_interfaces_lock_;
477  mutable std::recursive_mutex resources_lock_;
478 
479 private:
480  bool validate_storage(const std::vector<hardware_interface::HardwareInfo> & hardware_info) const;
481 
482  void release_command_interface(const std::string & key);
483 
484  std::unordered_map<std::string, bool> claimed_command_interface_map_;
485 
486  std::unique_ptr<ResourceStorage> resource_storage_;
487 
488  // Structure to store read and write status so it is not initialized in the real-time loop
489  HardwareReadWriteStatus read_write_status;
490 };
491 
492 } // namespace hardware_interface
493 #endif // HARDWARE_INTERFACE__RESOURCE_MANAGER_HPP_
Definition: loaned_command_interface.hpp:30
Definition: loaned_state_interface.hpp:29
Definition: resource_manager.hpp:48
Definition: actuator.hpp:34
This structure stores information about hardware defined in a robot's URDF.
Definition: hardware_info.hpp:170
Definition: resource_manager.hpp:42