51 static constexpr bool kWaitForAllResources =
false;
52 static constexpr double kInfiniteTimeout = 0.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 =
127 rclcpp::Duration(
static_cast<rcl_duration_value_t
>(kInfiniteTimeout)));
129 CONTROLLER_MANAGER_PUBLIC
132 CONTROLLER_MANAGER_PUBLIC
133 controller_interface::return_type update();
135 CONTROLLER_MANAGER_PUBLIC
148 CONTROLLER_MANAGER_PUBLIC
151 CONTROLLER_MANAGER_PUBLIC
152 controller_interface::ControllerInterfaceSharedPtr add_controller_impl(
155 CONTROLLER_MANAGER_PUBLIC
156 void manage_switch();
158 CONTROLLER_MANAGER_PUBLIC
159 void stop_controllers();
161 CONTROLLER_MANAGER_PUBLIC
162 void start_controllers();
164 CONTROLLER_MANAGER_PUBLIC
165 void start_controllers_asap();
167 CONTROLLER_MANAGER_PUBLIC
168 void list_controllers_srv_cb(
169 const std::shared_ptr<controller_manager_msgs::srv::ListControllers::Request> request,
170 std::shared_ptr<controller_manager_msgs::srv::ListControllers::Response> response);
172 CONTROLLER_MANAGER_PUBLIC
173 void list_controller_types_srv_cb(
174 const std::shared_ptr<controller_manager_msgs::srv::ListControllerTypes::Request> request,
175 std::shared_ptr<controller_manager_msgs::srv::ListControllerTypes::Response> response);
177 CONTROLLER_MANAGER_PUBLIC
178 void list_hardware_interfaces_srv_cb(
179 const std::shared_ptr<controller_manager_msgs::srv::ListHardwareInterfaces::Request> request,
180 std::shared_ptr<controller_manager_msgs::srv::ListHardwareInterfaces::Response> response);
182 CONTROLLER_MANAGER_PUBLIC
183 void load_controller_service_cb(
184 const std::shared_ptr<controller_manager_msgs::srv::LoadController::Request> request,
185 std::shared_ptr<controller_manager_msgs::srv::LoadController::Response> response);
187 CONTROLLER_MANAGER_PUBLIC
188 void configure_controller_service_cb(
189 const std::shared_ptr<controller_manager_msgs::srv::ConfigureController::Request> request,
190 std::shared_ptr<controller_manager_msgs::srv::ConfigureController::Response> response);
192 CONTROLLER_MANAGER_PUBLIC
193 void load_and_configure_controller_service_cb(
194 const std::shared_ptr<controller_manager_msgs::srv::LoadConfigureController::Request> request,
195 std::shared_ptr<controller_manager_msgs::srv::LoadConfigureController::Response> response);
197 CONTROLLER_MANAGER_PUBLIC
198 void load_and_start_controller_service_cb(
199 const std::shared_ptr<controller_manager_msgs::srv::LoadStartController::Request> request,
200 std::shared_ptr<controller_manager_msgs::srv::LoadStartController::Response> response);
202 CONTROLLER_MANAGER_PUBLIC
203 void configure_and_start_controller_service_cb(
204 const std::shared_ptr<controller_manager_msgs::srv::ConfigureStartController::Request> request,
205 std::shared_ptr<controller_manager_msgs::srv::ConfigureStartController::Response> response);
207 CONTROLLER_MANAGER_PUBLIC
208 void reload_controller_libraries_service_cb(
209 const std::shared_ptr<controller_manager_msgs::srv::ReloadControllerLibraries::Request> request,
210 std::shared_ptr<controller_manager_msgs::srv::ReloadControllerLibraries::Response> response);
212 CONTROLLER_MANAGER_PUBLIC
213 void switch_controller_service_cb(
214 const std::shared_ptr<controller_manager_msgs::srv::SwitchController::Request> request,
215 std::shared_ptr<controller_manager_msgs::srv::SwitchController::Response> response);
217 CONTROLLER_MANAGER_PUBLIC
218 void unload_controller_service_cb(
219 const std::shared_ptr<controller_manager_msgs::srv::UnloadController::Request> request,
220 std::shared_ptr<controller_manager_msgs::srv::UnloadController::Response> response);
223 std::vector<std::string> get_controller_names();
225 std::unique_ptr<hardware_interface::ResourceManager> resource_manager_;
227 std::shared_ptr<rclcpp::Executor> executor_;
229 std::shared_ptr<pluginlib::ClassLoader<controller_interface::ControllerInterface>> loader_;
236 rclcpp::CallbackGroup::SharedPtr best_effort_callback_group_;
249 class RTControllerListWrapper
260 std::vector<ControllerSpec> & update_and_get_used_by_rt_list();
269 std::vector<ControllerSpec> & get_unused_list(
270 const std::lock_guard<std::recursive_mutex> & guard);
277 const std::vector<ControllerSpec> & get_updated_list(
278 const std::lock_guard<std::recursive_mutex> & guard)
const;
285 void switch_updated_list(
const std::lock_guard<std::recursive_mutex> & guard);
289 mutable std::recursive_mutex controllers_lock_;
298 int get_other_list(
int index)
const;
300 void wait_until_rt_not_using(
301 int index, std::chrono::microseconds sleep_delay = std::chrono::microseconds(200))
const;
303 std::vector<ControllerSpec> controllers_lists_[2];
305 int updated_controllers_index_ = 0;
307 int used_by_realtime_controllers_index_ = -1;
310 RTControllerListWrapper rt_controllers_wrapper_;
313 std::mutex services_lock_;
314 rclcpp::Service<controller_manager_msgs::srv::ListControllers>::SharedPtr
315 list_controllers_service_;
316 rclcpp::Service<controller_manager_msgs::srv::ListControllerTypes>::SharedPtr
317 list_controller_types_service_;
318 rclcpp::Service<controller_manager_msgs::srv::ListHardwareInterfaces>::SharedPtr
319 list_hardware_interfaces_service_;
320 rclcpp::Service<controller_manager_msgs::srv::LoadController>::SharedPtr load_controller_service_;
321 rclcpp::Service<controller_manager_msgs::srv::ConfigureController>::SharedPtr
322 configure_controller_service_;
323 rclcpp::Service<controller_manager_msgs::srv::LoadConfigureController>::SharedPtr
324 load_and_configure_controller_service_;
325 rclcpp::Service<controller_manager_msgs::srv::LoadStartController>::SharedPtr
326 load_and_start_controller_service_;
327 rclcpp::Service<controller_manager_msgs::srv::ConfigureStartController>::SharedPtr
328 configure_and_start_controller_service_;
329 rclcpp::Service<controller_manager_msgs::srv::ReloadControllerLibraries>::SharedPtr
330 reload_controller_libraries_service_;
331 rclcpp::Service<controller_manager_msgs::srv::SwitchController>::SharedPtr
332 switch_controller_service_;
333 rclcpp::Service<controller_manager_msgs::srv::UnloadController>::SharedPtr
334 unload_controller_service_;
336 std::vector<std::string> start_request_, stop_request_;
337 std::vector<std::string> start_command_interface_request_, stop_command_interface_request_;
341 bool do_switch = {
false};
342 bool started = {
false};
343 rclcpp::Time init_time = {rclcpp::Time::max()};
346 int strictness = {0};
347 bool start_asap = {
false};
348 rclcpp::Duration timeout = rclcpp::Duration{0, 0};
351 SwitchParams switch_params_;