64 static constexpr bool kWaitForAllResources =
false;
65 static constexpr auto kInfiniteTimeout = 0;
68 std::unique_ptr<hardware_interface::ResourceManager> resource_manager,
69 std::shared_ptr<rclcpp::Executor> executor,
70 const std::string & manager_node_name =
"controller_manager",
71 const std::string & node_namespace =
"",
72 const rclcpp::NodeOptions & options = get_cm_node_options());
75 std::shared_ptr<rclcpp::Executor> executor,
76 const std::string & manager_node_name =
"controller_manager",
77 const std::string & node_namespace =
"",
78 const rclcpp::NodeOptions & options = get_cm_node_options());
81 std::shared_ptr<rclcpp::Executor> executor,
const std::string & urdf,
82 bool activate_all_hw_components,
const std::string & manager_node_name =
"controller_manager",
83 const std::string & node_namespace =
"",
84 const rclcpp::NodeOptions & options = get_cm_node_options());
94 void robot_description_callback(
const std_msgs::msg::String & msg);
96 void init_resource_manager(
const std::string & robot_description);
98 controller_interface::ControllerInterfaceBaseSharedPtr load_controller(
99 const std::string & controller_name,
const std::string & controller_type);
107 controller_interface::ControllerInterfaceBaseSharedPtr load_controller(
108 const std::string & controller_name);
110 controller_interface::return_type unload_controller(
const std::string & controller_name);
112 controller_interface::return_type cleanup_controller(
const std::string & controller_name);
114 std::vector<ControllerSpec> get_loaded_controllers()
const;
117 typename T,
typename std::enable_if<
118 std::is_convertible<T *, controller_interface::ControllerInterfaceBase *>::value,
119 T>::type * =
nullptr>
120 controller_interface::ControllerInterfaceBaseSharedPtr add_controller(
121 std::shared_ptr<T> controller,
const std::string & controller_name,
122 const std::string & controller_type)
125 controller_spec.c = controller;
126 controller_spec.info.
name = controller_name;
127 controller_spec.info.
type = controller_type;
128 controller_spec.last_update_cycle_time = std::make_shared<rclcpp::Time>(0);
129 return add_controller_impl(controller_spec);
132 controller_interface::ControllerInterfaceBaseSharedPtr add_controller(
135 return add_controller_impl(controller_spec);
158 bool activate_asap = kWaitForAllResources,
159 const rclcpp::Duration & timeout = rclcpp::Duration::from_nanoseconds(kInfiniteTimeout));
174 const rclcpp::Duration & timeout, std::string & message);
184 void read(
const rclcpp::Time & time,
const rclcpp::Duration & period);
194 controller_interface::return_type
update(
195 const rclcpp::Time & time,
const rclcpp::Duration & period);
205 void write(
const rclcpp::Time & time,
const rclcpp::Duration & period);
223 return resource_manager_ && resource_manager_->are_components_initialized();
249 void init_services();
251 controller_interface::ControllerInterfaceBaseSharedPtr add_controller_impl(
254 void manage_switch();
265 const std::vector<ControllerSpec> & rt_controller_list,
266 const std::vector<std::string> & controllers_to_deactivate);
277 const std::vector<std::string> & chained_mode_switch_list,
bool to_chained_mode);
289 const std::vector<ControllerSpec> & rt_controller_list,
290 const std::vector<std::string> & controllers_to_activate,
int strictness);
292 void list_controllers_srv_cb(
293 const std::shared_ptr<controller_manager_msgs::srv::ListControllers::Request> request,
294 std::shared_ptr<controller_manager_msgs::srv::ListControllers::Response> response);
296 void list_hardware_interfaces_srv_cb(
297 const std::shared_ptr<controller_manager_msgs::srv::ListHardwareInterfaces::Request> request,
298 std::shared_ptr<controller_manager_msgs::srv::ListHardwareInterfaces::Response> response);
300 void load_controller_service_cb(
301 const std::shared_ptr<controller_manager_msgs::srv::LoadController::Request> request,
302 std::shared_ptr<controller_manager_msgs::srv::LoadController::Response> response);
304 void configure_controller_service_cb(
305 const std::shared_ptr<controller_manager_msgs::srv::ConfigureController::Request> request,
306 std::shared_ptr<controller_manager_msgs::srv::ConfigureController::Response> response);
308 void reload_controller_libraries_service_cb(
309 const std::shared_ptr<controller_manager_msgs::srv::ReloadControllerLibraries::Request> request,
310 std::shared_ptr<controller_manager_msgs::srv::ReloadControllerLibraries::Response> response);
312 void switch_controller_service_cb(
313 const std::shared_ptr<controller_manager_msgs::srv::SwitchController::Request> request,
314 std::shared_ptr<controller_manager_msgs::srv::SwitchController::Response> response);
316 void unload_controller_service_cb(
317 const std::shared_ptr<controller_manager_msgs::srv::UnloadController::Request> request,
318 std::shared_ptr<controller_manager_msgs::srv::UnloadController::Response> response);
320 void cleanup_controller_service_cb(
321 const std::shared_ptr<controller_manager_msgs::srv::CleanupController::Request> request,
322 std::shared_ptr<controller_manager_msgs::srv::CleanupController::Response> response);
324 void list_controller_types_srv_cb(
325 const std::shared_ptr<controller_manager_msgs::srv::ListControllerTypes::Request> request,
326 std::shared_ptr<controller_manager_msgs::srv::ListControllerTypes::Response> response);
328 void list_hardware_components_srv_cb(
329 const std::shared_ptr<controller_manager_msgs::srv::ListHardwareComponents::Request> request,
330 std::shared_ptr<controller_manager_msgs::srv::ListHardwareComponents::Response> response);
332 void set_hardware_component_state_srv_cb(
333 const std::shared_ptr<controller_manager_msgs::srv::SetHardwareComponentState::Request> request,
334 std::shared_ptr<controller_manager_msgs::srv::SetHardwareComponentState::Response> response);
337 unsigned int update_loop_counter_ = 0;
338 unsigned int update_rate_;
339 std::vector<std::vector<std::string>> chained_controllers_configuration_;
341 std::unique_ptr<hardware_interface::ResourceManager> resource_manager_;
344 std::vector<std::string> get_controller_names();
345 std::pair<std::string, std::string> split_command_interface(
346 const std::string & command_interface);
347 void init_controller_manager();
349 void initialize_parameters();
356 controller_interface::return_type cleanup_controller(
370 void clear_requests();
382 void perform_hardware_command_mode_change(
383 const std::vector<ControllerSpec> & rt_controller_list,
384 const std::vector<std::string> & activate_controllers_list,
385 const std::vector<std::string> & deactivate_controllers_list,
386 const std::string & rt_cycle_name);
394 void propagate_deactivation_of_chained_mode(
const std::vector<ControllerSpec> & controllers);
422 controller_interface::return_type check_following_controllers_for_activate(
423 const std::vector<ControllerSpec> & controllers,
int strictness,
424 const ControllersListIterator controller_it, std::string & message);
446 controller_interface::return_type check_preceding_controllers_for_deactivate(
447 const std::vector<ControllerSpec> & controllers,
int strictness,
448 const ControllersListIterator controller_it, std::string & message);
459 controller_interface::return_type check_fallback_controllers_state_pre_activation(
460 const std::vector<ControllerSpec> & controllers,
const ControllersListIterator controller_it,
461 std::string & message);
472 controller_interface::return_type check_for_interfaces_availability_to_activate(
473 const std::vector<ControllerSpec> & controllers,
const std::vector<std::string> activation_list,
474 const std::vector<std::string> deactivation_list, std::string & message);
495 void update_list_with_controller_chain(
496 const std::string & ctrl_name, std::vector<std::string>::iterator controller_iterator,
497 bool append_to_controller);
505 void build_controllers_topology_info(
const std::vector<ControllerSpec> & controllers);
512 void publish_activity();
514 void controller_activity_diagnostic_callback(diagnostic_updater::DiagnosticStatusWrapper & stat);
516 void hardware_components_diagnostic_callback(diagnostic_updater::DiagnosticStatusWrapper & stat);
518 void controller_manager_diagnostic_callback(diagnostic_updater::DiagnosticStatusWrapper & stat);
527 rclcpp::NodeOptions determine_controller_node_options(
const ControllerSpec & controller)
const;
534 void cleanup_controller_exported_interfaces(
const ControllerSpec & controller);
536 std::shared_ptr<controller_manager::ParamListener> cm_param_listener_;
537 std::shared_ptr<controller_manager::Params> params_;
538 diagnostic_updater::Updater diagnostics_updater_;
540 std::shared_ptr<rclcpp::Executor> executor_;
542 std::shared_ptr<pluginlib::ClassLoader<controller_interface::ControllerInterface>> loader_;
543 std::shared_ptr<pluginlib::ClassLoader<controller_interface::ChainableControllerInterface>>
551 rclcpp::CallbackGroup::SharedPtr best_effort_callback_group_;
564 class RTControllerListWrapper
575 std::vector<ControllerSpec> & update_and_get_used_by_rt_list();
585 std::vector<ControllerSpec> & get_unused_list(
586 const std::lock_guard<std::recursive_mutex> & guard);
594 const std::vector<ControllerSpec> & get_updated_list(
595 const std::lock_guard<std::recursive_mutex> & guard)
const;
603 void switch_updated_list(
const std::lock_guard<std::recursive_mutex> & guard);
609 void set_on_switch_callback(std::function<
void()> callback);
613 mutable std::recursive_mutex controllers_lock_;
622 int get_other_list(
int index)
const;
624 void wait_until_rt_not_using(
625 int index, std::chrono::microseconds sleep_delay = std::chrono::microseconds(200))
const;
627 std::vector<ControllerSpec> controllers_lists_[2];
629 int updated_controllers_index_ = 0;
631 int used_by_realtime_controllers_index_ = -1;
633 std::function<void()> on_switch_callback_ =
nullptr;
637 rclcpp::Clock::SharedPtr trigger_clock_ =
nullptr;
638 std::unique_ptr<rclcpp::PreShutdownCallbackHandle> preshutdown_cb_handle_{
nullptr};
639 RTControllerListWrapper rt_controllers_wrapper_;
640 std::unordered_map<std::string, ControllerChainSpec> controller_chain_spec_;
641 std::vector<std::string> ordered_controllers_names_;
644 std::mutex services_lock_;
645 rclcpp::Publisher<controller_manager_msgs::msg::ControllerManagerActivity>::SharedPtr
646 controller_manager_activity_publisher_;
647 rclcpp::Service<controller_manager_msgs::srv::ListControllers>::SharedPtr
648 list_controllers_service_;
649 rclcpp::Service<controller_manager_msgs::srv::ListControllerTypes>::SharedPtr
650 list_controller_types_service_;
651 rclcpp::Service<controller_manager_msgs::srv::LoadController>::SharedPtr load_controller_service_;
652 rclcpp::Service<controller_manager_msgs::srv::ConfigureController>::SharedPtr
653 configure_controller_service_;
654 rclcpp::Service<controller_manager_msgs::srv::ReloadControllerLibraries>::SharedPtr
655 reload_controller_libraries_service_;
656 rclcpp::Service<controller_manager_msgs::srv::SwitchController>::SharedPtr
657 switch_controller_service_;
658 rclcpp::Service<controller_manager_msgs::srv::UnloadController>::SharedPtr
659 unload_controller_service_;
660 rclcpp::Service<controller_manager_msgs::srv::CleanupController>::SharedPtr
661 cleanup_controller_service_;
663 rclcpp::Service<controller_manager_msgs::srv::ListHardwareComponents>::SharedPtr
664 list_hardware_components_service_;
665 rclcpp::Service<controller_manager_msgs::srv::ListHardwareInterfaces>::SharedPtr
666 list_hardware_interfaces_service_;
667 rclcpp::Service<controller_manager_msgs::srv::SetHardwareComponentState>::SharedPtr
668 set_hardware_component_state_service_;
670 std::map<std::string, std::vector<std::string>> controller_chained_reference_interfaces_cache_;
671 std::map<std::string, std::vector<std::string>> controller_chained_state_interfaces_cache_;
673 std::string robot_description_;
674 rclcpp::Subscription<std_msgs::msg::String>::SharedPtr robot_description_subscription_;
675 rclcpp::TimerBase::SharedPtr robot_description_notification_timer_;
677 struct ControllerManagerExecutionTime
679 double read_time = 0.0;
680 double update_time = 0.0;
681 double write_time = 0.0;
682 double switch_time = 0.0;
683 double total_time = 0.0;
684 double switch_chained_mode_time = 0.0;
685 double switch_perform_mode_time = 0.0;
686 double deactivation_time = 0.0;
687 double activation_time = 0.0;
690 ControllerManagerExecutionTime execution_time_;
700 activate_asap =
false;
701 ready_to_switch =
false;
704 std::atomic_bool do_switch{
false};
705 std::atomic_bool ready_to_switch{
false};
709 std::atomic_bool activate_asap{
false};
710 std::chrono::nanoseconds timeout;
713 std::condition_variable cv;
718 const std::string controller_name = spec.info.
name;
719 return ros2_control::has_item(activate_request, controller_name) ||
720 ros2_control::has_item(deactivate_request, controller_name) ||
721 ros2_control::has_item(to_chained_mode_request, controller_name) ||
722 ros2_control::has_item(from_chained_mode_request, controller_name);
726 std::vector<std::string> activate_request;
727 std::vector<std::string> deactivate_request;
728 std::vector<std::string> to_chained_mode_request;
729 std::vector<std::string> from_chained_mode_request;
730 std::vector<std::string> activate_command_interface_request;
731 std::vector<std::string> deactivate_command_interface_request;
734 SwitchParams switch_params_;
736 struct RTBufferVariables
740 deactivate_controllers_list.reserve(1000);
741 activate_controllers_using_interfaces_list.reserve(1000);
742 fallback_controllers_list.reserve(1000);
743 interfaces_to_start.reserve(1000);
744 interfaces_to_stop.reserve(1000);
745 concatenated_string.reserve(5000);
748 const std::string & get_concatenated_string(
749 const std::vector<std::string> & strings,
bool clear_string =
true)
753 concatenated_string.clear();
755 for (
const auto & str : strings)
757 concatenated_string.append(str);
758 concatenated_string.append(
" ");
760 return concatenated_string;
763 std::vector<std::string> deactivate_controllers_list;
764 std::vector<std::string> activate_controllers_using_interfaces_list;
765 std::vector<std::string> fallback_controllers_list;
766 std::vector<std::string> interfaces_to_start;
767 std::vector<std::string> interfaces_to_stop;
768 std::string concatenated_string;
770 RTBufferVariables rt_buffer_;