Skip to content

Commit

Permalink
[ControllerManager] Fix all warnings from the latets features. (backp…
Browse files Browse the repository at this point in the history
…ort #1174) (#1308)

* [ControllerManager] Fix all warnings from the latets features. (#1174)

(cherry picked from commit 7d79464)

---------

Co-authored-by: Dr. Denis <[email protected]>
  • Loading branch information
mergify[bot] and destogl authored Jan 17, 2024
1 parent 39b26db commit d4ea1ce
Show file tree
Hide file tree
Showing 2 changed files with 10 additions and 7 deletions.
13 changes: 8 additions & 5 deletions controller_manager/src/controller_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -2545,13 +2545,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
Expand Down
4 changes: 2 additions & 2 deletions controller_manager/test/test_controller_manager_srvs.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -770,7 +770,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(),
Expand Down Expand Up @@ -982,7 +982,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(),
Expand Down

0 comments on commit d4ea1ce

Please sign in to comment.