Skip to content

Commit

Permalink
define time_ variable in ControllerManagerFixture and reuse it in oth…
Browse files Browse the repository at this point in the history
…er tests
  • Loading branch information
saikishor committed Oct 4, 2023
1 parent 9fb786b commit 4bc0f68
Show file tree
Hide file tree
Showing 5 changed files with 47 additions and 157 deletions.
22 changes: 7 additions & 15 deletions controller_manager/test/controller_manager_test_common.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -100,6 +100,7 @@ class ControllerManagerFixture : public ::testing::Test
cm_->robot_description_callback(msg);
}
}
time_ = rclcpp::Time(0, 0, cm_->get_node_clock_interface()->get_clock()->get_clock_type());
}

static void SetUpTestCase() { rclcpp::init(0, nullptr); }
Expand All @@ -118,9 +119,7 @@ class ControllerManagerFixture : public ::testing::Test
{
while (run_updater_)
{
cm_->update(
rclcpp::Time(0, 0, cm_->get_node_clock_interface()->get_clock()->get_clock_type()),
rclcpp::Duration::from_seconds(0.01));
cm_->update(time_, rclcpp::Duration::from_seconds(0.01));
std::this_thread::sleep_for(std::chrono::milliseconds(10));
}
});
Expand Down Expand Up @@ -158,6 +157,7 @@ class ControllerManagerFixture : public ::testing::Test
bool run_updater_;
const std::string robot_description_;
const bool pass_urdf_as_parameter_;
rclcpp::Time time_;
};

class TestControllerManagerSrvs
Expand All @@ -178,15 +178,9 @@ class TestControllerManagerSrvs
std::chrono::milliseconds(10),
[&]()
{
cm_->read(
rclcpp::Time(0, 0, cm_->get_node_clock_interface()->get_clock()->get_clock_type()),
PERIOD);
cm_->update(
rclcpp::Time(0, 0, cm_->get_node_clock_interface()->get_clock()->get_clock_type()),
PERIOD);
cm_->write(
rclcpp::Time(0, 0, cm_->get_node_clock_interface()->get_clock()->get_clock_type()),
PERIOD);
cm_->read(time_, PERIOD);
cm_->update(time_, PERIOD);
cm_->write(time_, PERIOD);
});

executor_->add_node(cm_);
Expand All @@ -213,9 +207,7 @@ class TestControllerManagerSrvs
while (service_executor.spin_until_future_complete(result, std::chrono::milliseconds(50)) !=
rclcpp::FutureReturnCode::SUCCESS)
{
cm_->update(
rclcpp::Time(0, 0, cm_->get_node_clock_interface()->get_clock()->get_clock_type()),
rclcpp::Duration::from_seconds(0.01));
cm_->update(time_, rclcpp::Duration::from_seconds(0.01));
}
}
else
Expand Down
76 changes: 19 additions & 57 deletions controller_manager/test/test_controller_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -96,9 +96,7 @@ TEST_P(TestControllerManagerWithStrictness, controller_lifecycle)

EXPECT_EQ(
controller_interface::return_type::OK,
cm_->update(
rclcpp::Time(0, 0, cm_->get_node_clock_interface()->get_clock()->get_clock_type()),
rclcpp::Duration::from_seconds(0.01)));
cm_->update(time_, rclcpp::Duration::from_seconds(0.01)));
EXPECT_EQ(0u, test_controller->internal_counter)
<< "Update should not reach an unconfigured controller";

Expand All @@ -110,9 +108,7 @@ TEST_P(TestControllerManagerWithStrictness, controller_lifecycle)
cm_->configure_controller(TEST_CONTROLLER2_NAME);
EXPECT_EQ(
controller_interface::return_type::OK,
cm_->update(
rclcpp::Time(0, 0, cm_->get_node_clock_interface()->get_clock()->get_clock_type()),
rclcpp::Duration::from_seconds(0.01)));
cm_->update(time_, rclcpp::Duration::from_seconds(0.01)));
EXPECT_EQ(0u, test_controller->internal_counter) << "Controller is not started";
EXPECT_EQ(0u, test_controller2->internal_counter) << "Controller is not started";

Expand All @@ -127,9 +123,7 @@ TEST_P(TestControllerManagerWithStrictness, controller_lifecycle)

EXPECT_EQ(
controller_interface::return_type::OK,
cm_->update(
rclcpp::Time(0, 0, cm_->get_node_clock_interface()->get_clock()->get_clock_type()),
rclcpp::Duration::from_seconds(0.01)));
cm_->update(time_, rclcpp::Duration::from_seconds(0.01)));
EXPECT_EQ(0u, test_controller2->internal_counter) << "Controller is started at the end of update";
{
ControllerManagerRunner cm_runner(this);
Expand All @@ -138,9 +132,7 @@ TEST_P(TestControllerManagerWithStrictness, controller_lifecycle)

EXPECT_EQ(
controller_interface::return_type::OK,
cm_->update(
rclcpp::Time(0, 0, cm_->get_node_clock_interface()->get_clock()->get_clock_type()),
rclcpp::Duration::from_seconds(0.01)));
cm_->update(time_, rclcpp::Duration::from_seconds(0.01)));
EXPECT_GE(test_controller2->internal_counter, test_param.expected_counter);

// Start the real test controller, will take effect at the end of the update function
Expand All @@ -155,9 +147,7 @@ TEST_P(TestControllerManagerWithStrictness, controller_lifecycle)

EXPECT_EQ(
controller_interface::return_type::OK,
cm_->update(
rclcpp::Time(0, 0, cm_->get_node_clock_interface()->get_clock()->get_clock_type()),
rclcpp::Duration::from_seconds(0.01)));
cm_->update(time_, rclcpp::Duration::from_seconds(0.01)));
EXPECT_EQ(0u, test_controller->internal_counter) << "Controller is started at the end of update";
{
ControllerManagerRunner cm_runner(this);
Expand All @@ -167,9 +157,7 @@ TEST_P(TestControllerManagerWithStrictness, controller_lifecycle)

EXPECT_EQ(
controller_interface::return_type::OK,
cm_->update(
rclcpp::Time(0, 0, cm_->get_node_clock_interface()->get_clock()->get_clock_type()),
rclcpp::Duration::from_seconds(0.01)));
cm_->update(time_, rclcpp::Duration::from_seconds(0.01)));
EXPECT_GE(test_controller->internal_counter, 1u);
size_t last_internal_counter = test_controller->internal_counter;

Expand All @@ -185,9 +173,7 @@ TEST_P(TestControllerManagerWithStrictness, controller_lifecycle)

EXPECT_EQ(
controller_interface::return_type::OK,
cm_->update(
rclcpp::Time(0, 0, cm_->get_node_clock_interface()->get_clock()->get_clock_type()),
rclcpp::Duration::from_seconds(0.01)));
cm_->update(time_, rclcpp::Duration::from_seconds(0.01)));
EXPECT_EQ(last_internal_counter + 1u, test_controller->internal_counter)
<< "Controller is stopped at the end of update, so it should have done one more update";
{
Expand Down Expand Up @@ -222,9 +208,7 @@ TEST_P(TestControllerManagerWithStrictness, per_controller_update_rate)

EXPECT_EQ(
controller_interface::return_type::OK,
cm_->update(
rclcpp::Time(0, 0, cm_->get_node_clock_interface()->get_clock()->get_clock_type()),
rclcpp::Duration::from_seconds(0.01)));
cm_->update(time_, rclcpp::Duration::from_seconds(0.01)));
EXPECT_EQ(0u, test_controller->internal_counter)
<< "Update should not reach an unconfigured controller";

Expand All @@ -236,9 +220,7 @@ TEST_P(TestControllerManagerWithStrictness, per_controller_update_rate)
cm_->configure_controller(test_controller::TEST_CONTROLLER_NAME);
EXPECT_EQ(
controller_interface::return_type::OK,
cm_->update(
rclcpp::Time(0, 0, cm_->get_node_clock_interface()->get_clock()->get_clock_type()),
rclcpp::Duration::from_seconds(0.01)));
cm_->update(time_, rclcpp::Duration::from_seconds(0.01)));
EXPECT_EQ(0u, test_controller->internal_counter) << "Controller is not started";

EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, test_controller->get_state().id());
Expand All @@ -255,9 +237,7 @@ TEST_P(TestControllerManagerWithStrictness, per_controller_update_rate)

EXPECT_EQ(
controller_interface::return_type::OK,
cm_->update(
rclcpp::Time(0, 0, cm_->get_node_clock_interface()->get_clock()->get_clock_type()),
rclcpp::Duration::from_seconds(0.01)));
cm_->update(time_, rclcpp::Duration::from_seconds(0.01)));
EXPECT_EQ(0u, test_controller->internal_counter) << "Controller is started at the end of update";
{
ControllerManagerRunner cm_runner(this);
Expand All @@ -271,9 +251,7 @@ TEST_P(TestControllerManagerWithStrictness, per_controller_update_rate)
{
EXPECT_EQ(
controller_interface::return_type::OK,
cm_->update(
rclcpp::Time(0, 0, cm_->get_node_clock_interface()->get_clock()->get_clock_type()),
rclcpp::Duration::from_seconds(0.01)));
cm_->update(time_, 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 @@ -308,9 +286,7 @@ TEST_P(TestControllerManagerWithUpdateRates, per_controller_equal_and_higher_upd
EXPECT_EQ(2, test_controller.use_count());
EXPECT_EQ(
controller_interface::return_type::OK,
cm_->update(
rclcpp::Time(0, 0, cm_->get_node_clock_interface()->get_clock()->get_clock_type()),
rclcpp::Duration::from_seconds(0.01)));
cm_->update(time_, rclcpp::Duration::from_seconds(0.01)));
EXPECT_EQ(last_internal_counter, test_controller->internal_counter)
<< "Update should not reach an unconfigured controller";

Expand All @@ -323,9 +299,7 @@ TEST_P(TestControllerManagerWithUpdateRates, per_controller_equal_and_higher_upd
cm_->configure_controller(test_controller::TEST_CONTROLLER_NAME);
EXPECT_EQ(
controller_interface::return_type::OK,
cm_->update(
rclcpp::Time(0, 0, cm_->get_node_clock_interface()->get_clock()->get_clock_type()),
rclcpp::Duration::from_seconds(0.01)));
cm_->update(time_, rclcpp::Duration::from_seconds(0.01)));
EXPECT_EQ(last_internal_counter, test_controller->internal_counter)
<< "Controller is not started";
EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, test_controller->get_state().id());
Expand All @@ -342,9 +316,7 @@ TEST_P(TestControllerManagerWithUpdateRates, per_controller_equal_and_higher_upd

EXPECT_EQ(
controller_interface::return_type::OK,
cm_->update(
rclcpp::Time(0, 0, cm_->get_node_clock_interface()->get_clock()->get_clock_type()),
rclcpp::Duration::from_seconds(0.01)));
cm_->update(time_, rclcpp::Duration::from_seconds(0.01)));
EXPECT_EQ(last_internal_counter, test_controller->internal_counter)
<< "Controller is started at the end of update";
{
Expand All @@ -360,9 +332,7 @@ TEST_P(TestControllerManagerWithUpdateRates, per_controller_equal_and_higher_upd
{
EXPECT_EQ(
controller_interface::return_type::OK,
cm_->update(
rclcpp::Time(0, 0, cm_->get_node_clock_interface()->get_clock()->get_clock_type()),
rclcpp::Duration::from_seconds(0.01)));
cm_->update(time_, rclcpp::Duration::from_seconds(0.01)));
loop_rate.sleep();
}
// if we do 2 times of the controller_manager update rate, the internal counter should be
Expand All @@ -378,10 +348,7 @@ TEST_P(TestControllerManagerWithUpdateRates, per_controller_equal_and_higher_upd
<< "switch_controller should be blocking until next update cycle";

EXPECT_EQ(
controller_interface::return_type::OK,
cm_->update(
rclcpp::Time(0, 0, cm_->get_node_clock_interface()->get_clock()->get_clock_type()),
rclcpp::Duration::from_seconds(0.01)))
controller_interface::return_type::OK, cm_->update(time_, rclcpp::Duration::from_seconds(0.01)))
<< "Controller is stopped at the end of update, so it should have done one more update";
{
ControllerManagerRunner cm_runner(this);
Expand Down Expand Up @@ -425,9 +392,7 @@ TEST_P(TestControllerUpdateRates, check_the_controller_update_rate)
cm_->configure_controller(test_controller::TEST_CONTROLLER_NAME);
EXPECT_EQ(
controller_interface::return_type::OK,
cm_->update(
rclcpp::Time(0, 0, cm_->get_node_clock_interface()->get_clock()->get_clock_type()),
rclcpp::Duration::from_seconds(0.01)));
cm_->update(time_, rclcpp::Duration::from_seconds(0.01)));
EXPECT_EQ(0u, test_controller->internal_counter) << "Controller is not started";

EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, test_controller->get_state().id());
Expand All @@ -445,9 +410,7 @@ TEST_P(TestControllerUpdateRates, check_the_controller_update_rate)

EXPECT_EQ(
controller_interface::return_type::OK,
cm_->update(
rclcpp::Time(0, 0, cm_->get_node_clock_interface()->get_clock()->get_clock_type()),
rclcpp::Duration::from_seconds(0.01)));
cm_->update(time_, rclcpp::Duration::from_seconds(0.01)));
EXPECT_EQ(0u, test_controller->internal_counter) << "Controller is started at the end of update";
{
ControllerManagerRunner cm_runner(this);
Expand All @@ -461,8 +424,7 @@ TEST_P(TestControllerUpdateRates, check_the_controller_update_rate)
const auto controller_update_rate = test_controller->get_update_rate();

const auto initial_counter = test_controller->internal_counter;
rclcpp::Time time =
rclcpp::Time(0, 0, cm_->get_node_clock_interface()->get_clock()->get_clock_type());
rclcpp::Time time = time_;
for (size_t update_counter = 0; update_counter <= 10 * cm_update_rate; ++update_counter)
{
EXPECT_EQ(
Expand Down
Loading

0 comments on commit 4bc0f68

Please sign in to comment.