.. _program_listing_file_include_hardware_interface_resource_manager.hpp: Program Listing for File resource_manager.hpp ============================================= |exhale_lsh| :ref:`Return to documentation for file ` (``include/hardware_interface/resource_manager.hpp``) .. |exhale_lsh| unicode:: U+021B0 .. UPWARDS ARROW WITH TIP LEFTWARDS .. code-block:: cpp // Copyright 2020 Open Source Robotics Foundation, Inc. // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. // You may obtain a copy of the License at // // http://www.apache.org/licenses/LICENSE-2.0 // // Unless required by applicable law or agreed to in writing, software // distributed under the License is distributed on an "AS IS" BASIS, // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. // See the License for the specific language governing permissions and // limitations under the License. #ifndef HARDWARE_INTERFACE__RESOURCE_MANAGER_HPP_ #define HARDWARE_INTERFACE__RESOURCE_MANAGER_HPP_ #include #include #include #include #include "hardware_interface/actuator.hpp" #include "hardware_interface/hardware_component_info.hpp" #include "hardware_interface/hardware_info.hpp" #include "hardware_interface/loaned_command_interface.hpp" #include "hardware_interface/loaned_state_interface.hpp" #include "hardware_interface/sensor.hpp" #include "hardware_interface/system.hpp" #include "hardware_interface/types/hardware_interface_return_values.hpp" #include "hardware_interface/types/lifecycle_state_names.hpp" #include "lifecycle_msgs/msg/state.hpp" #include "rclcpp/duration.hpp" #include "rclcpp/node.hpp" #include "rclcpp/time.hpp" namespace hardware_interface { class ResourceStorage; class ControllerManager; struct HardwareReadWriteStatus { bool ok; std::vector failed_hardware_names; }; class HARDWARE_INTERFACE_PUBLIC ResourceManager { public: ResourceManager( unsigned int update_rate = 100, rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock_interface = nullptr); explicit ResourceManager( const std::string & urdf, bool validate_interfaces = true, bool activate_all = false, unsigned int update_rate = 100, rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock_interface = nullptr); ResourceManager(const ResourceManager &) = delete; ~ResourceManager(); void load_urdf( const std::string & urdf, bool validate_interfaces = true, bool load_and_initialize_components = true); bool is_urdf_already_loaded() const; LoanedStateInterface claim_state_interface(const std::string & key); std::vector state_interface_keys() const; std::vector available_state_interfaces() const; bool state_interface_is_available(const std::string & name) const; void import_controller_reference_interfaces( const std::string & controller_name, std::vector & interfaces); std::vector get_controller_reference_interface_names( const std::string & controller_name); void make_controller_reference_interfaces_available(const std::string & controller_name); void make_controller_reference_interfaces_unavailable(const std::string & controller_name); void remove_controller_reference_interfaces(const std::string & controller_name); void cache_controller_to_hardware( const std::string & controller_name, const std::vector & interfaces); std::vector get_cached_controllers_to_hardware(const std::string & hardware_name); bool command_interface_is_claimed(const std::string & key) const; LoanedCommandInterface claim_command_interface(const std::string & key); std::vector command_interface_keys() const; std::vector available_command_interfaces() const; bool command_interface_is_available(const std::string & interface) const; size_t actuator_components_size() const; size_t sensor_components_size() const; size_t system_components_size() const; void import_component( std::unique_ptr actuator, const HardwareInfo & hardware_info); void import_component( std::unique_ptr sensor, const HardwareInfo & hardware_info); void import_component( std::unique_ptr system, const HardwareInfo & hardware_info); std::unordered_map get_components_status(); bool prepare_command_mode_switch( const std::vector & start_interfaces, const std::vector & stop_interfaces); bool perform_command_mode_switch( const std::vector & start_interfaces, const std::vector & stop_interfaces); return_type set_component_state( const std::string & component_name, rclcpp_lifecycle::State & target_state); void shutdown_async_components(); HardwareReadWriteStatus read(const rclcpp::Time & time, const rclcpp::Duration & period); HardwareReadWriteStatus write(const rclcpp::Time & time, const rclcpp::Duration & period); bool command_interface_exists(const std::string & key) const; bool state_interface_exists(const std::string & key) const; private: void validate_storage(const std::vector & hardware_info) const; void release_command_interface(const std::string & key); std::unordered_map claimed_command_interface_map_; mutable std::recursive_mutex resource_interfaces_lock_; mutable std::recursive_mutex claimed_command_interfaces_lock_; mutable std::recursive_mutex resources_lock_; std::unique_ptr resource_storage_; // Structure to store read and write status so it is not initialized in the real-time loop HardwareReadWriteStatus read_write_status; bool is_urdf_loaded__ = false; }; } // namespace hardware_interface #endif // HARDWARE_INTERFACE__RESOURCE_MANAGER_HPP_