Skip to content

Commit

Permalink
address rate related flaky tests. (#2329)
Browse files Browse the repository at this point in the history
Signed-off-by: Tomoya Fujita <[email protected]>
  • Loading branch information
fujitatomoya authored Oct 26, 2023
1 parent c366e53 commit fcbe64c
Show file tree
Hide file tree
Showing 3 changed files with 23 additions and 16 deletions.
2 changes: 1 addition & 1 deletion rclcpp/src/rclcpp/context.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -496,7 +496,7 @@ Context::sleep_for(const std::chrono::nanoseconds & nanoseconds)
std::unique_lock<std::mutex> 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());
Expand Down
3 changes: 2 additions & 1 deletion rclcpp/src/rclcpp/rate.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -67,7 +67,8 @@ Rate::sleep()
// Calculate the time to sleep
auto time_to_sleep = next_interval - now;
// Sleep (will get interrupted by ctrl-c, may not sleep full time)
return clock_->sleep_for(time_to_sleep);
clock_->sleep_for(time_to_sleep);
return true;
}

bool
Expand Down
34 changes: 20 additions & 14 deletions rclcpp/test/rclcpp/test_rate.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -21,12 +21,24 @@

#include "../utils/rclcpp_gtest_macros.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) {
rclcpp::init(0, nullptr);

TEST_F(TestRate, rate_basics) {
auto period = std::chrono::milliseconds(1000);
auto offset = std::chrono::milliseconds(500);
auto epsilon = std::chrono::milliseconds(100);
Expand Down Expand Up @@ -79,13 +91,9 @@ TEST(TestRate, rate_basics) {
auto five = std::chrono::system_clock::now();
delta = five - four;
ASSERT_TRUE(epsilon > delta);

rclcpp::shutdown();
}

TEST(TestRate, wall_rate_basics) {
rclcpp::init(0, nullptr);

TEST_F(TestRate, wall_rate_basics) {
auto period = std::chrono::milliseconds(100);
auto offset = std::chrono::milliseconds(50);
auto epsilon = std::chrono::milliseconds(1);
Expand Down Expand Up @@ -140,14 +148,12 @@ TEST(TestRate, wall_rate_basics) {
auto five = std::chrono::steady_clock::now();
delta = five - four;
EXPECT_GT(epsilon, delta);

rclcpp::shutdown();
}

/*
Basic test for the deprecated GenericRate class.
*/
TEST(TestRate, generic_rate) {
TEST_F(TestRate, generic_rate) {
auto period = std::chrono::milliseconds(100);
auto offset = std::chrono::milliseconds(50);
auto epsilon = std::chrono::milliseconds(1);
Expand Down Expand Up @@ -262,7 +268,7 @@ TEST(TestRate, generic_rate) {
}
}

TEST(TestRate, from_double) {
TEST_F(TestRate, from_double) {
{
rclcpp::Rate rate(1.0);
EXPECT_EQ(rclcpp::Duration(std::chrono::seconds(1)), rate.period());
Expand All @@ -281,7 +287,7 @@ TEST(TestRate, from_double) {
}
}

TEST(TestRate, clock_types) {
TEST_F(TestRate, clock_types) {
{
rclcpp::Rate rate(1.0, std::make_shared<rclcpp::Clock>(RCL_SYSTEM_TIME));
// suppress deprecated warnings
Expand Down Expand Up @@ -341,7 +347,7 @@ TEST(TestRate, clock_types) {
}
}

TEST(TestRate, incorrect_constuctor) {
TEST_F(TestRate, incorrect_constuctor) {
// Constructor with 0-frequency
RCLCPP_EXPECT_THROW_EQ(
rclcpp::Rate rate(0.0),
Expand Down

0 comments on commit fcbe64c

Please sign in to comment.