Skip to content

Commit

Permalink
[ControllerManager] Fix all warnings from the latets features. (ros-c…
Browse files Browse the repository at this point in the history
  • Loading branch information
destogl authored Nov 24, 2023
1 parent 99d2f61 commit 7d79464
Show file tree
Hide file tree
Showing 4 changed files with 17 additions and 12 deletions.
15 changes: 9 additions & 6 deletions controller_manager/src/controller_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -2501,20 +2501,23 @@ bool ControllerManager::controller_sorting(
// If there is no common parent, then they belong to 2 different sets
auto following_ctrls_b = get_following_controller_names(ctrl_b.info.name, controllers);
if (following_ctrls_b.empty()) return true;
auto find_first_element = [&](const auto & controllers_list)
auto find_first_element = [&](const auto & controllers_list) -> size_t
{
auto it = std::find_if(
controllers.begin(), controllers.end(),
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
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,7 @@ TestControllerFailedInit::on_init()

controller_interface::return_type TestControllerFailedInit::init(
const std::string & /* controller_name */, const std::string & /* urdf */,
unsigned int cm_update_rate, const std::string & /*namespace_*/,
unsigned int /*cm_update_rate*/, const std::string & /*namespace_*/,
const rclcpp::NodeOptions & /*node_options*/)
{
return controller_interface::return_type::ERROR;
Expand Down
8 changes: 5 additions & 3 deletions controller_manager/test/test_controller_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -486,16 +486,18 @@ TEST_P(TestControllerUpdateRates, check_the_controller_update_rate)
time += rclcpp::Duration::from_seconds(0.01);
if (update_counter % cm_update_rate == 0)
{
const auto no_of_secs_passed = update_counter / cm_update_rate;
const double no_of_secs_passed = static_cast<double>(update_counter) / cm_update_rate;
// NOTE: here EXPECT_NEAR is used because it is observed that in the first iteration of whole
// cycle of cm_update_rate counts, there is one count missing, but in rest of the 9 cycles it
// is clearly tracking, so adding 1 here won't affect the final count.
// For instance, a controller with update rate 37 Hz, seems to have 36 in the first update
// cycle and then on accumulating 37 on every other update cycle so at the end of the 10
// cycles it will have 369 instead of 370.
EXPECT_NEAR(
EXPECT_THAT(
test_controller->internal_counter - initial_counter,
(controller_update_rate * no_of_secs_passed), 1);
testing::AnyOf(
testing::Eq(controller_update_rate * no_of_secs_passed),
testing::Eq((controller_update_rate * no_of_secs_passed) - 1)));
}
}
}
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 @@ -807,7 +807,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 @@ -1016,7 +1016,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 7d79464

Please sign in to comment.