|
| 1 | +diff --git a/controller_manager/src/controller_manager.cpp b/controller_manager/src/controller_manager.cpp |
| 2 | +index 6e088a2e..feca559f 100644 |
| 3 | +--- a/controller_manager/src/controller_manager.cpp |
| 4 | ++++ b/controller_manager/src/controller_manager.cpp |
| 5 | +@@ -94,7 +94,7 @@ bool controller_name_compare(const controller_manager::ControllerSpec & a, const |
| 6 | + * \return true if interface has a controller name as prefix, false otherwise. |
| 7 | + */ |
| 8 | + bool command_interface_is_reference_interface_of_controller( |
| 9 | +- const std::string interface_name, |
| 10 | ++ const std::string & interface_name, |
| 11 | + const std::vector<controller_manager::ControllerSpec> & controllers, |
| 12 | + controller_manager::ControllersListIterator & following_controller_it) |
| 13 | + { |
| 14 | +@@ -146,7 +146,7 @@ bool command_interface_is_reference_interface_of_controller( |
| 15 | + * empty. |
| 16 | + */ |
| 17 | + std::vector<std::string> get_following_controller_names( |
| 18 | +- const std::string controller_name, |
| 19 | ++ const std::string & controller_name, |
| 20 | + const std::vector<controller_manager::ControllerSpec> & controllers) |
| 21 | + { |
| 22 | + std::vector<std::string> following_controllers; |
| 23 | +@@ -208,7 +208,7 @@ std::vector<std::string> get_following_controller_names( |
| 24 | + * empty. |
| 25 | + */ |
| 26 | + std::vector<std::string> get_preceding_controller_names( |
| 27 | +- const std::string controller_name, |
| 28 | ++ const std::string & controller_name, |
| 29 | + const std::vector<controller_manager::ControllerSpec> & controllers) |
| 30 | + { |
| 31 | + std::vector<std::string> preceding_controllers; |
| 32 | +@@ -1319,7 +1319,7 @@ controller_interface::return_type ControllerManager::switch_controller( |
| 33 | + switch_params_.do_switch = true; |
| 34 | + // wait until switch is finished |
| 35 | + RCLCPP_DEBUG(get_logger(), "Requested atomic controller switch from realtime loop"); |
| 36 | +- std::unique_lock<std::mutex> switch_params_guard(switch_params_.mutex, std::defer_lock); |
| 37 | ++ std::unique_lock<std::mutex> switch_params_guard(switch_params_.mutex); |
| 38 | + if (!switch_params_.cv.wait_for( |
| 39 | + switch_params_guard, switch_params_.timeout, [this] { return !switch_params_.do_switch; })) |
| 40 | + { |
| 41 | + |
0 commit comments