Skip to content

Commit

Permalink
address rate related flaky tests. (#2329) (#2342)
Browse files Browse the repository at this point in the history
Signed-off-by: Tomoya Fujita <Tomoya.Fujita@sony.com>
(cherry picked from commit fcbe64c)

Co-authored-by: Tomoya Fujita <Tomoya.Fujita@sony.com>
  • Loading branch information
mergify[bot] and fujitatomoya authored Oct 26, 2023
1 parent adfc546 commit 8709146
Show file tree
Hide file tree
Showing 2 changed files with 18 additions and 4 deletions.
2 changes: 1 addition & 1 deletion rclcpp/src/rclcpp/context.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -497,7 +497,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
20 changes: 17 additions & 3 deletions rclcpp/test/rclcpp/test_rate.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);
Expand Down Expand Up @@ -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);
Expand Down Expand Up @@ -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());
Expand Down

0 comments on commit 8709146

Please sign in to comment.