Skip to content

Commit 1ed61ef

Browse files
Fix update period for the first update after activation (ros-controls#1551)
1 parent e122f71 commit 1ed61ef

File tree

4 files changed

+27
-13
lines changed

4 files changed

+27
-13
lines changed

controller_manager/src/controller_manager.cpp

Lines changed: 11 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -2147,6 +2147,17 @@ controller_interface::return_type ControllerManager::update(
21472147
run_controller_at_cm_rate ? period
21482148
: rclcpp::Duration::from_seconds((1.0 / controller_update_rate));
21492149

2150+
if (
2151+
*loaded_controller.next_update_cycle_time ==
2152+
rclcpp::Time(0, 0, this->get_node_clock_interface()->get_clock()->get_clock_type()))
2153+
{
2154+
// it is zero after activation
2155+
RCLCPP_DEBUG(
2156+
get_logger(), "Setting next_update_cycle_time to %fs for the controller : %s",
2157+
time.seconds(), loaded_controller.info.name.c_str());
2158+
*loaded_controller.next_update_cycle_time = time;
2159+
}
2160+
21502161
bool controller_go =
21512162
(time ==
21522163
rclcpp::Time(0, 0, this->get_node_clock_interface()->get_clock()->get_clock_type())) ||
@@ -2182,12 +2193,6 @@ controller_interface::return_type ControllerManager::update(
21822193
controller_ret = controller_interface::return_type::ERROR;
21832194
}
21842195

2185-
if (
2186-
*loaded_controller.next_update_cycle_time ==
2187-
rclcpp::Time(0, 0, this->get_node_clock_interface()->get_clock()->get_clock_type()))
2188-
{
2189-
*loaded_controller.next_update_cycle_time = time;
2190-
}
21912196
*loaded_controller.next_update_cycle_time += controller_period;
21922197

21932198
if (controller_ret != controller_interface::return_type::OK)

controller_manager/test/test_controller/test_controller.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -62,7 +62,7 @@ controller_interface::InterfaceConfiguration TestController::state_interface_con
6262
controller_interface::return_type TestController::update(
6363
const rclcpp::Time & /*time*/, const rclcpp::Duration & period)
6464
{
65-
update_period_ = period.seconds();
65+
update_period_ = period;
6666
++internal_counter;
6767

6868
// set value to hardware to produce and test different behaviors there

controller_manager/test/test_controller/test_controller.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -80,7 +80,7 @@ class TestController : public controller_interface::ControllerInterface
8080
// enables external setting of values to command interfaces - used for simulation of hardware
8181
// errors
8282
double set_first_command_interface_value_to;
83-
double update_period_ = 0;
83+
rclcpp::Duration update_period_ = rclcpp::Duration::from_seconds(0.);
8484
};
8585

8686
} // namespace test_controller

controller_manager/test/test_controller_manager.cpp

Lines changed: 14 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -374,9 +374,12 @@ TEST_P(TestControllerManagerWithUpdateRates, per_controller_equal_and_higher_upd
374374
controller_interface::return_type::OK,
375375
cm_->update(time_, rclcpp::Duration::from_seconds(0.01)));
376376
// In case of a non perfect divisor, the update period should respect the rule
377-
// [controller_update_rate, 2*controller_update_rate)
378-
ASSERT_GE(test_controller->update_period_, 1.0 / cm_update_rate);
379-
ASSERT_LT(test_controller->update_period_, 2.0 / cm_update_rate);
377+
// [cm_update_rate, 2*cm_update_rate)
378+
EXPECT_THAT(
379+
test_controller->update_period_,
380+
testing::AllOf(
381+
testing::Ge(rclcpp::Duration::from_seconds(1.0 / cm_update_rate)),
382+
testing::Lt(rclcpp::Duration::from_seconds(2.0 / cm_update_rate))));
380383
loop_rate.sleep();
381384
}
382385
// if we do 2 times of the controller_manager update rate, the internal counter should be
@@ -445,6 +448,7 @@ TEST_P(TestControllerUpdateRates, check_the_controller_update_rate)
445448
EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, test_controller->get_state().id());
446449

447450
// Start controller, will take effect at the end of the update function
451+
time_ = test_controller->get_node()->now(); // set to something nonzero
448452
const auto strictness = controller_manager_msgs::srv::SwitchController::Request::STRICT;
449453
std::vector<std::string> start_controllers = {test_controller::TEST_CONTROLLER_NAME};
450454
std::vector<std::string> stop_controllers = {};
@@ -472,6 +476,7 @@ TEST_P(TestControllerUpdateRates, check_the_controller_update_rate)
472476
const auto controller_update_rate = test_controller->get_update_rate();
473477

474478
const auto initial_counter = test_controller->internal_counter;
479+
// don't start with zero to check if the period is correct if controller is activated anytime
475480
rclcpp::Time time = time_;
476481
for (size_t update_counter = 0; update_counter <= 10 * cm_update_rate; ++update_counter)
477482
{
@@ -480,8 +485,12 @@ TEST_P(TestControllerUpdateRates, check_the_controller_update_rate)
480485
cm_->update(time, rclcpp::Duration::from_seconds(0.01)));
481486
// In case of a non perfect divisor, the update period should respect the rule
482487
// [controller_update_rate, 2*controller_update_rate)
483-
ASSERT_GE(test_controller->update_period_, 1.0 / controller_update_rate);
484-
ASSERT_LT(test_controller->update_period_, 2.0 / controller_update_rate);
488+
EXPECT_THAT(
489+
test_controller->update_period_,
490+
testing::AllOf(
491+
testing::Ge(rclcpp::Duration::from_seconds(1.0 / controller_update_rate)),
492+
testing::Lt(rclcpp::Duration::from_seconds(2.0 / controller_update_rate))))
493+
<< "update_counter: " << update_counter;
485494

486495
time += rclcpp::Duration::from_seconds(0.01);
487496
if (update_counter % cm_update_rate == 0)

0 commit comments

Comments
 (0)