|
15 | 15 | #ifndef CONTROLLER_MANAGER__CONTROLLER_MANAGER_HPP_ |
16 | 16 | #define CONTROLLER_MANAGER__CONTROLLER_MANAGER_HPP_ |
17 | 17 |
|
| 18 | +#include <map> |
18 | 19 | #include <memory> |
19 | 20 | #include <string> |
20 | 21 | #include <tuple> |
| 22 | +#include <unordered_map> |
21 | 23 | #include <vector> |
22 | 24 |
|
23 | 25 | #include "controller_interface/chainable_controller_interface.hpp" |
|
40 | 42 | #include "controller_manager_msgs/srv/switch_controller.hpp" |
41 | 43 | #include "controller_manager_msgs/srv/unload_controller.hpp" |
42 | 44 |
|
| 45 | +#include "hardware_interface/handle.hpp" |
43 | 46 | #include "hardware_interface/resource_manager.hpp" |
44 | 47 |
|
45 | 48 | #include "pluginlib/class_loader.hpp" |
46 | 49 |
|
47 | 50 | #include "rclcpp/executor.hpp" |
48 | 51 | #include "rclcpp/node.hpp" |
| 52 | +#include "rclcpp/node_interfaces/node_logging_interface.hpp" |
| 53 | +#include "rclcpp/node_interfaces/node_parameters_interface.hpp" |
| 54 | +#include "rclcpp/parameter.hpp" |
49 | 55 |
|
50 | 56 | namespace controller_manager |
51 | 57 | { |
| 58 | +using ControllersListIterator = std::vector<controller_manager::ControllerSpec>::const_iterator; |
| 59 | + |
52 | 60 | class ControllerManager : public rclcpp::Node |
53 | 61 | { |
54 | 62 | public: |
@@ -169,6 +177,18 @@ class ControllerManager : public rclcpp::Node |
169 | 177 | CONTROLLER_MANAGER_PUBLIC |
170 | 178 | void stop_controllers(); |
171 | 179 |
|
| 180 | + /** |
| 181 | + * Switch chained mode for all the controllers with respect to the following cases: |
| 182 | + * - a preceding controller is getting activated --> switch controller to chained mode; |
| 183 | + * - all preceding controllers are deactivated --> switch controller from chained mode. |
| 184 | + * |
| 185 | + * \param[in] chained_mode_switch_list list of controller to switch chained mode. |
| 186 | + * \param[in] to_chained_mode flag if controller should be switched *to* or *from* chained mode. |
| 187 | + */ |
| 188 | + CONTROLLER_MANAGER_PUBLIC |
| 189 | + void switch_chained_mode( |
| 190 | + const std::vector<std::string> & chained_mode_switch_list, bool to_chained_mode); |
| 191 | + |
172 | 192 | CONTROLLER_MANAGER_PUBLIC |
173 | 193 | void start_controllers(); |
174 | 194 |
|
@@ -243,11 +263,78 @@ class ControllerManager : public rclcpp::Node |
243 | 263 | // Per controller update rate support |
244 | 264 | unsigned int update_loop_counter_ = 0; |
245 | 265 | unsigned int update_rate_ = 100; |
| 266 | + std::vector<std::vector<std::string>> chained_controllers_configuration_; |
| 267 | + |
| 268 | + std::unique_ptr<hardware_interface::ResourceManager> resource_manager_; |
246 | 269 |
|
247 | 270 | private: |
248 | 271 | std::vector<std::string> get_controller_names(); |
249 | 272 |
|
250 | | - std::unique_ptr<hardware_interface::ResourceManager> resource_manager_; |
| 273 | + /** |
| 274 | + * Clear request lists used when switching controllers. The lists are shared between "callback" and |
| 275 | + * "control loop" threads. |
| 276 | + */ |
| 277 | + void clear_requests(); |
| 278 | + |
| 279 | + /** |
| 280 | + * If a controller is deactivated all following controllers (if any exist) should be switched |
| 281 | + * 'from' the chained mode. |
| 282 | + * |
| 283 | + * \param[in] controllers list with controllers. |
| 284 | + */ |
| 285 | + void propagate_deactivation_of_chained_mode(const std::vector<ControllerSpec> & controllers); |
| 286 | + |
| 287 | + /// Check if all the following controllers will be in active state and in the chained mode |
| 288 | + /// after controllers' switch. |
| 289 | + /** |
| 290 | + * Check recursively that all following controllers of the @controller_it |
| 291 | + * - are already active, |
| 292 | + * - will not be deactivated, |
| 293 | + * - or will be activated. |
| 294 | + * The following controllers are added to the request to switch in the chained mode or removed |
| 295 | + * from the request to switch from the chained mode. |
| 296 | + * |
| 297 | + * For each controller the whole chain of following controllers is checked. |
| 298 | + * |
| 299 | + * NOTE: The automatically adding of following controller into starting list is not implemented |
| 300 | + * yet. |
| 301 | + * |
| 302 | + * \param[in] controllers list with controllers. |
| 303 | + * \param[in] strictness if value is equal "MANIPULATE_CONTROLLERS_CHAIN" then all following |
| 304 | + * controllers will be automatically added to the activate request list if they are not in the |
| 305 | + * deactivate request. |
| 306 | + * \param[in] controller_it iterator to the controller for which the following controllers are |
| 307 | + * checked. |
| 308 | + * |
| 309 | + * \returns return_type::OK if all following controllers pass the checks, otherwise |
| 310 | + * return_type::ERROR. |
| 311 | + */ |
| 312 | + controller_interface::return_type check_following_controllers_for_activate( |
| 313 | + const std::vector<ControllerSpec> & controllers, int strictness, |
| 314 | + const ControllersListIterator controller_it); |
| 315 | + |
| 316 | + /// Check if all the preceding controllers will be in inactive state after controllers' switch. |
| 317 | + /** |
| 318 | + * Check that all preceding controllers of the @controller_it |
| 319 | + * - are inactive, |
| 320 | + * - will be deactivated, |
| 321 | + * - and will not be activated. |
| 322 | + * |
| 323 | + * NOTE: The automatically adding of preceding controllers into stopping list is not implemented |
| 324 | + * yet. |
| 325 | + * |
| 326 | + * \param[in] controllers list with controllers. |
| 327 | + * \param[in] strictness if value is equal "MANIPULATE_CONTROLLERS_CHAIN" then all preceding |
| 328 | + * controllers will be automatically added to the deactivate request list. |
| 329 | + * \param[in] controller_it iterator to the controller for which the preceding controllers are |
| 330 | + * checked. |
| 331 | + * |
| 332 | + * \returns return_type::OK if all preceding controllers pass the checks, otherwise |
| 333 | + * return_type::ERROR. |
| 334 | + */ |
| 335 | + controller_interface::return_type check_preceeding_controllers_for_deactivate( |
| 336 | + const std::vector<ControllerSpec> & controllers, int strictness, |
| 337 | + const ControllersListIterator controller_it); |
251 | 338 |
|
252 | 339 | std::shared_ptr<rclcpp::Executor> executor_; |
253 | 340 |
|
@@ -366,6 +453,7 @@ class ControllerManager : public rclcpp::Node |
366 | 453 | set_hardware_component_state_service_; |
367 | 454 |
|
368 | 455 | std::vector<std::string> start_request_, stop_request_; |
| 456 | + std::vector<std::string> to_chained_mode_request_, from_chained_mode_request_; |
369 | 457 | std::vector<std::string> start_command_interface_request_, stop_command_interface_request_; |
370 | 458 |
|
371 | 459 | struct SwitchParams |
|
0 commit comments