Skip to content

Commit d0fd7ff

Browse files
fujitatomoyamergify[bot]
authored andcommitted
address rate related flaky tests. (#2329)
Signed-off-by: Tomoya Fujita <[email protected]> (cherry picked from commit fcbe64c) # Conflicts: # rclcpp/src/rclcpp/rate.cpp # rclcpp/test/rclcpp/test_rate.cpp
1 parent adfc546 commit d0fd7ff

File tree

3 files changed

+341
-2
lines changed

3 files changed

+341
-2
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/src/rclcpp/rate.cpp

Lines changed: 106 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,106 @@
1+
// Copyright 2023 Open Source Robotics Foundation, Inc.
2+
//
3+
// Licensed under the Apache License, Version 2.0 (the "License");
4+
// you may not use this file except in compliance with the License.
5+
// You may obtain a copy of the License at
6+
//
7+
// http://www.apache.org/licenses/LICENSE-2.0
8+
//
9+
// Unless required by applicable law or agreed to in writing, software
10+
// distributed under the License is distributed on an "AS IS" BASIS,
11+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
// See the License for the specific language governing permissions and
13+
// limitations under the License.
14+
15+
#include "rclcpp/rate.hpp"
16+
17+
#include <chrono>
18+
#include <stdexcept>
19+
20+
namespace rclcpp
21+
{
22+
23+
Rate::Rate(
24+
const double rate, Clock::SharedPtr clock)
25+
: clock_(clock), period_(0, 0), last_interval_(clock_->now())
26+
{
27+
if (rate <= 0.0) {
28+
throw std::invalid_argument{"rate must be greater than 0"};
29+
}
30+
period_ = Duration::from_seconds(1.0 / rate);
31+
}
32+
33+
Rate::Rate(
34+
const Duration & period, Clock::SharedPtr clock)
35+
: clock_(clock), period_(period), last_interval_(clock_->now())
36+
{
37+
if (period <= Duration(0, 0)) {
38+
throw std::invalid_argument{"period must be greater than 0"};
39+
}
40+
}
41+
42+
bool
43+
Rate::sleep()
44+
{
45+
// Time coming into sleep
46+
auto now = clock_->now();
47+
// Time of next interval
48+
auto next_interval = last_interval_ + period_;
49+
// Detect backwards time flow
50+
if (now < last_interval_) {
51+
// Best thing to do is to set the next_interval to now + period
52+
next_interval = now + period_;
53+
}
54+
// Update the interval
55+
last_interval_ += period_;
56+
// If the time_to_sleep is negative or zero, don't sleep
57+
if (next_interval <= now) {
58+
// If an entire cycle was missed then reset next interval.
59+
// This might happen if the loop took more than a cycle.
60+
// Or if time jumps forward.
61+
if (now > next_interval + period_) {
62+
last_interval_ = now + period_;
63+
}
64+
// Either way do not sleep and return false
65+
return false;
66+
}
67+
// Calculate the time to sleep
68+
auto time_to_sleep = next_interval - now;
69+
// Sleep (will get interrupted by ctrl-c, may not sleep full time)
70+
clock_->sleep_for(time_to_sleep);
71+
return true;
72+
}
73+
74+
bool
75+
Rate::is_steady() const
76+
{
77+
return clock_->get_clock_type() == RCL_STEADY_TIME;
78+
}
79+
80+
rcl_clock_type_t
81+
Rate::get_type() const
82+
{
83+
return clock_->get_clock_type();
84+
}
85+
86+
void
87+
Rate::reset()
88+
{
89+
last_interval_ = clock_->now();
90+
}
91+
92+
std::chrono::nanoseconds
93+
Rate::period() const
94+
{
95+
return std::chrono::nanoseconds(period_.nanoseconds());
96+
}
97+
98+
WallRate::WallRate(const double rate)
99+
: Rate(rate, std::make_shared<Clock>(RCL_STEADY_TIME))
100+
{}
101+
102+
WallRate::WallRate(const Duration & period)
103+
: Rate(period, std::make_shared<Clock>(RCL_STEADY_TIME))
104+
{}
105+
106+
} // namespace rclcpp

rclcpp/test/rclcpp/test_rate.cpp

Lines changed: 234 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -18,10 +18,33 @@
1818

1919
#include "rclcpp/rate.hpp"
2020

21+
<<<<<<< HEAD
2122
/*
2223
Basic tests for the Rate and WallRate classes.
2324
*/
2425
TEST(TestRate, rate_basics) {
26+
=======
27+
#include "../utils/rclcpp_gtest_macros.hpp"
28+
29+
class TestRate : public ::testing::Test
30+
{
31+
public:
32+
void SetUp()
33+
{
34+
rclcpp::init(0, nullptr);
35+
}
36+
37+
void TearDown()
38+
{
39+
rclcpp::shutdown();
40+
}
41+
};
42+
43+
/*
44+
Basic tests for the Rate and WallRate classes.
45+
*/
46+
TEST_F(TestRate, rate_basics) {
47+
>>>>>>> fcbe64cf (address rate related flaky tests. (#2329))
2548
auto period = std::chrono::milliseconds(1000);
2649
auto offset = std::chrono::milliseconds(500);
2750
auto epsilon = std::chrono::milliseconds(100);
@@ -61,7 +84,11 @@ TEST(TestRate, rate_basics) {
6184
ASSERT_TRUE(epsilon > delta);
6285
}
6386

87+
<<<<<<< HEAD
6488
TEST(TestRate, wall_rate_basics) {
89+
=======
90+
TEST_F(TestRate, wall_rate_basics) {
91+
>>>>>>> fcbe64cf (address rate related flaky tests. (#2329))
6592
auto period = std::chrono::milliseconds(100);
6693
auto offset = std::chrono::milliseconds(50);
6794
auto epsilon = std::chrono::milliseconds(1);
@@ -99,9 +126,130 @@ TEST(TestRate, wall_rate_basics) {
99126
auto five = std::chrono::steady_clock::now();
100127
delta = five - four;
101128
EXPECT_GT(epsilon, delta);
129+
<<<<<<< HEAD
130+
=======
102131
}
103132

104-
TEST(TestRate, from_double) {
133+
/*
134+
Basic test for the deprecated GenericRate class.
135+
*/
136+
TEST_F(TestRate, generic_rate) {
137+
auto period = std::chrono::milliseconds(100);
138+
auto offset = std::chrono::milliseconds(50);
139+
auto epsilon = std::chrono::milliseconds(1);
140+
double overrun_ratio = 1.5;
141+
142+
{
143+
auto start = std::chrono::system_clock::now();
144+
145+
// suppress deprecated warnings
146+
#if !defined(_WIN32)
147+
# pragma GCC diagnostic push
148+
# pragma GCC diagnostic ignored "-Wdeprecated-declarations"
149+
#else // !defined(_WIN32)
150+
# pragma warning(push)
151+
# pragma warning(disable: 4996)
152+
#endif
153+
154+
rclcpp::GenericRate<std::chrono::system_clock> gr(period);
155+
ASSERT_FALSE(gr.is_steady());
156+
157+
// remove warning suppression
158+
#if !defined(_WIN32)
159+
# pragma GCC diagnostic pop
160+
#else // !defined(_WIN32)
161+
# pragma warning(pop)
162+
#endif
163+
164+
ASSERT_EQ(gr.get_type(), RCL_SYSTEM_TIME);
165+
EXPECT_EQ(period, gr.period());
166+
ASSERT_TRUE(gr.sleep());
167+
auto one = std::chrono::system_clock::now();
168+
auto delta = one - start;
169+
EXPECT_LT(period, delta + epsilon);
170+
EXPECT_GT(period * overrun_ratio, delta);
171+
172+
rclcpp::sleep_for(offset);
173+
ASSERT_TRUE(gr.sleep());
174+
auto two = std::chrono::system_clock::now();
175+
delta = two - start;
176+
EXPECT_LT(2 * period, delta);
177+
EXPECT_GT(2 * period * overrun_ratio, delta);
178+
179+
rclcpp::sleep_for(offset);
180+
auto two_offset = std::chrono::system_clock::now();
181+
gr.reset();
182+
ASSERT_TRUE(gr.sleep());
183+
auto three = std::chrono::system_clock::now();
184+
delta = three - two_offset;
185+
EXPECT_LT(period, delta + epsilon);
186+
EXPECT_GT(period * overrun_ratio, delta);
187+
188+
rclcpp::sleep_for(offset + period);
189+
auto four = std::chrono::system_clock::now();
190+
ASSERT_FALSE(gr.sleep());
191+
auto five = std::chrono::system_clock::now();
192+
delta = five - four;
193+
ASSERT_TRUE(epsilon > delta);
194+
}
195+
196+
{
197+
auto start = std::chrono::steady_clock::now();
198+
199+
// suppress deprecated warnings
200+
#if !defined(_WIN32)
201+
# pragma GCC diagnostic push
202+
# pragma GCC diagnostic ignored "-Wdeprecated-declarations"
203+
#else // !defined(_WIN32)
204+
# pragma warning(push)
205+
# pragma warning(disable: 4996)
206+
#endif
207+
208+
rclcpp::GenericRate<std::chrono::steady_clock> gr(period);
209+
ASSERT_TRUE(gr.is_steady());
210+
211+
// remove warning suppression
212+
#if !defined(_WIN32)
213+
# pragma GCC diagnostic pop
214+
#else // !defined(_WIN32)
215+
# pragma warning(pop)
216+
#endif
217+
218+
ASSERT_EQ(gr.get_type(), RCL_STEADY_TIME);
219+
EXPECT_EQ(period, gr.period());
220+
ASSERT_TRUE(gr.sleep());
221+
auto one = std::chrono::steady_clock::now();
222+
auto delta = one - start;
223+
EXPECT_LT(period, delta);
224+
EXPECT_GT(period * overrun_ratio, delta);
225+
226+
rclcpp::sleep_for(offset);
227+
ASSERT_TRUE(gr.sleep());
228+
auto two = std::chrono::steady_clock::now();
229+
delta = two - start;
230+
EXPECT_LT(2 * period, delta + epsilon);
231+
EXPECT_GT(2 * period * overrun_ratio, delta);
232+
233+
rclcpp::sleep_for(offset);
234+
auto two_offset = std::chrono::steady_clock::now();
235+
gr.reset();
236+
ASSERT_TRUE(gr.sleep());
237+
auto three = std::chrono::steady_clock::now();
238+
delta = three - two_offset;
239+
EXPECT_LT(period, delta);
240+
EXPECT_GT(period * overrun_ratio, delta);
241+
242+
rclcpp::sleep_for(offset + period);
243+
auto four = std::chrono::steady_clock::now();
244+
ASSERT_FALSE(gr.sleep());
245+
auto five = std::chrono::steady_clock::now();
246+
delta = five - four;
247+
EXPECT_GT(epsilon, delta);
248+
}
249+
>>>>>>> fcbe64cf (address rate related flaky tests. (#2329))
250+
}
251+
252+
TEST_F(TestRate, from_double) {
105253
{
106254
rclcpp::WallRate rate(1.0);
107255
EXPECT_EQ(std::chrono::seconds(1), rate.period());
@@ -119,3 +267,88 @@ TEST(TestRate, from_double) {
119267
EXPECT_EQ(std::chrono::milliseconds(250), rate.period());
120268
}
121269
}
270+
<<<<<<< HEAD
271+
=======
272+
273+
TEST_F(TestRate, clock_types) {
274+
{
275+
rclcpp::Rate rate(1.0, std::make_shared<rclcpp::Clock>(RCL_SYSTEM_TIME));
276+
// suppress deprecated warnings
277+
#if !defined(_WIN32)
278+
# pragma GCC diagnostic push
279+
# pragma GCC diagnostic ignored "-Wdeprecated-declarations"
280+
#else // !defined(_WIN32)
281+
# pragma warning(push)
282+
# pragma warning(disable: 4996)
283+
#endif
284+
EXPECT_FALSE(rate.is_steady());
285+
// remove warning suppression
286+
#if !defined(_WIN32)
287+
# pragma GCC diagnostic pop
288+
#else // !defined(_WIN32)
289+
# pragma warning(pop)
290+
#endif
291+
EXPECT_EQ(RCL_SYSTEM_TIME, rate.get_type());
292+
}
293+
{
294+
rclcpp::Rate rate(1.0, std::make_shared<rclcpp::Clock>(RCL_STEADY_TIME));
295+
// suppress deprecated warnings
296+
#if !defined(_WIN32)
297+
# pragma GCC diagnostic push
298+
# pragma GCC diagnostic ignored "-Wdeprecated-declarations"
299+
#else // !defined(_WIN32)
300+
# pragma warning(push)
301+
# pragma warning(disable: 4996)
302+
#endif
303+
EXPECT_TRUE(rate.is_steady());
304+
// remove warning suppression
305+
#if !defined(_WIN32)
306+
# pragma GCC diagnostic pop
307+
#else // !defined(_WIN32)
308+
# pragma warning(pop)
309+
#endif
310+
EXPECT_EQ(RCL_STEADY_TIME, rate.get_type());
311+
}
312+
{
313+
rclcpp::Rate rate(1.0, std::make_shared<rclcpp::Clock>(RCL_ROS_TIME));
314+
// suppress deprecated warnings
315+
#if !defined(_WIN32)
316+
# pragma GCC diagnostic push
317+
# pragma GCC diagnostic ignored "-Wdeprecated-declarations"
318+
#else // !defined(_WIN32)
319+
# pragma warning(push)
320+
# pragma warning(disable: 4996)
321+
#endif
322+
EXPECT_FALSE(rate.is_steady());
323+
// remove warning suppression
324+
#if !defined(_WIN32)
325+
# pragma GCC diagnostic pop
326+
#else // !defined(_WIN32)
327+
# pragma warning(pop)
328+
#endif
329+
EXPECT_EQ(RCL_ROS_TIME, rate.get_type());
330+
}
331+
}
332+
333+
TEST_F(TestRate, incorrect_constuctor) {
334+
// Constructor with 0-frequency
335+
RCLCPP_EXPECT_THROW_EQ(
336+
rclcpp::Rate rate(0.0),
337+
std::invalid_argument("rate must be greater than 0"));
338+
339+
// Constructor with negative frequency
340+
RCLCPP_EXPECT_THROW_EQ(
341+
rclcpp::Rate rate(-1.0),
342+
std::invalid_argument("rate must be greater than 0"));
343+
344+
// Constructor with 0-duration
345+
RCLCPP_EXPECT_THROW_EQ(
346+
rclcpp::Rate rate(rclcpp::Duration(0, 0)),
347+
std::invalid_argument("period must be greater than 0"));
348+
349+
// Constructor with negative duration
350+
RCLCPP_EXPECT_THROW_EQ(
351+
rclcpp::Rate rate(rclcpp::Duration(-1, 0)),
352+
std::invalid_argument("period must be greater than 0"));
353+
}
354+
>>>>>>> fcbe64cf (address rate related flaky tests. (#2329))

0 commit comments

Comments
 (0)