Skip to content

Commit 6077af4

Browse files
authored
[Controllers] Receive a valid period on the first update cycle (#2572)
1 parent 1506412 commit 6077af4

File tree

2 files changed

+15
-17
lines changed

2 files changed

+15
-17
lines changed

controller_manager/src/controller_manager.cpp

Lines changed: 5 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -2961,21 +2961,13 @@ controller_interface::return_type ControllerManager::update(
29612961
run_controller_at_cm_rate ? period
29622962
: rclcpp::Duration::from_seconds((1.0 / controller_update_rate));
29632963

2964-
bool first_update_cycle = false;
2964+
const bool first_update_cycle =
2965+
(*loaded_controller.last_update_cycle_time ==
2966+
rclcpp::Time(0, 0, this->get_trigger_clock()->get_clock_type()));
29652967
const rclcpp::Time current_time = get_clock()->started() ? get_trigger_clock()->now() : time;
2966-
if (
2967-
*loaded_controller.last_update_cycle_time ==
2968-
rclcpp::Time(0, 0, this->get_trigger_clock()->get_clock_type()))
2969-
{
2970-
// last_update_cycle_time is zero after activation
2971-
first_update_cycle = true;
2972-
*loaded_controller.last_update_cycle_time = current_time;
2973-
RCLCPP_DEBUG(
2974-
get_logger(), "Setting last_update_cycle_time to %fs for the controller : %s",
2975-
loaded_controller.last_update_cycle_time->seconds(), loaded_controller.info.name.c_str());
2976-
}
29772968
const auto controller_actual_period =
2978-
(current_time - *loaded_controller.last_update_cycle_time);
2969+
first_update_cycle ? controller_period
2970+
: (current_time - *loaded_controller.last_update_cycle_time);
29792971

29802972
const double error_now =
29812973
std::abs((controller_actual_period.seconds() * controller_update_rate) - 1.0);

controller_manager/test/test_controller_manager.cpp

Lines changed: 10 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -472,8 +472,11 @@ TEST_P(TestControllerManagerWithStrictness, async_controller_lifecycle)
472472
std::this_thread::sleep_for(
473473
std::chrono::milliseconds(1000 / (test_controller->get_update_rate())));
474474
EXPECT_EQ(test_controller->internal_counter, 1u);
475-
EXPECT_EQ(test_controller->update_period_.seconds(), 0.0)
476-
<< "The first trigger cycle should have zero period";
475+
EXPECT_NEAR(
476+
test_controller->update_period_.seconds(),
477+
1.0 / (static_cast<double>(test_controller->get_update_rate())), 1.e-6)
478+
<< "The first trigger cycle should have non-zero period to allow for integration in the "
479+
"controllers";
477480

478481
const double exp_period = (cm_->get_trigger_clock()->now() - time_).seconds();
479482
time_ = cm_->get_trigger_clock()->now();
@@ -1064,8 +1067,11 @@ TEST_P(TestControllerUpdateRates, check_the_controller_update_rate)
10641067
}
10651068
else
10661069
{
1067-
// Check that the first cycle update period is zero
1068-
EXPECT_EQ(test_controller->update_period_.seconds(), 0.0);
1070+
EXPECT_NEAR(
1071+
test_controller->update_period_.seconds(),
1072+
1.0 / (static_cast<double>(test_controller->get_update_rate())), 1.e-6)
1073+
<< "The first trigger cycle should have non-zero period to allow for integration in the "
1074+
"controllers";
10691075
}
10701076

10711077
if (update_counter > 0 && update_counter % cm_update_rate == 0)

0 commit comments

Comments
 (0)