Skip to content

Commit 328efb2

Browse files
committed
address rate related flaky tests. (#2329)
Signed-off-by: Tomoya Fujita <[email protected]> (cherry picked from commit fcbe64c)
1 parent adfc546 commit 328efb2

File tree

2 files changed

+18
-4
lines changed

2 files changed

+18
-4
lines changed

rclcpp/src/rclcpp/context.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -497,7 +497,7 @@ Context::sleep_for(const std::chrono::nanoseconds & nanoseconds)
497497
std::unique_lock<std::mutex> lock(interrupt_mutex_);
498498
auto start = std::chrono::steady_clock::now();
499499
// this will release the lock while waiting
500-
interrupt_condition_variable_.wait_for(lock, nanoseconds);
500+
interrupt_condition_variable_.wait_for(lock, time_left);
501501
time_left -= std::chrono::steady_clock::now() - start;
502502
}
503503
} while (time_left > std::chrono::nanoseconds::zero() && this->is_valid());

rclcpp/test/rclcpp/test_rate.cpp

Lines changed: 17 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -18,10 +18,24 @@
1818

1919
#include "rclcpp/rate.hpp"
2020

21+
class TestRate : public ::testing::Test
22+
{
23+
public:
24+
void SetUp()
25+
{
26+
rclcpp::init(0, nullptr);
27+
}
28+
29+
void TearDown()
30+
{
31+
rclcpp::shutdown();
32+
}
33+
};
34+
2135
/*
2236
Basic tests for the Rate and WallRate classes.
2337
*/
24-
TEST(TestRate, rate_basics) {
38+
TEST_F(TestRate, rate_basics) {
2539
auto period = std::chrono::milliseconds(1000);
2640
auto offset = std::chrono::milliseconds(500);
2741
auto epsilon = std::chrono::milliseconds(100);
@@ -61,7 +75,7 @@ TEST(TestRate, rate_basics) {
6175
ASSERT_TRUE(epsilon > delta);
6276
}
6377

64-
TEST(TestRate, wall_rate_basics) {
78+
TEST_F(TestRate, wall_rate_basics) {
6579
auto period = std::chrono::milliseconds(100);
6680
auto offset = std::chrono::milliseconds(50);
6781
auto epsilon = std::chrono::milliseconds(1);
@@ -101,7 +115,7 @@ TEST(TestRate, wall_rate_basics) {
101115
EXPECT_GT(epsilon, delta);
102116
}
103117

104-
TEST(TestRate, from_double) {
118+
TEST_F(TestRate, from_double) {
105119
{
106120
rclcpp::WallRate rate(1.0);
107121
EXPECT_EQ(std::chrono::seconds(1), rate.period());

0 commit comments

Comments
 (0)