65 static constexpr bool kWaitForAllResources =
false;
66 static constexpr auto kInfiniteTimeout = 0;
68 CONTROLLER_MANAGER_PUBLIC
70 std::unique_ptr<hardware_interface::ResourceManager> resource_manager,
71 std::shared_ptr<rclcpp::Executor> executor,
72 const std::string & manager_node_name =
"controller_manager",
73 const std::string & namespace_ =
"",
74 const rclcpp::NodeOptions & options = get_cm_node_options());
76 CONTROLLER_MANAGER_PUBLIC
78 std::shared_ptr<rclcpp::Executor> executor,
79 const std::string & manager_node_name =
"controller_manager",
80 const std::string & namespace_ =
"",
81 const rclcpp::NodeOptions & options = get_cm_node_options());
83 CONTROLLER_MANAGER_PUBLIC
90 CONTROLLER_MANAGER_PUBLIC
93 CONTROLLER_MANAGER_PUBLIC
94 void robot_description_callback(
const std_msgs::msg::String & msg);
96 CONTROLLER_MANAGER_PUBLIC
97 void init_resource_manager(
const std::string & robot_description);
99 CONTROLLER_MANAGER_PUBLIC
100 controller_interface::ControllerInterfaceBaseSharedPtr load_controller(
101 const std::string & controller_name,
const std::string & controller_type);
109 CONTROLLER_MANAGER_PUBLIC
110 controller_interface::ControllerInterfaceBaseSharedPtr load_controller(
111 const std::string & controller_name);
113 CONTROLLER_MANAGER_PUBLIC
114 controller_interface::return_type unload_controller(
const std::string & controller_name);
116 CONTROLLER_MANAGER_PUBLIC
117 std::vector<ControllerSpec> get_loaded_controllers()
const;
120 typename T,
typename std::enable_if<
121 std::is_convertible<T *, controller_interface::ControllerInterfaceBase *>::value,
122 T>::type * =
nullptr>
123 controller_interface::ControllerInterfaceBaseSharedPtr add_controller(
124 std::shared_ptr<T> controller,
const std::string & controller_name,
125 const std::string & controller_type)
128 controller_spec.c = controller;
129 controller_spec.info.
name = controller_name;
130 controller_spec.info.
type = controller_type;
131 return add_controller_impl(controller_spec);
140 CONTROLLER_MANAGER_PUBLIC
150 CONTROLLER_MANAGER_PUBLIC
152 const std::vector<std::string> & start_controllers,
153 const std::vector<std::string> & stop_controllers,
int strictness,
154 bool activate_asap = kWaitForAllResources,
155 const rclcpp::Duration & timeout = rclcpp::Duration::from_nanoseconds(kInfiniteTimeout));
165 CONTROLLER_MANAGER_PUBLIC
166 void read(
const rclcpp::Time & time,
const rclcpp::Duration & period);
176 CONTROLLER_MANAGER_PUBLIC
177 controller_interface::return_type
update(
178 const rclcpp::Time & time,
const rclcpp::Duration & period);
188 CONTROLLER_MANAGER_PUBLIC
189 void write(
const rclcpp::Time & time,
const rclcpp::Duration & period);
201 CONTROLLER_MANAGER_PUBLIC
205 CONTROLLER_MANAGER_PUBLIC
206 void init_services();
208 CONTROLLER_MANAGER_PUBLIC
209 controller_interface::ControllerInterfaceBaseSharedPtr add_controller_impl(
212 CONTROLLER_MANAGER_PUBLIC
213 void manage_switch();
215 CONTROLLER_MANAGER_PUBLIC
216 void deactivate_controllers();
226 CONTROLLER_MANAGER_PUBLIC
228 const std::vector<std::string> & chained_mode_switch_list,
bool to_chained_mode);
230 CONTROLLER_MANAGER_PUBLIC
231 void activate_controllers();
233 CONTROLLER_MANAGER_PUBLIC
234 void activate_controllers_asap();
236 CONTROLLER_MANAGER_PUBLIC
237 void list_controllers_srv_cb(
238 const std::shared_ptr<controller_manager_msgs::srv::ListControllers::Request> request,
239 std::shared_ptr<controller_manager_msgs::srv::ListControllers::Response> response);
241 CONTROLLER_MANAGER_PUBLIC
242 void list_hardware_interfaces_srv_cb(
243 const std::shared_ptr<controller_manager_msgs::srv::ListHardwareInterfaces::Request> request,
244 std::shared_ptr<controller_manager_msgs::srv::ListHardwareInterfaces::Response> response);
246 CONTROLLER_MANAGER_PUBLIC
247 void load_controller_service_cb(
248 const std::shared_ptr<controller_manager_msgs::srv::LoadController::Request> request,
249 std::shared_ptr<controller_manager_msgs::srv::LoadController::Response> response);
251 CONTROLLER_MANAGER_PUBLIC
252 void configure_controller_service_cb(
253 const std::shared_ptr<controller_manager_msgs::srv::ConfigureController::Request> request,
254 std::shared_ptr<controller_manager_msgs::srv::ConfigureController::Response> response);
256 CONTROLLER_MANAGER_PUBLIC
257 void reload_controller_libraries_service_cb(
258 const std::shared_ptr<controller_manager_msgs::srv::ReloadControllerLibraries::Request> request,
259 std::shared_ptr<controller_manager_msgs::srv::ReloadControllerLibraries::Response> response);
261 CONTROLLER_MANAGER_PUBLIC
262 void switch_controller_service_cb(
263 const std::shared_ptr<controller_manager_msgs::srv::SwitchController::Request> request,
264 std::shared_ptr<controller_manager_msgs::srv::SwitchController::Response> response);
266 CONTROLLER_MANAGER_PUBLIC
267 void unload_controller_service_cb(
268 const std::shared_ptr<controller_manager_msgs::srv::UnloadController::Request> request,
269 std::shared_ptr<controller_manager_msgs::srv::UnloadController::Response> response);
271 CONTROLLER_MANAGER_PUBLIC
272 void list_controller_types_srv_cb(
273 const std::shared_ptr<controller_manager_msgs::srv::ListControllerTypes::Request> request,
274 std::shared_ptr<controller_manager_msgs::srv::ListControllerTypes::Response> response);
276 CONTROLLER_MANAGER_PUBLIC
277 void list_hardware_components_srv_cb(
278 const std::shared_ptr<controller_manager_msgs::srv::ListHardwareComponents::Request> request,
279 std::shared_ptr<controller_manager_msgs::srv::ListHardwareComponents::Response> response);
281 CONTROLLER_MANAGER_PUBLIC
282 void set_hardware_component_state_srv_cb(
283 const std::shared_ptr<controller_manager_msgs::srv::SetHardwareComponentState::Request> request,
284 std::shared_ptr<controller_manager_msgs::srv::SetHardwareComponentState::Response> response);
287 unsigned int update_loop_counter_ = 0;
288 unsigned int update_rate_ = 100;
289 std::vector<std::vector<std::string>> chained_controllers_configuration_;
291 std::unique_ptr<hardware_interface::ResourceManager> resource_manager_;
294 std::vector<std::string> get_controller_names();
295 std::pair<std::string, std::string> split_command_interface(
296 const std::string & command_interface);
297 void subscribe_to_robot_description_topic();
303 void clear_requests();
311 void propagate_deactivation_of_chained_mode(
const std::vector<ControllerSpec> & controllers);
338 controller_interface::return_type check_following_controllers_for_activate(
339 const std::vector<ControllerSpec> & controllers,
int strictness,
340 const ControllersListIterator controller_it);
361 controller_interface::return_type check_preceeding_controllers_for_deactivate(
362 const std::vector<ControllerSpec> & controllers,
int strictness,
363 const ControllersListIterator controller_it);
384 bool controller_sorting(
386 const std::vector<controller_manager::ControllerSpec> & controllers);
395 rclcpp::NodeOptions determine_controller_node_options(
const ControllerSpec & controller)
const;
397 std::shared_ptr<rclcpp::Executor> executor_;
399 std::shared_ptr<pluginlib::ClassLoader<controller_interface::ControllerInterface>> loader_;
400 std::shared_ptr<pluginlib::ClassLoader<controller_interface::ChainableControllerInterface>>
408 rclcpp::CallbackGroup::SharedPtr best_effort_callback_group_;
421 class RTControllerListWrapper
432 std::vector<ControllerSpec> & update_and_get_used_by_rt_list();
442 std::vector<ControllerSpec> & get_unused_list(
443 const std::lock_guard<std::recursive_mutex> & guard);
451 const std::vector<ControllerSpec> & get_updated_list(
452 const std::lock_guard<std::recursive_mutex> & guard)
const;
460 void switch_updated_list(
const std::lock_guard<std::recursive_mutex> & guard);
464 mutable std::recursive_mutex controllers_lock_;
473 int get_other_list(
int index)
const;
475 void wait_until_rt_not_using(
476 int index, std::chrono::microseconds sleep_delay = std::chrono::microseconds(200))
const;
478 std::vector<ControllerSpec> controllers_lists_[2];
480 int updated_controllers_index_ = 0;
482 int used_by_realtime_controllers_index_ = -1;
485 std::unique_ptr<rclcpp::PreShutdownCallbackHandle> preshutdown_cb_handle_{
nullptr};
486 RTControllerListWrapper rt_controllers_wrapper_;
489 std::mutex services_lock_;
490 rclcpp::Service<controller_manager_msgs::srv::ListControllers>::SharedPtr
491 list_controllers_service_;
492 rclcpp::Service<controller_manager_msgs::srv::ListControllerTypes>::SharedPtr
493 list_controller_types_service_;
494 rclcpp::Service<controller_manager_msgs::srv::LoadController>::SharedPtr load_controller_service_;
495 rclcpp::Service<controller_manager_msgs::srv::ConfigureController>::SharedPtr
496 configure_controller_service_;
497 rclcpp::Service<controller_manager_msgs::srv::ReloadControllerLibraries>::SharedPtr
498 reload_controller_libraries_service_;
499 rclcpp::Service<controller_manager_msgs::srv::SwitchController>::SharedPtr
500 switch_controller_service_;
501 rclcpp::Service<controller_manager_msgs::srv::UnloadController>::SharedPtr
502 unload_controller_service_;
504 rclcpp::Service<controller_manager_msgs::srv::ListHardwareComponents>::SharedPtr
505 list_hardware_components_service_;
506 rclcpp::Service<controller_manager_msgs::srv::ListHardwareInterfaces>::SharedPtr
507 list_hardware_interfaces_service_;
508 rclcpp::Service<controller_manager_msgs::srv::SetHardwareComponentState>::SharedPtr
509 set_hardware_component_state_service_;
511 std::vector<std::string> activate_request_, deactivate_request_;
512 std::vector<std::string> to_chained_mode_request_, from_chained_mode_request_;
513 std::vector<std::string> activate_command_interface_request_,
514 deactivate_command_interface_request_;
516 rclcpp::Subscription<std_msgs::msg::String>::SharedPtr robot_description_subscription_;
525 activate_asap =
false;
534 std::chrono::nanoseconds timeout;
537 std::condition_variable cv;
541 SwitchParams switch_params_;