From 7a3a4a1f81a0ce8e9932e7ccd44a88c1597e3a30 Mon Sep 17 00:00:00 2001 From: "mergify[bot]" <37929162+mergify[bot]@users.noreply.github.com> Date: Wed, 17 Jan 2024 16:09:10 +0100 Subject: [PATCH] [ControllerManager] Fix all warnings from the latets features. (backport #1174) (#1309) * [ControllerManager] Fix all warnings from the latets features. (#1174) (cherry picked from commit 7d7946424be4b501476191e9ba6d5de956410f47) --------- Co-authored-by: Dr. Denis --- controller_manager/src/controller_manager.cpp | 13 ++++++++----- .../test/test_controller_manager_srvs.cpp | 4 ++-- 2 files changed, 10 insertions(+), 7 deletions(-) diff --git a/controller_manager/src/controller_manager.cpp b/controller_manager/src/controller_manager.cpp index f69b0ddb8e..d71b6f47c0 100644 --- a/controller_manager/src/controller_manager.cpp +++ b/controller_manager/src/controller_manager.cpp @@ -2390,13 +2390,16 @@ bool ControllerManager::controller_sorting( std::bind(controller_name_compare, std::placeholders::_1, controllers_list.back())); if (it != controllers.end()) { - int dist = std::distance(controllers.begin(), it); - return dist; + return std::distance(controllers.begin(), it); } + return 0; }; - const int ctrl_a_chain_first_controller = find_first_element(following_ctrls); - const int ctrl_b_chain_first_controller = find_first_element(following_ctrls_b); - if (ctrl_a_chain_first_controller < ctrl_b_chain_first_controller) return true; + const auto ctrl_a_chain_first_controller = find_first_element(following_ctrls); + const auto ctrl_b_chain_first_controller = find_first_element(following_ctrls_b); + if (ctrl_a_chain_first_controller < ctrl_b_chain_first_controller) + { + return true; + } } // If the ctrl_a's state interface is the one exported by the ctrl_b then ctrl_b should be diff --git a/controller_manager/test/test_controller_manager_srvs.cpp b/controller_manager/test/test_controller_manager_srvs.cpp index 1b86b04b9a..54a1c741a5 100644 --- a/controller_manager/test/test_controller_manager_srvs.cpp +++ b/controller_manager/test/test_controller_manager_srvs.cpp @@ -769,7 +769,7 @@ TEST_F(TestControllerManagerSrvs, list_sorted_complex_chained_controllers) ASSERT_EQ(result->controller[1].name, TEST_CHAINED_CONTROLLER_7); ASSERT_EQ(result->controller[2].name, TEST_CHAINED_CONTROLLER_6); - auto get_ctrl_pos = [result](const std::string & controller_name) -> int + auto get_ctrl_pos = [result](const std::string & controller_name) -> int64_t { auto it = std::find_if( result->controller.begin(), result->controller.end(), @@ -981,7 +981,7 @@ TEST_F(TestControllerManagerSrvs, list_sorted_independent_chained_controllers) result = call_service_and_wait(*client, request, srv_executor); ASSERT_EQ(10u, result->controller.size()); - auto get_ctrl_pos = [result](const std::string & controller_name) -> int + auto get_ctrl_pos = [result](const std::string & controller_name) -> int64_t { auto it = std::find_if( result->controller.begin(), result->controller.end(),