Skip to content

Commit 7a3a4a1

Browse files
[ControllerManager] Fix all warnings from the latets features. (backport #1174) (#1309)
* [ControllerManager] Fix all warnings from the latets features. (#1174) (cherry picked from commit 7d79464) --------- Co-authored-by: Dr. Denis <[email protected]>
1 parent 61e8548 commit 7a3a4a1

File tree

2 files changed

+10
-7
lines changed

2 files changed

+10
-7
lines changed

controller_manager/src/controller_manager.cpp

Lines changed: 8 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -2390,13 +2390,16 @@ bool ControllerManager::controller_sorting(
23902390
std::bind(controller_name_compare, std::placeholders::_1, controllers_list.back()));
23912391
if (it != controllers.end())
23922392
{
2393-
int dist = std::distance(controllers.begin(), it);
2394-
return dist;
2393+
return std::distance(controllers.begin(), it);
23952394
}
2395+
return 0;
23962396
};
2397-
const int ctrl_a_chain_first_controller = find_first_element(following_ctrls);
2398-
const int ctrl_b_chain_first_controller = find_first_element(following_ctrls_b);
2399-
if (ctrl_a_chain_first_controller < ctrl_b_chain_first_controller) return true;
2397+
const auto ctrl_a_chain_first_controller = find_first_element(following_ctrls);
2398+
const auto ctrl_b_chain_first_controller = find_first_element(following_ctrls_b);
2399+
if (ctrl_a_chain_first_controller < ctrl_b_chain_first_controller)
2400+
{
2401+
return true;
2402+
}
24002403
}
24012404

24022405
// If the ctrl_a's state interface is the one exported by the ctrl_b then ctrl_b should be

controller_manager/test/test_controller_manager_srvs.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -769,7 +769,7 @@ TEST_F(TestControllerManagerSrvs, list_sorted_complex_chained_controllers)
769769
ASSERT_EQ(result->controller[1].name, TEST_CHAINED_CONTROLLER_7);
770770
ASSERT_EQ(result->controller[2].name, TEST_CHAINED_CONTROLLER_6);
771771

772-
auto get_ctrl_pos = [result](const std::string & controller_name) -> int
772+
auto get_ctrl_pos = [result](const std::string & controller_name) -> int64_t
773773
{
774774
auto it = std::find_if(
775775
result->controller.begin(), result->controller.end(),
@@ -981,7 +981,7 @@ TEST_F(TestControllerManagerSrvs, list_sorted_independent_chained_controllers)
981981
result = call_service_and_wait(*client, request, srv_executor);
982982
ASSERT_EQ(10u, result->controller.size());
983983

984-
auto get_ctrl_pos = [result](const std::string & controller_name) -> int
984+
auto get_ctrl_pos = [result](const std::string & controller_name) -> int64_t
985985
{
986986
auto it = std::find_if(
987987
result->controller.begin(), result->controller.end(),

0 commit comments

Comments
 (0)