Skip to content

Commit

Permalink
use ControllerManagerRunner to avoid blocking when switching lists
Browse files Browse the repository at this point in the history
  • Loading branch information
saikishor committed Aug 27, 2023
1 parent 751bed7 commit 5c2cc55
Show file tree
Hide file tree
Showing 2 changed files with 29 additions and 8 deletions.
22 changes: 17 additions & 5 deletions controller_manager/test/test_controller_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -104,8 +104,11 @@ TEST_P(TestControllerManagerWithStrictness, controller_lifecycle)
lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, test_controller->get_state().id());

// configure controller
cm_->configure_controller(test_controller::TEST_CONTROLLER_NAME);
cm_->configure_controller(TEST_CONTROLLER2_NAME);
{
ControllerManagerRunner cm_runner(this);
cm_->configure_controller(test_controller::TEST_CONTROLLER_NAME);
cm_->configure_controller(TEST_CONTROLLER2_NAME);
}
EXPECT_EQ(
controller_interface::return_type::OK,
cm_->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)));
Expand Down Expand Up @@ -217,7 +220,10 @@ TEST_P(TestControllerManagerWithStrictness, per_controller_update_rate)

test_controller->get_node()->set_parameter({"update_rate", 4});
// configure controller
cm_->configure_controller(test_controller::TEST_CONTROLLER_NAME);
{
ControllerManagerRunner cm_runner(this);
cm_->configure_controller(test_controller::TEST_CONTROLLER_NAME);
}
EXPECT_EQ(
controller_interface::return_type::OK,
cm_->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)));
Expand Down Expand Up @@ -296,7 +302,10 @@ TEST_P(TestControllerManagerWithUpdateRates, per_controller_equal_and_higher_upd
rclcpp::Parameter update_rate_parameter("update_rate", static_cast<int>(ctrl_update_rate));
test_controller->get_node()->set_parameter(update_rate_parameter);
// configure controller
cm_->configure_controller(test_controller::TEST_CONTROLLER_NAME);
{
ControllerManagerRunner cm_runner(this);
cm_->configure_controller(test_controller::TEST_CONTROLLER_NAME);
}
EXPECT_EQ(
controller_interface::return_type::OK,
cm_->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)));
Expand Down Expand Up @@ -390,7 +399,10 @@ TEST_P(TestControllerUpdateRates, check_the_controller_update_rate)

test_controller->get_node()->set_parameter({"update_rate", static_cast<int>(ctrl_update_rate)});
// configure controller
cm_->configure_controller(test_controller::TEST_CONTROLLER_NAME);
{
ControllerManagerRunner cm_runner(this);
cm_->configure_controller(test_controller::TEST_CONTROLLER_NAME);
}
EXPECT_EQ(
controller_interface::return_type::OK,
cm_->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)));
Expand Down
15 changes: 12 additions & 3 deletions controller_manager/test/test_load_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -162,7 +162,10 @@ TEST_P(TestLoadedControllerParametrized, starting_and_stopping_a_controller)
lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, controller_if->get_state().id());

// Activate configured controller
cm_->configure_controller(controller_name1);
{
ControllerManagerRunner cm_runner(this);
cm_->configure_controller(controller_name1);
}
start_test_controller(test_param.strictness);
ASSERT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, controller_if->get_state().id());
}
Expand Down Expand Up @@ -246,7 +249,10 @@ TEST_P(TestLoadedControllerParametrized, inactive_controller_cannot_be_configure
test_controller->cleanup_calls = &cleanup_calls;
// Configure from inactive state
test_controller->simulate_cleanup_failure = false;
EXPECT_EQ(cm_->configure_controller(controller_name1), controller_interface::return_type::OK);
{
ControllerManagerRunner cm_runner(this);
EXPECT_EQ(cm_->configure_controller(controller_name1), controller_interface::return_type::OK);
}
ASSERT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, controller_if->get_state().id());
EXPECT_EQ(1u, cleanup_calls);
}
Expand Down Expand Up @@ -421,7 +427,10 @@ TEST_P(TestTwoLoadedControllers, switch_multiple_controllers)
ASSERT_EQ(
lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, controller_if2->get_state().id());

cm_->configure_controller(controller_name2);
{
ControllerManagerRunner cm_runner(this);
cm_->configure_controller(controller_name2);
}

// Stop controller 1
RCLCPP_INFO(cm_->get_logger(), "Stopping controller #1");
Expand Down

0 comments on commit 5c2cc55

Please sign in to comment.