Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Fix equal and higher ctrl update rate #1070

Merged
Merged
Show file tree
Hide file tree
Changes from 3 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
17 changes: 15 additions & 2 deletions controller_manager/src/controller_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -553,6 +553,18 @@ controller_interface::return_type ControllerManager::configure_controller(
controller_name, std::make_unique<ControllerThreadWrapper>(controller, update_rate_));
}

const auto controller_update_rate = controller->get_update_rate();
const auto cm_update_rate = get_update_rate();
if (controller_update_rate > cm_update_rate)
bmagyar marked this conversation as resolved.
Show resolved Hide resolved
{
RCLCPP_WARN(
get_logger(),
"The controller : %s update rate : %d Hz should be less than or equal to controller "
"manager's update rate : %d Hz!. The controller will be updated at controller_manager's "
"update rate.",
controller_name.c_str(), controller_update_rate, cm_update_rate);
}

// CHAINABLE CONTROLLERS: get reference interfaces from chainable controllers
if (controller->is_chainable())
{
Expand Down Expand Up @@ -1816,8 +1828,9 @@ controller_interface::return_type ControllerManager::update(
{
const auto controller_update_rate = loaded_controller.c->get_update_rate();

bool controller_go =
controller_update_rate == 0 || ((update_loop_counter_ % controller_update_rate) == 0);
bool controller_go = controller_update_rate == 0 ||
((update_loop_counter_ % controller_update_rate) == 0) ||
(controller_update_rate >= update_rate_);
RCLCPP_DEBUG(
get_logger(), "update_loop_counter: '%d ' controller_go: '%s ' controller_name: '%s '",
update_loop_counter_, controller_go ? "True" : "False",
Expand Down
104 changes: 104 additions & 0 deletions controller_manager/test/test_controller_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -253,5 +253,109 @@ TEST_P(TestControllerManager, per_controller_update_rate)
EXPECT_EQ(test_controller->get_update_rate(), 4u);
}

TEST_P(TestControllerManager, per_controller_equal_and_higher_update_rate)
{
auto strictness = GetParam().strictness;
auto test_controller = std::make_shared<test_controller::TestController>();

auto last_internal_counter = 0u;
for (unsigned int ctrl_update_rate : {100, 232, 400})
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I'll do a small refactor here tomorrow, otherwise we are good to go IMO

Copy link
Member Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Sure

{
RCLCPP_INFO(
rclcpp::get_logger("test_controller_manager"), "Testing update rate : %d Hz",
ctrl_update_rate);
{
ControllerManagerRunner cm_runner(this);
cm_->add_controller(
test_controller, test_controller::TEST_CONTROLLER_NAME,
test_controller::TEST_CONTROLLER_CLASS_NAME);
}
EXPECT_EQ(1u, cm_->get_loaded_controllers().size());
EXPECT_EQ(2, test_controller.use_count());
EXPECT_EQ(
controller_interface::return_type::OK,
cm_->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)));
EXPECT_EQ(last_internal_counter, test_controller->internal_counter)
<< "Update should not reach an unconfigured controller";

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

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);
EXPECT_EQ(
controller_interface::return_type::OK,
cm_->update(rclcpp::Time(0), 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());

// Start controller, will take effect at the end of the update function
std::vector<std::string> start_controllers = {test_controller::TEST_CONTROLLER_NAME};
std::vector<std::string> stop_controllers = {};
auto switch_future = std::async(
std::launch::async, &controller_manager::ControllerManager::switch_controller, cm_,
start_controllers, stop_controllers, strictness, true, rclcpp::Duration(0, 0));

ASSERT_EQ(std::future_status::timeout, switch_future.wait_for(std::chrono::milliseconds(100)))
<< "switch_controller should be blocking until next update cycle";

EXPECT_EQ(
controller_interface::return_type::OK,
cm_->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)));
EXPECT_EQ(last_internal_counter, test_controller->internal_counter)
<< "Controller is started at the end of update";
{
ControllerManagerRunner cm_runner(this);
EXPECT_EQ(controller_interface::return_type::OK, switch_future.get());
}

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

const auto pre_internal_counter = test_controller->internal_counter;
rclcpp::Rate loop_rate(cm_->get_update_rate());
for (size_t i = 0; i < 2 * cm_->get_update_rate(); i++)
{
EXPECT_EQ(
controller_interface::return_type::OK,
cm_->update(rclcpp::Time(0), 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
// similarly incremented
EXPECT_EQ(
test_controller->internal_counter, pre_internal_counter + (2 * cm_->get_update_rate()));
EXPECT_EQ(test_controller->get_update_rate(), ctrl_update_rate);

auto deactivate_future = std::async(
std::launch::async, &controller_manager::ControllerManager::switch_controller, cm_,
stop_controllers, start_controllers, strictness, true, rclcpp::Duration(0, 0));

ASSERT_EQ(
std::future_status::timeout, deactivate_future.wait_for(std::chrono::milliseconds(100)))
<< "switch_controller should be blocking until next update cycle";

EXPECT_EQ(
controller_interface::return_type::OK,
cm_->update(rclcpp::Time(0), 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);
EXPECT_EQ(controller_interface::return_type::OK, deactivate_future.get());
}
auto unload_future = std::async(
std::launch::async, &controller_manager::ControllerManager::unload_controller, cm_,
test_controller::TEST_CONTROLLER_NAME);
ASSERT_EQ(std::future_status::timeout, unload_future.wait_for(std::chrono::milliseconds(100)))
<< "unload_controller should be blocking until next update cycle";
ControllerManagerRunner cm_runner(this);
EXPECT_EQ(controller_interface::return_type::OK, unload_future.get());
last_internal_counter = test_controller->internal_counter;
}
}

INSTANTIATE_TEST_SUITE_P(
test_strict_best_effort, TestControllerManager, testing::Values(strict, best_effort));