53 unsigned int update_rate = 100,
54 rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock_interface =
nullptr);
72 const std::string & urdf,
bool validate_interfaces =
true,
bool activate_all =
false,
73 unsigned int update_rate = 100,
74 rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock_interface =
nullptr);
93 const std::string & urdf,
bool validate_interfaces =
true,
94 bool load_and_initialize_components =
true);
104 bool is_urdf_already_loaded()
const;
122 std::vector<std::string> state_interface_keys()
const;
129 std::vector<std::string> available_state_interfaces()
const;
135 bool state_interface_is_available(
const std::string & name)
const;
147 void import_controller_reference_interfaces(
148 const std::string & controller_name, std::vector<CommandInterface> & interfaces);
157 std::vector<std::string> get_controller_reference_interface_names(
158 const std::string & controller_name);
168 void make_controller_reference_interfaces_available(
const std::string & controller_name);
178 void make_controller_reference_interfaces_unavailable(
const std::string & controller_name);
187 void remove_controller_reference_interfaces(
const std::string & controller_name);
197 void cache_controller_to_hardware(
198 const std::string & controller_name,
const std::vector<std::string> & interfaces);
208 std::vector<std::string> get_cached_controllers_to_hardware(
const std::string & hardware_name);
219 bool command_interface_is_claimed(
const std::string & key)
const;
237 std::vector<std::string> command_interface_keys()
const;
244 std::vector<std::string> available_command_interfaces()
const;
251 bool command_interface_is_available(
const std::string & interface)
const;
257 size_t actuator_components_size()
const;
263 size_t sensor_components_size()
const;
269 size_t system_components_size()
const;
284 void import_component(
285 std::unique_ptr<ActuatorInterface> actuator,
const HardwareInfo & hardware_info);
300 void import_component(
301 std::unique_ptr<SensorInterface> sensor,
const HardwareInfo & hardware_info);
316 void import_component(
317 std::unique_ptr<SystemInterface> system,
const HardwareInfo & hardware_info);
323 std::unordered_map<std::string, HardwareComponentInfo> get_components_status();
342 bool prepare_command_mode_switch(
343 const std::vector<std::string> & start_interfaces,
344 const std::vector<std::string> & stop_interfaces);
359 bool perform_command_mode_switch(
360 const std::vector<std::string> & start_interfaces,
361 const std::vector<std::string> & stop_interfaces);
376 return_type set_component_state(
377 const std::string & component_name, rclcpp_lifecycle::State & target_state);
402 bool command_interface_exists(
const std::string & key)
const;
408 bool state_interface_exists(
const std::string & key)
const;
411 void validate_storage(
const std::vector<hardware_interface::HardwareInfo> & hardware_info)
const;
413 void release_command_interface(
const std::string & key);
415 std::unordered_map<std::string, bool> claimed_command_interface_map_;
417 mutable std::recursive_mutex resource_interfaces_lock_;
418 mutable std::recursive_mutex claimed_command_interfaces_lock_;
419 mutable std::recursive_mutex resources_lock_;
421 std::unique_ptr<ResourceStorage> resource_storage_;
426 bool is_urdf_loaded__ =
false;