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
86 CONTROLLER_MANAGER_PUBLIC
87 void robot_description_callback(
const std_msgs::msg::String & msg);
89 CONTROLLER_MANAGER_PUBLIC
90 void init_resource_manager(
const std::string & robot_description);
92 CONTROLLER_MANAGER_PUBLIC
93 controller_interface::ControllerInterfaceBaseSharedPtr load_controller(
94 const std::string & controller_name,
const std::string & controller_type);
102 CONTROLLER_MANAGER_PUBLIC
103 controller_interface::ControllerInterfaceBaseSharedPtr load_controller(
104 const std::string & controller_name);
106 CONTROLLER_MANAGER_PUBLIC
107 controller_interface::return_type unload_controller(
const std::string & controller_name);
109 CONTROLLER_MANAGER_PUBLIC
110 std::vector<ControllerSpec> get_loaded_controllers()
const;
113 typename T,
typename std::enable_if<
114 std::is_convertible<T *, controller_interface::ControllerInterfaceBase *>::value,
115 T>::type * =
nullptr>
116 controller_interface::ControllerInterfaceBaseSharedPtr add_controller(
117 std::shared_ptr<T> controller,
const std::string & controller_name,
118 const std::string & controller_type)
121 controller_spec.c = controller;
122 controller_spec.info.
name = controller_name;
123 controller_spec.info.
type = controller_type;
124 return add_controller_impl(controller_spec);
133 CONTROLLER_MANAGER_PUBLIC
143 CONTROLLER_MANAGER_PUBLIC
145 const std::vector<std::string> & start_controllers,
146 const std::vector<std::string> & stop_controllers,
int strictness,
147 bool activate_asap = kWaitForAllResources,
148 const rclcpp::Duration & timeout = rclcpp::Duration::from_nanoseconds(kInfiniteTimeout));
158 CONTROLLER_MANAGER_PUBLIC
159 void read(
const rclcpp::Time & time,
const rclcpp::Duration & period);
169 CONTROLLER_MANAGER_PUBLIC
170 controller_interface::return_type
update(
171 const rclcpp::Time & time,
const rclcpp::Duration & period);
181 CONTROLLER_MANAGER_PUBLIC
182 void write(
const rclcpp::Time & time,
const rclcpp::Duration & period);
194 CONTROLLER_MANAGER_PUBLIC
198 CONTROLLER_MANAGER_PUBLIC
199 void init_services();
201 CONTROLLER_MANAGER_PUBLIC
202 controller_interface::ControllerInterfaceBaseSharedPtr add_controller_impl(
205 CONTROLLER_MANAGER_PUBLIC
206 void manage_switch();
208 CONTROLLER_MANAGER_PUBLIC
209 void deactivate_controllers();
219 CONTROLLER_MANAGER_PUBLIC
221 const std::vector<std::string> & chained_mode_switch_list,
bool to_chained_mode);
223 CONTROLLER_MANAGER_PUBLIC
224 void activate_controllers();
226 CONTROLLER_MANAGER_PUBLIC
227 void activate_controllers_asap();
229 CONTROLLER_MANAGER_PUBLIC
230 void list_controllers_srv_cb(
231 const std::shared_ptr<controller_manager_msgs::srv::ListControllers::Request> request,
232 std::shared_ptr<controller_manager_msgs::srv::ListControllers::Response> response);
234 CONTROLLER_MANAGER_PUBLIC
235 void list_hardware_interfaces_srv_cb(
236 const std::shared_ptr<controller_manager_msgs::srv::ListHardwareInterfaces::Request> request,
237 std::shared_ptr<controller_manager_msgs::srv::ListHardwareInterfaces::Response> response);
239 CONTROLLER_MANAGER_PUBLIC
240 void load_controller_service_cb(
241 const std::shared_ptr<controller_manager_msgs::srv::LoadController::Request> request,
242 std::shared_ptr<controller_manager_msgs::srv::LoadController::Response> response);
244 CONTROLLER_MANAGER_PUBLIC
245 void configure_controller_service_cb(
246 const std::shared_ptr<controller_manager_msgs::srv::ConfigureController::Request> request,
247 std::shared_ptr<controller_manager_msgs::srv::ConfigureController::Response> response);
249 CONTROLLER_MANAGER_PUBLIC
250 void reload_controller_libraries_service_cb(
251 const std::shared_ptr<controller_manager_msgs::srv::ReloadControllerLibraries::Request> request,
252 std::shared_ptr<controller_manager_msgs::srv::ReloadControllerLibraries::Response> response);
254 CONTROLLER_MANAGER_PUBLIC
255 void switch_controller_service_cb(
256 const std::shared_ptr<controller_manager_msgs::srv::SwitchController::Request> request,
257 std::shared_ptr<controller_manager_msgs::srv::SwitchController::Response> response);
259 CONTROLLER_MANAGER_PUBLIC
260 void unload_controller_service_cb(
261 const std::shared_ptr<controller_manager_msgs::srv::UnloadController::Request> request,
262 std::shared_ptr<controller_manager_msgs::srv::UnloadController::Response> response);
264 CONTROLLER_MANAGER_PUBLIC
265 void list_controller_types_srv_cb(
266 const std::shared_ptr<controller_manager_msgs::srv::ListControllerTypes::Request> request,
267 std::shared_ptr<controller_manager_msgs::srv::ListControllerTypes::Response> response);
269 CONTROLLER_MANAGER_PUBLIC
270 void list_hardware_components_srv_cb(
271 const std::shared_ptr<controller_manager_msgs::srv::ListHardwareComponents::Request> request,
272 std::shared_ptr<controller_manager_msgs::srv::ListHardwareComponents::Response> response);
274 CONTROLLER_MANAGER_PUBLIC
275 void set_hardware_component_state_srv_cb(
276 const std::shared_ptr<controller_manager_msgs::srv::SetHardwareComponentState::Request> request,
277 std::shared_ptr<controller_manager_msgs::srv::SetHardwareComponentState::Response> response);
280 unsigned int update_loop_counter_ = 0;
281 unsigned int update_rate_ = 100;
282 std::vector<std::vector<std::string>> chained_controllers_configuration_;
284 std::unique_ptr<hardware_interface::ResourceManager> resource_manager_;
287 std::vector<std::string> get_controller_names();
288 std::pair<std::string, std::string> split_command_interface(
289 const std::string & command_interface);
290 void subscribe_to_robot_description_topic();
296 void clear_requests();
304 void propagate_deactivation_of_chained_mode(
const std::vector<ControllerSpec> & controllers);
331 controller_interface::return_type check_following_controllers_for_activate(
332 const std::vector<ControllerSpec> & controllers,
int strictness,
333 const ControllersListIterator controller_it);
354 controller_interface::return_type check_preceeding_controllers_for_deactivate(
355 const std::vector<ControllerSpec> & controllers,
int strictness,
356 const ControllersListIterator controller_it);
377 bool controller_sorting(
379 const std::vector<controller_manager::ControllerSpec> & controllers);
388 rclcpp::NodeOptions determine_controller_node_options(
const ControllerSpec & controller)
const;
390 std::shared_ptr<rclcpp::Executor> executor_;
392 std::shared_ptr<pluginlib::ClassLoader<controller_interface::ControllerInterface>> loader_;
393 std::shared_ptr<pluginlib::ClassLoader<controller_interface::ChainableControllerInterface>>
401 rclcpp::CallbackGroup::SharedPtr best_effort_callback_group_;
414 class RTControllerListWrapper
425 std::vector<ControllerSpec> & update_and_get_used_by_rt_list();
435 std::vector<ControllerSpec> & get_unused_list(
436 const std::lock_guard<std::recursive_mutex> & guard);
444 const std::vector<ControllerSpec> & get_updated_list(
445 const std::lock_guard<std::recursive_mutex> & guard)
const;
453 void switch_updated_list(
const std::lock_guard<std::recursive_mutex> & guard);
457 mutable std::recursive_mutex controllers_lock_;
466 int get_other_list(
int index)
const;
468 void wait_until_rt_not_using(
469 int index, std::chrono::microseconds sleep_delay = std::chrono::microseconds(200))
const;
471 std::vector<ControllerSpec> controllers_lists_[2];
473 int updated_controllers_index_ = 0;
475 int used_by_realtime_controllers_index_ = -1;
478 RTControllerListWrapper rt_controllers_wrapper_;
481 std::mutex services_lock_;
482 rclcpp::Service<controller_manager_msgs::srv::ListControllers>::SharedPtr
483 list_controllers_service_;
484 rclcpp::Service<controller_manager_msgs::srv::ListControllerTypes>::SharedPtr
485 list_controller_types_service_;
486 rclcpp::Service<controller_manager_msgs::srv::LoadController>::SharedPtr load_controller_service_;
487 rclcpp::Service<controller_manager_msgs::srv::ConfigureController>::SharedPtr
488 configure_controller_service_;
489 rclcpp::Service<controller_manager_msgs::srv::ReloadControllerLibraries>::SharedPtr
490 reload_controller_libraries_service_;
491 rclcpp::Service<controller_manager_msgs::srv::SwitchController>::SharedPtr
492 switch_controller_service_;
493 rclcpp::Service<controller_manager_msgs::srv::UnloadController>::SharedPtr
494 unload_controller_service_;
496 rclcpp::Service<controller_manager_msgs::srv::ListHardwareComponents>::SharedPtr
497 list_hardware_components_service_;
498 rclcpp::Service<controller_manager_msgs::srv::ListHardwareInterfaces>::SharedPtr
499 list_hardware_interfaces_service_;
500 rclcpp::Service<controller_manager_msgs::srv::SetHardwareComponentState>::SharedPtr
501 set_hardware_component_state_service_;
503 std::vector<std::string> activate_request_, deactivate_request_;
504 std::vector<std::string> to_chained_mode_request_, from_chained_mode_request_;
505 std::vector<std::string> activate_command_interface_request_,
506 deactivate_command_interface_request_;
508 rclcpp::Subscription<std_msgs::msg::String>::SharedPtr robot_description_subscription_;
517 activate_asap =
false;
526 std::chrono::nanoseconds timeout;
529 std::condition_variable cv;
533 SwitchParams switch_params_;