@@ -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