From 328efb2ecfa65ad159b325375c22b3e433bbfc1f Mon Sep 17 00:00:00 2001 From: Tomoya Fujita Date: Thu, 26 Oct 2023 00:08:18 -0700 Subject: [PATCH] address rate related flaky tests. (#2329) Signed-off-by: Tomoya Fujita (cherry picked from commit fcbe64cff4bea3109531254ceb2955dc4b1bb320) --- rclcpp/src/rclcpp/context.cpp | 2 +- rclcpp/test/rclcpp/test_rate.cpp | 20 +++++++++++++++++--- 2 files changed, 18 insertions(+), 4 deletions(-) diff --git a/rclcpp/src/rclcpp/context.cpp b/rclcpp/src/rclcpp/context.cpp index b9410ca089..33bd0bf0b9 100644 --- a/rclcpp/src/rclcpp/context.cpp +++ b/rclcpp/src/rclcpp/context.cpp @@ -497,7 +497,7 @@ Context::sleep_for(const std::chrono::nanoseconds & nanoseconds) std::unique_lock lock(interrupt_mutex_); auto start = std::chrono::steady_clock::now(); // this will release the lock while waiting - interrupt_condition_variable_.wait_for(lock, nanoseconds); + interrupt_condition_variable_.wait_for(lock, time_left); time_left -= std::chrono::steady_clock::now() - start; } } while (time_left > std::chrono::nanoseconds::zero() && this->is_valid()); diff --git a/rclcpp/test/rclcpp/test_rate.cpp b/rclcpp/test/rclcpp/test_rate.cpp index d6608d59f6..7120805429 100644 --- a/rclcpp/test/rclcpp/test_rate.cpp +++ b/rclcpp/test/rclcpp/test_rate.cpp @@ -18,10 +18,24 @@ #include "rclcpp/rate.hpp" +class TestRate : public ::testing::Test +{ +public: + void SetUp() + { + rclcpp::init(0, nullptr); + } + + void TearDown() + { + rclcpp::shutdown(); + } +}; + /* Basic tests for the Rate and WallRate classes. */ -TEST(TestRate, rate_basics) { +TEST_F(TestRate, rate_basics) { auto period = std::chrono::milliseconds(1000); auto offset = std::chrono::milliseconds(500); auto epsilon = std::chrono::milliseconds(100); @@ -61,7 +75,7 @@ TEST(TestRate, rate_basics) { ASSERT_TRUE(epsilon > delta); } -TEST(TestRate, wall_rate_basics) { +TEST_F(TestRate, wall_rate_basics) { auto period = std::chrono::milliseconds(100); auto offset = std::chrono::milliseconds(50); auto epsilon = std::chrono::milliseconds(1); @@ -101,7 +115,7 @@ TEST(TestRate, wall_rate_basics) { EXPECT_GT(epsilon, delta); } -TEST(TestRate, from_double) { +TEST_F(TestRate, from_double) { { rclcpp::WallRate rate(1.0); EXPECT_EQ(std::chrono::seconds(1), rate.period());