66 static constexpr bool kWaitForAllResources =
false;
67 static constexpr auto kInfiniteTimeout = 0;
69 CONTROLLER_MANAGER_PUBLIC
71 std::unique_ptr<hardware_interface::ResourceManager> resource_manager,
72 std::shared_ptr<rclcpp::Executor> executor,
73 const std::string & manager_node_name =
"controller_manager",
74 const std::string & namespace_ =
"",
75 const rclcpp::NodeOptions & options = get_cm_node_options());
77 CONTROLLER_MANAGER_PUBLIC
79 std::shared_ptr<rclcpp::Executor> executor,
80 const std::string & manager_node_name =
"controller_manager",
81 const std::string & namespace_ =
"",
82 const rclcpp::NodeOptions & options = get_cm_node_options());
84 CONTROLLER_MANAGER_PUBLIC
87 CONTROLLER_MANAGER_PUBLIC
88 void robot_description_callback(
const std_msgs::msg::String & msg);
90 CONTROLLER_MANAGER_PUBLIC
91 void init_resource_manager(
const std::string & robot_description);
93 CONTROLLER_MANAGER_PUBLIC
94 controller_interface::ControllerInterfaceBaseSharedPtr load_controller(
95 const std::string & controller_name,
const std::string & controller_type);
103 CONTROLLER_MANAGER_PUBLIC
104 controller_interface::ControllerInterfaceBaseSharedPtr load_controller(
105 const std::string & controller_name);
107 CONTROLLER_MANAGER_PUBLIC
108 controller_interface::return_type unload_controller(
const std::string & controller_name);
110 CONTROLLER_MANAGER_PUBLIC
111 std::vector<ControllerSpec> get_loaded_controllers()
const;
114 typename T,
typename std::enable_if<
115 std::is_convertible<T *, controller_interface::ControllerInterfaceBase *>::value,
116 T>::type * =
nullptr>
117 controller_interface::ControllerInterfaceBaseSharedPtr add_controller(
118 std::shared_ptr<T> controller,
const std::string & controller_name,
119 const std::string & controller_type)
122 controller_spec.c = controller;
123 controller_spec.info.
name = controller_name;
124 controller_spec.info.
type = controller_type;
125 controller_spec.last_update_cycle_time = std::make_shared<rclcpp::Time>(0);
126 return add_controller_impl(controller_spec);
135 CONTROLLER_MANAGER_PUBLIC
145 CONTROLLER_MANAGER_PUBLIC
149 bool activate_asap = kWaitForAllResources,
150 const rclcpp::Duration & timeout = rclcpp::Duration::from_nanoseconds(kInfiniteTimeout));
160 CONTROLLER_MANAGER_PUBLIC
161 void read(
const rclcpp::Time & time,
const rclcpp::Duration & period);
171 CONTROLLER_MANAGER_PUBLIC
172 controller_interface::return_type
update(
173 const rclcpp::Time & time,
const rclcpp::Duration & period);
183 CONTROLLER_MANAGER_PUBLIC
184 void write(
const rclcpp::Time & time,
const rclcpp::Duration & period);
196 CONTROLLER_MANAGER_PUBLIC
200 CONTROLLER_MANAGER_PUBLIC
201 void init_services();
203 CONTROLLER_MANAGER_PUBLIC
204 controller_interface::ControllerInterfaceBaseSharedPtr add_controller_impl(
207 CONTROLLER_MANAGER_PUBLIC
208 void manage_switch();
218 CONTROLLER_MANAGER_PUBLIC
220 const std::vector<ControllerSpec> & rt_controller_list,
221 const std::vector<std::string> controllers_to_deactivate);
231 CONTROLLER_MANAGER_PUBLIC
233 const std::vector<std::string> & chained_mode_switch_list,
bool to_chained_mode);
243 CONTROLLER_MANAGER_PUBLIC
245 const std::vector<ControllerSpec> & rt_controller_list,
246 const std::vector<std::string> controllers_to_activate);
259 CONTROLLER_MANAGER_PUBLIC
261 const std::vector<ControllerSpec> & rt_controller_list,
262 const std::vector<std::string> controllers_to_activate);
264 CONTROLLER_MANAGER_PUBLIC
265 void list_controllers_srv_cb(
266 const std::shared_ptr<controller_manager_msgs::srv::ListControllers::Request> request,
267 std::shared_ptr<controller_manager_msgs::srv::ListControllers::Response> response);
269 CONTROLLER_MANAGER_PUBLIC
270 void list_hardware_interfaces_srv_cb(
271 const std::shared_ptr<controller_manager_msgs::srv::ListHardwareInterfaces::Request> request,
272 std::shared_ptr<controller_manager_msgs::srv::ListHardwareInterfaces::Response> response);
274 CONTROLLER_MANAGER_PUBLIC
275 void load_controller_service_cb(
276 const std::shared_ptr<controller_manager_msgs::srv::LoadController::Request> request,
277 std::shared_ptr<controller_manager_msgs::srv::LoadController::Response> response);
279 CONTROLLER_MANAGER_PUBLIC
280 void configure_controller_service_cb(
281 const std::shared_ptr<controller_manager_msgs::srv::ConfigureController::Request> request,
282 std::shared_ptr<controller_manager_msgs::srv::ConfigureController::Response> response);
284 CONTROLLER_MANAGER_PUBLIC
285 void reload_controller_libraries_service_cb(
286 const std::shared_ptr<controller_manager_msgs::srv::ReloadControllerLibraries::Request> request,
287 std::shared_ptr<controller_manager_msgs::srv::ReloadControllerLibraries::Response> response);
289 CONTROLLER_MANAGER_PUBLIC
290 void switch_controller_service_cb(
291 const std::shared_ptr<controller_manager_msgs::srv::SwitchController::Request> request,
292 std::shared_ptr<controller_manager_msgs::srv::SwitchController::Response> response);
294 CONTROLLER_MANAGER_PUBLIC
295 void unload_controller_service_cb(
296 const std::shared_ptr<controller_manager_msgs::srv::UnloadController::Request> request,
297 std::shared_ptr<controller_manager_msgs::srv::UnloadController::Response> response);
299 CONTROLLER_MANAGER_PUBLIC
300 void list_controller_types_srv_cb(
301 const std::shared_ptr<controller_manager_msgs::srv::ListControllerTypes::Request> request,
302 std::shared_ptr<controller_manager_msgs::srv::ListControllerTypes::Response> response);
304 CONTROLLER_MANAGER_PUBLIC
305 void list_hardware_components_srv_cb(
306 const std::shared_ptr<controller_manager_msgs::srv::ListHardwareComponents::Request> request,
307 std::shared_ptr<controller_manager_msgs::srv::ListHardwareComponents::Response> response);
309 CONTROLLER_MANAGER_PUBLIC
310 void set_hardware_component_state_srv_cb(
311 const std::shared_ptr<controller_manager_msgs::srv::SetHardwareComponentState::Request> request,
312 std::shared_ptr<controller_manager_msgs::srv::SetHardwareComponentState::Response> response);
315 unsigned int update_loop_counter_ = 0;
316 unsigned int update_rate_ = 100;
317 std::vector<std::vector<std::string>> chained_controllers_configuration_;
319 std::unique_ptr<hardware_interface::ResourceManager> resource_manager_;
322 std::vector<std::string> get_controller_names();
323 std::pair<std::string, std::string> split_command_interface(
324 const std::string & command_interface);
325 void subscribe_to_robot_description_topic();
331 void clear_requests();
339 void propagate_deactivation_of_chained_mode(
const std::vector<ControllerSpec> & controllers);
366 controller_interface::return_type check_following_controllers_for_activate(
367 const std::vector<ControllerSpec> & controllers,
int strictness,
368 const ControllersListIterator controller_it);
389 controller_interface::return_type check_preceeding_controllers_for_deactivate(
390 const std::vector<ControllerSpec> & controllers,
int strictness,
391 const ControllersListIterator controller_it);
412 bool controller_sorting(
414 const std::vector<controller_manager::ControllerSpec> & controllers);
416 void controller_activity_diagnostic_callback(diagnostic_updater::DiagnosticStatusWrapper & stat);
425 rclcpp::NodeOptions determine_controller_node_options(
const ControllerSpec & controller)
const;
427 diagnostic_updater::Updater diagnostics_updater_;
429 std::shared_ptr<rclcpp::Executor> executor_;
431 std::shared_ptr<pluginlib::ClassLoader<controller_interface::ControllerInterface>> loader_;
432 std::shared_ptr<pluginlib::ClassLoader<controller_interface::ChainableControllerInterface>>
440 rclcpp::CallbackGroup::SharedPtr best_effort_callback_group_;
453 class RTControllerListWrapper
464 std::vector<ControllerSpec> & update_and_get_used_by_rt_list();
474 std::vector<ControllerSpec> & get_unused_list(
475 const std::lock_guard<std::recursive_mutex> & guard);
483 const std::vector<ControllerSpec> & get_updated_list(
484 const std::lock_guard<std::recursive_mutex> & guard)
const;
492 void switch_updated_list(
const std::lock_guard<std::recursive_mutex> & guard);
496 mutable std::recursive_mutex controllers_lock_;
505 int get_other_list(
int index)
const;
507 void wait_until_rt_not_using(
508 int index, std::chrono::microseconds sleep_delay = std::chrono::microseconds(200))
const;
510 std::vector<ControllerSpec> controllers_lists_[2];
512 int updated_controllers_index_ = 0;
514 int used_by_realtime_controllers_index_ = -1;
517 RTControllerListWrapper rt_controllers_wrapper_;
520 std::mutex services_lock_;
521 rclcpp::Service<controller_manager_msgs::srv::ListControllers>::SharedPtr
522 list_controllers_service_;
523 rclcpp::Service<controller_manager_msgs::srv::ListControllerTypes>::SharedPtr
524 list_controller_types_service_;
525 rclcpp::Service<controller_manager_msgs::srv::LoadController>::SharedPtr load_controller_service_;
526 rclcpp::Service<controller_manager_msgs::srv::ConfigureController>::SharedPtr
527 configure_controller_service_;
528 rclcpp::Service<controller_manager_msgs::srv::ReloadControllerLibraries>::SharedPtr
529 reload_controller_libraries_service_;
530 rclcpp::Service<controller_manager_msgs::srv::SwitchController>::SharedPtr
531 switch_controller_service_;
532 rclcpp::Service<controller_manager_msgs::srv::UnloadController>::SharedPtr
533 unload_controller_service_;
535 rclcpp::Service<controller_manager_msgs::srv::ListHardwareComponents>::SharedPtr
536 list_hardware_components_service_;
537 rclcpp::Service<controller_manager_msgs::srv::ListHardwareInterfaces>::SharedPtr
538 list_hardware_interfaces_service_;
539 rclcpp::Service<controller_manager_msgs::srv::SetHardwareComponentState>::SharedPtr
540 set_hardware_component_state_service_;
542 std::vector<std::string> activate_request_, deactivate_request_;
543 std::vector<std::string> to_chained_mode_request_, from_chained_mode_request_;
544 std::vector<std::string> activate_command_interface_request_,
545 deactivate_command_interface_request_;
547 rclcpp::Subscription<std_msgs::msg::String>::SharedPtr robot_description_subscription_;
556 activate_asap =
false;
565 std::chrono::nanoseconds timeout;
568 std::condition_variable cv;
572 SwitchParams switch_params_;
574 class ControllerThreadWrapper
577 ControllerThreadWrapper(
578 std::shared_ptr<controller_interface::ControllerInterfaceBase> & controller,
580 : terminated_(
false), controller_(controller), thread_{}, cm_update_rate_(cm_update_rate)
584 ControllerThreadWrapper(
const ControllerThreadWrapper & t) =
delete;
585 ControllerThreadWrapper(ControllerThreadWrapper && t) =
default;
586 ~ControllerThreadWrapper()
588 terminated_.store(
true, std::memory_order_seq_cst);
589 if (thread_.joinable())
597 thread_ = std::thread(&ControllerThreadWrapper::call_controller_update,
this);
600 void call_controller_update()
602 using TimePoint = std::chrono::system_clock::time_point;
603 unsigned int used_update_rate =
604 controller_->get_update_rate() == 0
609 while (!terminated_.load(std::memory_order_relaxed))
611 auto const period = std::chrono::nanoseconds(1'000'000'000 / used_update_rate);
612 TimePoint next_iteration_time =
613 TimePoint(std::chrono::nanoseconds(controller_->get_node()->now().nanoseconds()));
615 if (controller_->get_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE)
620 next_iteration_time += period;
621 std::this_thread::sleep_until(next_iteration_time);
626 std::atomic<bool> terminated_;
627 std::shared_ptr<controller_interface::ControllerInterfaceBase> controller_;
629 unsigned int cm_update_rate_;
632 std::unordered_map<std::string, std::unique_ptr<ControllerThreadWrapper>>
633 async_controller_threads_;