Skip to content

Commit

Permalink
add parameterized tests for testing more test cases
Browse files Browse the repository at this point in the history
  • Loading branch information
saikishor committed Jul 25, 2023
1 parent 8f0c051 commit 2e734c7
Showing 1 changed file with 27 additions and 11 deletions.
38 changes: 27 additions & 11 deletions controller_manager/test/test_controller_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -246,9 +246,13 @@ TEST_P(TestControllerManagerWithStrictness, per_controller_update_rate)

EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, test_controller->get_state().id());

EXPECT_EQ(
controller_interface::return_type::OK,
cm_->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)));
// As the controller frequency is 4Hz, it needs to pass 25 iterations for 1 update cycle
for (size_t i = 0; i < 25; i++)
{
EXPECT_EQ(
controller_interface::return_type::OK,
cm_->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)));
}
EXPECT_GE(test_controller->internal_counter, 1u);
EXPECT_EQ(test_controller->get_update_rate(), 4u);
}
Expand Down Expand Up @@ -361,13 +365,19 @@ TEST_P(TestControllerManagerWithUpdateRates, per_controller_equal_and_higher_upd
last_internal_counter = test_controller->internal_counter;
}

INSTANTIATE_TEST_SUITE_P(
per_controller_equal_and_higher_update_rate, TestControllerManagerWithUpdateRates,
testing::Values(100, 232, 400));

class TestControllerUpdateRates
: public ControllerManagerFixture<controller_manager::ControllerManager>
: public ControllerManagerFixture<controller_manager::ControllerManager>,
public testing::WithParamInterface<unsigned int>
{
};

TEST_F(TestControllerUpdateRates, check_the_controller_update_rate)
TEST_P(TestControllerUpdateRates, check_the_controller_update_rate)
{
const unsigned int ctrl_update_rate = GetParam();
auto test_controller = std::make_shared<test_controller::TestController>();
cm_->add_controller(
test_controller, test_controller::TEST_CONTROLLER_NAME,
Expand All @@ -378,7 +388,7 @@ TEST_F(TestControllerUpdateRates, check_the_controller_update_rate)
EXPECT_EQ(
lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, test_controller->get_state().id());

test_controller->get_node()->set_parameter({"update_rate", 40});
test_controller->get_node()->set_parameter({"update_rate", static_cast<int>(ctrl_update_rate)});
// configure controller
cm_->configure_controller(test_controller::TEST_CONTROLLER_NAME);
EXPECT_EQ(
Expand Down Expand Up @@ -410,11 +420,15 @@ TEST_F(TestControllerUpdateRates, check_the_controller_update_rate)

EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, test_controller->get_state().id());

EXPECT_EQ(test_controller->get_update_rate(), 40u);
EXPECT_EQ(test_controller->get_update_rate(), ctrl_update_rate);
const auto cm_update_rate = cm_->get_update_rate();
const auto controller_update_rate = test_controller->get_update_rate();
const auto controller_factor = (cm_update_rate / controller_update_rate);
const auto expected_controller_update_rate =
static_cast<unsigned int>(std::round(cm_update_rate / static_cast<double>(controller_factor)));

for (size_t update_counter = 0; update_counter <= 10 * cm_update_rate; ++update_counter)
const auto initial_counter = test_controller->internal_counter;
for (size_t update_counter = 1; update_counter <= 10 * cm_update_rate; ++update_counter)
{
EXPECT_EQ(
controller_interface::return_type::OK,
Expand All @@ -423,11 +437,13 @@ TEST_F(TestControllerUpdateRates, check_the_controller_update_rate)
if (update_counter % cm_update_rate == 0)
{
const auto no_of_secs_passed = update_counter / cm_update_rate;
EXPECT_EQ(test_controller->internal_counter, controller_update_rate * no_of_secs_passed);
EXPECT_EQ(
test_controller->internal_counter - initial_counter,
(expected_controller_update_rate * no_of_secs_passed));
}
}
}

INSTANTIATE_TEST_SUITE_P(
per_controller_equal_and_higher_update_rate, TestControllerManagerWithUpdateRates,
testing::Values(100, 232, 400));
per_controller_update_rate_check, TestControllerUpdateRates,
testing::Values(10, 12, 16, 23, 37, 40, 50, 63, 71, 85, 98));

0 comments on commit 2e734c7

Please sign in to comment.