51 static constexpr bool kWaitForAllResources =
false;
52 static constexpr auto kInfiniteTimeout = 0;
54 CONTROLLER_MANAGER_PUBLIC
56 std::unique_ptr<hardware_interface::ResourceManager> resource_manager,
57 std::shared_ptr<rclcpp::Executor> executor,
58 const std::string & manager_node_name =
"controller_manager",
59 const std::string & namespace_ =
"");
61 CONTROLLER_MANAGER_PUBLIC
63 std::shared_ptr<rclcpp::Executor> executor,
64 const std::string & manager_node_name =
"controller_manager",
65 const std::string & namespace_ =
"");
67 CONTROLLER_MANAGER_PUBLIC
70 CONTROLLER_MANAGER_PUBLIC
71 controller_interface::ControllerInterfaceSharedPtr load_controller(
72 const std::string & controller_name,
const std::string & controller_type);
80 CONTROLLER_MANAGER_PUBLIC
81 controller_interface::ControllerInterfaceSharedPtr load_controller(
82 const std::string & controller_name);
84 CONTROLLER_MANAGER_PUBLIC
85 controller_interface::return_type unload_controller(
const std::string & controller_name);
87 CONTROLLER_MANAGER_PUBLIC
88 std::vector<ControllerSpec> get_loaded_controllers()
const;
91 typename T,
typename std::enable_if<
92 std::is_convertible<T *, controller_interface::ControllerInterface *>::value,
94 controller_interface::ControllerInterfaceSharedPtr add_controller(
95 std::shared_ptr<T> controller,
const std::string & controller_name,
96 const std::string & controller_type)
99 controller_spec.c = controller;
100 controller_spec.info.
name = controller_name;
101 controller_spec.info.
type = controller_type;
102 return add_controller_impl(controller_spec);
111 CONTROLLER_MANAGER_PUBLIC
121 CONTROLLER_MANAGER_PUBLIC
123 const std::vector<std::string> & start_controllers,
124 const std::vector<std::string> & stop_controllers,
int strictness,
125 bool start_asap = kWaitForAllResources,
126 const rclcpp::Duration & timeout = rclcpp::Duration::from_nanoseconds(kInfiniteTimeout));
128 CONTROLLER_MANAGER_PUBLIC
131 CONTROLLER_MANAGER_PUBLIC
132 controller_interface::return_type update(
133 const rclcpp::Time & time,
const rclcpp::Duration & period);
135 CONTROLLER_MANAGER_PUBLIC
148 CONTROLLER_MANAGER_PUBLIC
152 CONTROLLER_MANAGER_PUBLIC
153 void init_services();
155 CONTROLLER_MANAGER_PUBLIC
156 controller_interface::ControllerInterfaceSharedPtr add_controller_impl(
159 CONTROLLER_MANAGER_PUBLIC
160 void manage_switch();
162 CONTROLLER_MANAGER_PUBLIC
163 void stop_controllers();
165 CONTROLLER_MANAGER_PUBLIC
166 void start_controllers();
168 CONTROLLER_MANAGER_PUBLIC
169 void start_controllers_asap();
171 CONTROLLER_MANAGER_PUBLIC
172 void list_controllers_srv_cb(
173 const std::shared_ptr<controller_manager_msgs::srv::ListControllers::Request> request,
174 std::shared_ptr<controller_manager_msgs::srv::ListControllers::Response> response);
176 CONTROLLER_MANAGER_PUBLIC
177 void list_controller_types_srv_cb(
178 const std::shared_ptr<controller_manager_msgs::srv::ListControllerTypes::Request> request,
179 std::shared_ptr<controller_manager_msgs::srv::ListControllerTypes::Response> response);
181 CONTROLLER_MANAGER_PUBLIC
182 void list_hardware_interfaces_srv_cb(
183 const std::shared_ptr<controller_manager_msgs::srv::ListHardwareInterfaces::Request> request,
184 std::shared_ptr<controller_manager_msgs::srv::ListHardwareInterfaces::Response> response);
186 CONTROLLER_MANAGER_PUBLIC
187 void load_controller_service_cb(
188 const std::shared_ptr<controller_manager_msgs::srv::LoadController::Request> request,
189 std::shared_ptr<controller_manager_msgs::srv::LoadController::Response> response);
191 CONTROLLER_MANAGER_PUBLIC
192 void configure_controller_service_cb(
193 const std::shared_ptr<controller_manager_msgs::srv::ConfigureController::Request> request,
194 std::shared_ptr<controller_manager_msgs::srv::ConfigureController::Response> response);
196 CONTROLLER_MANAGER_PUBLIC
197 void load_and_configure_controller_service_cb(
198 const std::shared_ptr<controller_manager_msgs::srv::LoadConfigureController::Request> request,
199 std::shared_ptr<controller_manager_msgs::srv::LoadConfigureController::Response> response);
201 CONTROLLER_MANAGER_PUBLIC
202 void load_and_start_controller_service_cb(
203 const std::shared_ptr<controller_manager_msgs::srv::LoadStartController::Request> request,
204 std::shared_ptr<controller_manager_msgs::srv::LoadStartController::Response> response);
206 CONTROLLER_MANAGER_PUBLIC
207 void configure_and_start_controller_service_cb(
208 const std::shared_ptr<controller_manager_msgs::srv::ConfigureStartController::Request> request,
209 std::shared_ptr<controller_manager_msgs::srv::ConfigureStartController::Response> response);
211 CONTROLLER_MANAGER_PUBLIC
212 void reload_controller_libraries_service_cb(
213 const std::shared_ptr<controller_manager_msgs::srv::ReloadControllerLibraries::Request> request,
214 std::shared_ptr<controller_manager_msgs::srv::ReloadControllerLibraries::Response> response);
216 CONTROLLER_MANAGER_PUBLIC
217 void switch_controller_service_cb(
218 const std::shared_ptr<controller_manager_msgs::srv::SwitchController::Request> request,
219 std::shared_ptr<controller_manager_msgs::srv::SwitchController::Response> response);
221 CONTROLLER_MANAGER_PUBLIC
222 void unload_controller_service_cb(
223 const std::shared_ptr<controller_manager_msgs::srv::UnloadController::Request> request,
224 std::shared_ptr<controller_manager_msgs::srv::UnloadController::Response> response);
227 unsigned int update_loop_counter_ = 0;
228 unsigned int update_rate_ = 100;
231 std::vector<std::string> get_controller_names();
233 std::unique_ptr<hardware_interface::ResourceManager> resource_manager_;
235 std::shared_ptr<rclcpp::Executor> executor_;
237 std::shared_ptr<pluginlib::ClassLoader<controller_interface::ControllerInterface>> loader_;
244 rclcpp::CallbackGroup::SharedPtr best_effort_callback_group_;
257 class RTControllerListWrapper
268 std::vector<ControllerSpec> & update_and_get_used_by_rt_list();
277 std::vector<ControllerSpec> & get_unused_list(
278 const std::lock_guard<std::recursive_mutex> & guard);
285 const std::vector<ControllerSpec> & get_updated_list(
286 const std::lock_guard<std::recursive_mutex> & guard)
const;
293 void switch_updated_list(
const std::lock_guard<std::recursive_mutex> & guard);
297 mutable std::recursive_mutex controllers_lock_;
306 int get_other_list(
int index)
const;
308 void wait_until_rt_not_using(
309 int index, std::chrono::microseconds sleep_delay = std::chrono::microseconds(200))
const;
311 std::vector<ControllerSpec> controllers_lists_[2];
313 int updated_controllers_index_ = 0;
315 int used_by_realtime_controllers_index_ = -1;
318 RTControllerListWrapper rt_controllers_wrapper_;
321 std::mutex services_lock_;
322 rclcpp::Service<controller_manager_msgs::srv::ListControllers>::SharedPtr
323 list_controllers_service_;
324 rclcpp::Service<controller_manager_msgs::srv::ListControllerTypes>::SharedPtr
325 list_controller_types_service_;
326 rclcpp::Service<controller_manager_msgs::srv::ListHardwareInterfaces>::SharedPtr
327 list_hardware_interfaces_service_;
328 rclcpp::Service<controller_manager_msgs::srv::LoadController>::SharedPtr load_controller_service_;
329 rclcpp::Service<controller_manager_msgs::srv::ConfigureController>::SharedPtr
330 configure_controller_service_;
331 rclcpp::Service<controller_manager_msgs::srv::LoadConfigureController>::SharedPtr
332 load_and_configure_controller_service_;
333 rclcpp::Service<controller_manager_msgs::srv::LoadStartController>::SharedPtr
334 load_and_start_controller_service_;
335 rclcpp::Service<controller_manager_msgs::srv::ConfigureStartController>::SharedPtr
336 configure_and_start_controller_service_;
337 rclcpp::Service<controller_manager_msgs::srv::ReloadControllerLibraries>::SharedPtr
338 reload_controller_libraries_service_;
339 rclcpp::Service<controller_manager_msgs::srv::SwitchController>::SharedPtr
340 switch_controller_service_;
341 rclcpp::Service<controller_manager_msgs::srv::UnloadController>::SharedPtr
342 unload_controller_service_;
344 std::vector<std::string> start_request_, stop_request_;
345 std::vector<std::string> start_command_interface_request_, stop_command_interface_request_;
349 bool do_switch = {
false};
350 bool started = {
false};
351 rclcpp::Time init_time = {rclcpp::Time::max()};
354 int strictness = {0};
355 bool start_asap = {
false};
356 rclcpp::Duration timeout = rclcpp::Duration{0, 0};
359 SwitchParams switch_params_;