-
Notifications
You must be signed in to change notification settings - Fork 522
Expand file tree
/
Copy pathtest_clock_conditional.cpp
More file actions
246 lines (195 loc) · 7.01 KB
/
test_clock_conditional.cpp
File metadata and controls
246 lines (195 loc) · 7.01 KB
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
// Copyright 2025 Cellumation GmbH
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#include <gtest/gtest.h>
#include <chrono>
#include "rcl/error_handling.h"
#include "rcl/time.h"
#include "rclcpp/clock.hpp"
#include "rclcpp/rclcpp.hpp"
#include "rclcpp/time_source.hpp"
#include "../utils/rclcpp_gtest_macros.hpp"
using namespace std::chrono_literals;
class TestClockWakeup : public ::testing::TestWithParam<rcl_clock_type_e>
{
public:
void test_wakeup_before_sleep(const rclcpp::Clock::SharedPtr & clock)
{
std::atomic_bool thread_finished = false;
rclcpp::ClockConditionalVariable cond(clock);
bool stopSleeping = false;
std::thread wait_thread = std::thread(
[&cond, &clock, &stopSleeping, &thread_finished]()
{
// make sure the thread starts sleeping late
std::this_thread::sleep_for(std::chrono::milliseconds(100));
std::unique_lock lk(cond.mutex());
cond.wait_until(lk, clock->now() + std::chrono::seconds(3),
[&stopSleeping] () {return stopSleeping;});
thread_finished = true;
});
{
std::lock_guard lk(cond.mutex());
// stop sleeping after next notification
stopSleeping = true;
}
// notify the conditional, to recheck it pred
cond.notify_one();
auto start_time = std::chrono::steady_clock::now();
auto cur_time = start_time;
while (!thread_finished && start_time + std::chrono::seconds(1) > cur_time) {
std::this_thread::sleep_for(std::chrono::milliseconds(10));
cur_time = std::chrono::steady_clock::now();
}
wait_thread.join();
EXPECT_TRUE(thread_finished);
EXPECT_LT(cur_time, start_time + std::chrono::seconds(1));
}
void test_wakeup_after_sleep(const rclcpp::Clock::SharedPtr & clock)
{
std::atomic_bool thread_finished = false;
rclcpp::ClockConditionalVariable cond(clock);
bool stopSleeping = false;
std::thread wait_thread = std::thread(
[&cond, &clock, &stopSleeping, &thread_finished]()
{
std::unique_lock lk(cond.mutex());
cond.wait_until(lk, clock->now() + std::chrono::seconds(3),
[&stopSleeping] () {return stopSleeping;});
thread_finished = true;
});
// make sure the thread is already sleeping before we send the cancel
std::this_thread::sleep_for(std::chrono::milliseconds(100));
{
std::lock_guard lk(cond.mutex());
// stop sleeping after next notification
stopSleeping = true;
}
// notify the conditional, to recheck it pred
cond.notify_one();
auto start_time = std::chrono::steady_clock::now();
auto cur_time = start_time;
while (!thread_finished && start_time + std::chrono::seconds(1) > cur_time) {
std::this_thread::sleep_for(std::chrono::milliseconds(10));
cur_time = std::chrono::steady_clock::now();
}
wait_thread.join();
EXPECT_TRUE(thread_finished);
EXPECT_LT(cur_time, start_time + std::chrono::seconds(1));
}
protected:
static void SetUpTestCase()
{
rclcpp::init(0, nullptr);
}
static void TearDownTestCase()
{
rclcpp::shutdown();
}
void SetUp()
{
node = std::make_shared<rclcpp::Node>("my_node");
}
void TearDown()
{
node.reset();
}
rclcpp::Node::SharedPtr node;
};
INSTANTIATE_TEST_SUITE_P(
ClockConditionalVariable,
TestClockWakeup,
::testing::Values(
RCL_SYSTEM_TIME, RCL_ROS_TIME, RCL_STEADY_TIME
));
TEST_P(TestClockWakeup, wakeup_sleep) {
auto clock = std::make_shared<rclcpp::Clock>(GetParam());
test_wakeup_after_sleep(clock);
test_wakeup_before_sleep(clock);
}
TEST_F(TestClockWakeup, wakeup_sleep_ros_time_active) {
node->set_parameter({"use_sim_time", true});
auto clock = std::make_shared<rclcpp::Clock>(RCL_ROS_TIME);
rclcpp::TimeSource time_source(node);
time_source.attachClock(clock);
EXPECT_TRUE(clock->ros_time_is_active());
test_wakeup_after_sleep(clock);
test_wakeup_before_sleep(clock);
}
TEST_F(TestClockWakeup, no_wakeup_on_sim_time) {
node->set_parameter({"use_sim_time", true});
auto clock = std::make_shared<rclcpp::Clock>(RCL_ROS_TIME);
EXPECT_FALSE(clock->ros_time_is_active());
rclcpp::TimeSource time_source(node);
time_source.attachClock(clock);
EXPECT_TRUE(clock->ros_time_is_active());
std::atomic_bool thread_finished = false;
rclcpp::ClockConditionalVariable cond(clock);
bool stopSleeping = false;
std::thread wait_thread = std::thread(
[&cond, &clock, &stopSleeping, &thread_finished]()
{
std::unique_lock lk(cond.mutex());
// only sleep for an short period
cond.wait_until(lk, clock->now() + std::chrono::milliseconds(10),
[&stopSleeping] () {return stopSleeping;});
thread_finished = true;
});
// make sure, that the sim time clock does not wakeup, as no clock is provided
std::this_thread::sleep_for(std::chrono::milliseconds(500));
EXPECT_FALSE(thread_finished);
{
std::lock_guard lk(cond.mutex());
// stop sleeping after next notification
stopSleeping = true;
}
// notify the conditional, to recheck it pred
cond.notify_one();
auto start_time = std::chrono::steady_clock::now();
auto cur_time = start_time;
while (!thread_finished && start_time + std::chrono::seconds(1) > cur_time) {
std::this_thread::sleep_for(std::chrono::milliseconds(10));
cur_time = std::chrono::steady_clock::now();
}
wait_thread.join();
EXPECT_TRUE(thread_finished);
EXPECT_LT(cur_time, start_time + std::chrono::seconds(1));
}
TEST_F(TestClockWakeup, wakeup_on_ros_shutdown) {
auto clock = std::make_shared<rclcpp::Clock>(RCL_ROS_TIME);
std::atomic_bool thread_finished = false;
rclcpp::ClockConditionalVariable cond(clock);
bool stopSleeping = false;
std::thread wait_thread = std::thread(
[&cond, &clock, &stopSleeping, &thread_finished]()
{
std::unique_lock lk(cond.mutex());
// only sleep for an short period
cond.wait_until(lk, clock->now() + std::chrono::seconds(10),
[&stopSleeping] () {return stopSleeping;});
thread_finished = true;
});
// wait a bit to be sure the thread is sleeping
std::this_thread::sleep_for(std::chrono::milliseconds(500));
EXPECT_FALSE(thread_finished);
rclcpp::shutdown();
auto start_time = std::chrono::steady_clock::now();
auto cur_time = start_time;
while (!thread_finished && start_time + std::chrono::seconds(1) > cur_time) {
std::this_thread::sleep_for(std::chrono::milliseconds(10));
cur_time = std::chrono::steady_clock::now();
}
EXPECT_TRUE(thread_finished);
wait_thread.join();
EXPECT_LT(cur_time, start_time + std::chrono::seconds(1));
}