-
Notifications
You must be signed in to change notification settings - Fork 522
Expand file tree
/
Copy pathtest_events_executor.cpp
More file actions
617 lines (494 loc) · 16.2 KB
/
test_events_executor.cpp
File metadata and controls
617 lines (494 loc) · 16.2 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
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
// Copyright 2023 iRobot Corporation.
//
// 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 <memory>
#include <string>
#include "rclcpp/experimental/executors/events_executor/events_executor.hpp"
#include "test_msgs/srv/empty.hpp"
#include "test_msgs/msg/empty.hpp"
using namespace std::chrono_literals;
using rclcpp::experimental::executors::EventsExecutor;
class TestEventsExecutor : public ::testing::Test
{
public:
void SetUp()
{
rclcpp::init(0, nullptr);
}
void TearDown()
{
rclcpp::shutdown();
}
};
TEST_F(TestEventsExecutor, run_pub_sub)
{
auto node = std::make_shared<rclcpp::Node>("node");
bool msg_received = false;
auto subscription = node->create_subscription<test_msgs::msg::Empty>(
"topic", rclcpp::SensorDataQoS(),
[&msg_received]([[maybe_unused]] test_msgs::msg::Empty::ConstSharedPtr msg)
{
msg_received = true;
});
auto publisher = node->create_publisher<test_msgs::msg::Empty>("topic", rclcpp::SensorDataQoS());
EventsExecutor executor;
executor.add_node(node);
bool spin_exited = false;
std::thread spinner([&spin_exited, &executor]() {
executor.spin();
spin_exited = true;
});
auto msg = std::make_unique<test_msgs::msg::Empty>();
publisher->publish(std::move(msg));
// Wait some time for the subscription to receive the message
auto start = std::chrono::high_resolution_clock::now();
while (
!msg_received &&
!spin_exited &&
(std::chrono::high_resolution_clock::now() - start < 1s))
{
std::this_thread::sleep_for(25ms);
}
executor.cancel();
spinner.join();
executor.remove_node(node);
EXPECT_TRUE(msg_received);
EXPECT_TRUE(spin_exited);
}
TEST_F(TestEventsExecutor, run_clients_servers)
{
auto node = std::make_shared<rclcpp::Node>("node");
bool request_received = false;
bool response_received = false;
auto service =
node->create_service<test_msgs::srv::Empty>(
"service",
[&request_received](
const test_msgs::srv::Empty::Request::SharedPtr,
test_msgs::srv::Empty::Response::SharedPtr)
{
request_received = true;
});
auto client = node->create_client<test_msgs::srv::Empty>("service");
EventsExecutor executor;
executor.add_node(node);
bool spin_exited = false;
std::thread spinner([&spin_exited, &executor]() {
executor.spin();
spin_exited = true;
});
auto request = std::make_shared<test_msgs::srv::Empty::Request>();
client->async_send_request(
request,
[&response_received]([[maybe_unused]] rclcpp::Client<test_msgs::srv::Empty>::SharedFuture
result_future){
response_received = true;
});
// Wait some time for the client-server to be invoked
auto start = std::chrono::steady_clock::now();
while (
!response_received &&
!spin_exited &&
(std::chrono::steady_clock::now() - start < 1s))
{
std::this_thread::sleep_for(5ms);
}
executor.cancel();
spinner.join();
executor.remove_node(node);
EXPECT_TRUE(request_received);
EXPECT_TRUE(response_received);
EXPECT_TRUE(spin_exited);
}
TEST_F(TestEventsExecutor, spin_once_max_duration_timeout)
{
auto node = std::make_shared<rclcpp::Node>("node");
EventsExecutor executor;
executor.add_node(node);
// Consume previous events so we have a fresh start
executor.spin_all(1s);
size_t t_runs = 0;
auto t = node->create_wall_timer(
10s,
[&]() {
t_runs++;
});
// This first spin_once takes care of the waitable event
// generated by the addition of the timer to the node
executor.spin_once(1s);
EXPECT_EQ(0u, t_runs);
auto start = std::chrono::steady_clock::now();
// This second spin_once should take care of the timer,
executor.spin_once(10ms);
// but doesn't spin the time enough to call the timer callback.
EXPECT_EQ(0u, t_runs);
EXPECT_TRUE(std::chrono::steady_clock::now() - start < 200ms);
}
TEST_F(TestEventsExecutor, spin_once_max_duration_timer)
{
auto node = std::make_shared<rclcpp::Node>("node");
EventsExecutor executor;
executor.add_node(node);
// Consume previous events so we have a fresh start
executor.spin_all(1s);
size_t t_runs = 0;
auto t = node->create_wall_timer(
10ms,
[&]() {
t_runs++;
});
// This first spin_once takes care of the waitable event
// generated by the addition of the timer to the node
executor.spin_once(1s);
EXPECT_EQ(0u, t_runs);
auto start = std::chrono::steady_clock::now();
// This second spin_once should take care of the timer
executor.spin_once(11ms);
EXPECT_EQ(1u, t_runs);
EXPECT_TRUE(std::chrono::steady_clock::now() - start < 200ms);
}
TEST_F(TestEventsExecutor, spin_some_max_duration)
{
{
auto node = std::make_shared<rclcpp::Node>("node");
size_t t_runs = 0;
auto t = node->create_wall_timer(
10s,
[&]() {
t_runs++;
});
EventsExecutor executor;
executor.add_node(node);
auto start = std::chrono::steady_clock::now();
executor.spin_some(10ms);
EXPECT_EQ(0u, t_runs);
EXPECT_TRUE(std::chrono::steady_clock::now() - start < 200ms);
}
{
auto node = std::make_shared<rclcpp::Node>("node");
size_t t_runs = 0;
auto t = node->create_wall_timer(
10ms,
[&]() {
t_runs++;
});
// Sleep some time for the timer to be ready when spin
std::this_thread::sleep_for(10ms);
EventsExecutor executor;
executor.add_node(node);
auto start = std::chrono::steady_clock::now();
executor.spin_some(10s);
EXPECT_EQ(1u, t_runs);
EXPECT_TRUE(std::chrono::steady_clock::now() - start < 200ms);
}
}
TEST_F(TestEventsExecutor, spin_some_zero_duration)
{
auto node = std::make_shared<rclcpp::Node>("node");
size_t t_runs = 0;
auto t = node->create_wall_timer(
20ms,
[&]() {
t_runs++;
});
// Sleep some time for the timer to be ready when spin
std::this_thread::sleep_for(20ms);
EventsExecutor executor;
executor.add_node(node);
executor.spin_some(0ms);
EXPECT_EQ(1u, t_runs);
}
TEST_F(TestEventsExecutor, spin_all_max_duration)
{
{
auto node = std::make_shared<rclcpp::Node>("node");
size_t t_runs = 0;
auto t = node->create_wall_timer(
10s,
[&]() {
t_runs++;
});
EventsExecutor executor;
executor.add_node(node);
auto start = std::chrono::steady_clock::now();
executor.spin_all(10ms);
EXPECT_EQ(0u, t_runs);
EXPECT_TRUE(std::chrono::steady_clock::now() - start < 200ms);
}
{
auto node = std::make_shared<rclcpp::Node>("node");
size_t t_runs = 0;
auto t = node->create_wall_timer(
10ms,
[&]() {
t_runs++;
});
// Sleep some time for the timer to be ready when spin
std::this_thread::sleep_for(10ms);
EventsExecutor executor;
executor.add_node(node);
auto start = std::chrono::steady_clock::now();
executor.spin_all(10s);
EXPECT_EQ(1u, t_runs);
EXPECT_TRUE(std::chrono::steady_clock::now() - start < 200ms);
}
EventsExecutor executor;
EXPECT_THROW(executor.spin_all(0ms), std::invalid_argument);
EXPECT_THROW(executor.spin_all(-5ms), std::invalid_argument);
}
TEST_F(TestEventsExecutor, cancel_while_timers_running)
{
auto node = std::make_shared<rclcpp::Node>("node");
EventsExecutor executor;
executor.add_node(node);
// Take care of previous events for a fresh start
executor.spin_all(1s);
size_t t1_runs = 0;
auto t1 = node->create_wall_timer(
1ms,
[&]() {
t1_runs++;
std::this_thread::sleep_for(50ms);
});
size_t t2_runs = 0;
auto t2 = node->create_wall_timer(
1ms,
[&]() {
t2_runs++;
std::this_thread::sleep_for(50ms);
});
std::thread spinner([&executor]() {executor.spin();});
std::this_thread::sleep_for(10ms);
// Call cancel while t1 callback is still being executed
executor.cancel();
spinner.join();
// Depending on the latency on the system, t2 may start to execute before cancel is signaled
EXPECT_GE(1u, t1_runs);
EXPECT_GE(1u, t2_runs);
}
TEST_F(TestEventsExecutor, cancel_while_timers_waiting)
{
auto node = std::make_shared<rclcpp::Node>("node");
size_t t1_runs = 0;
auto t1 = node->create_wall_timer(
100s,
[&]() {
t1_runs++;
});
EventsExecutor executor;
executor.add_node(node);
auto start = std::chrono::steady_clock::now();
std::thread spinner([&executor]() {executor.spin();});
std::this_thread::sleep_for(10ms);
executor.cancel();
spinner.join();
EXPECT_EQ(0u, t1_runs);
EXPECT_TRUE(std::chrono::steady_clock::now() - start < 1s);
}
TEST_F(TestEventsExecutor, destroy_entities)
{
// This test fails on Windows! We skip it for now
GTEST_SKIP();
// Create a publisher node and start publishing messages
auto node_pub = std::make_shared<rclcpp::Node>("node_pub");
auto publisher = node_pub->create_publisher<test_msgs::msg::Empty>("topic", rclcpp::QoS(10));
auto timer = node_pub->create_wall_timer(
2ms, [&]() {publisher->publish(std::make_unique<test_msgs::msg::Empty>());});
EventsExecutor executor_pub;
executor_pub.add_node(node_pub);
std::thread spinner([&executor_pub]() {executor_pub.spin();});
// Create a node with two different subscriptions to the topic
auto node_sub = std::make_shared<rclcpp::Node>("node_sub");
size_t callback_count_1 = 0;
auto subscription_1 =
node_sub->create_subscription<test_msgs::msg::Empty>(
"topic", rclcpp::QoS(10), [&](test_msgs::msg::Empty::ConstSharedPtr) {callback_count_1++;});
size_t callback_count_2 = 0;
auto subscription_2 =
node_sub->create_subscription<test_msgs::msg::Empty>(
"topic", rclcpp::QoS(10), [&](test_msgs::msg::Empty::ConstSharedPtr) {callback_count_2++;});
EventsExecutor executor_sub;
executor_sub.add_node(node_sub);
// Wait some time while messages are published
std::this_thread::sleep_for(10ms);
// Destroy one of the two subscriptions
subscription_1.reset();
// Let subscriptions executor spin
executor_sub.spin_some(10ms);
// The callback count of the destroyed subscription remained at 0
EXPECT_EQ(0u, callback_count_1);
EXPECT_LT(0u, callback_count_2);
executor_pub.cancel();
spinner.join();
}
// Testing construction of a subscriptions with QoS event callback functions.
std::string * g_pub_log_msg;
std::string * g_sub_log_msg;
std::promise<void> * g_log_msgs_promise;
TEST_F(TestEventsExecutor, test_default_incompatible_qos_callbacks)
{
auto node = std::make_shared<rclcpp::Node>("node");
rcutils_logging_output_handler_t original_output_handler = rcutils_logging_get_output_handler();
std::string pub_log_msg;
std::string sub_log_msg;
std::promise<void> log_msgs_promise;
g_pub_log_msg = &pub_log_msg;
g_sub_log_msg = &sub_log_msg;
g_log_msgs_promise = &log_msgs_promise;
auto logger_callback = [](
const rcutils_log_location_t * /*location*/,
int /*level*/, const char * /*name*/, rcutils_time_point_value_t /*timestamp*/,
const char * format, va_list * args) -> void {
char buffer[1024];
vsnprintf(buffer, sizeof(buffer), format, *args);
const std::string msg = buffer;
if (msg.rfind("New subscription discovered on topic '/test_topic'", 0) == 0) {
*g_pub_log_msg = buffer;
} else if (msg.rfind("New publisher discovered on topic '/test_topic'", 0) == 0) {
*g_sub_log_msg = buffer;
}
if (!g_pub_log_msg->empty() && !g_sub_log_msg->empty()) {
g_log_msgs_promise->set_value();
}
};
rcutils_logging_set_output_handler(logger_callback);
std::shared_future<void> log_msgs_future = log_msgs_promise.get_future();
rclcpp::QoS qos_profile_publisher(10);
qos_profile_publisher.durability(RMW_QOS_POLICY_DURABILITY_VOLATILE);
auto publisher = node->create_publisher<test_msgs::msg::Empty>(
"test_topic", qos_profile_publisher);
rclcpp::QoS qos_profile_subscription(10);
qos_profile_subscription.durability(RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL);
auto subscription = node->create_subscription<test_msgs::msg::Empty>(
"test_topic", qos_profile_subscription, [&](test_msgs::msg::Empty::ConstSharedPtr) {});
EventsExecutor ex;
ex.add_node(node->get_node_base_interface());
const auto timeout = std::chrono::seconds(10);
ex.spin_until_future_complete(log_msgs_future, timeout);
rclcpp::QoSCheckCompatibleResult qos_compatible = rclcpp::qos_check_compatible(
publisher->get_actual_qos(), subscription->get_actual_qos());
if (qos_compatible.compatibility == rclcpp::QoSCompatibility::Error) {
EXPECT_EQ(
"New subscription discovered on topic '/test_topic', requesting incompatible QoS. "
"No messages will be sent to it. Last incompatible policy: DURABILITY_QOS_POLICY",
pub_log_msg);
EXPECT_EQ(
"New publisher discovered on topic '/test_topic', offering incompatible QoS. "
"No messages will be sent to it. Last incompatible policy: DURABILITY_QOS_POLICY",
sub_log_msg);
} else {
EXPECT_EQ("", pub_log_msg);
EXPECT_EQ("", sub_log_msg);
}
rcutils_logging_set_output_handler(original_output_handler);
}
class TestWaitableWithTimer : public rclcpp::Waitable
{
static constexpr int TimerCallbackType = 0;
public:
explicit TestWaitableWithTimer(const rclcpp::Context::SharedPtr & context)
{
auto timer_callback = [this] () {
timer_ready = true;
if (ready_callback) {
// inform executor that the waitable is ready to process a timer event
ready_callback(1, TimerCallbackType);
}
};
timer =
std::make_shared<rclcpp::WallTimer<decltype (timer_callback)>>(std::chrono::milliseconds(10),
std::move(timer_callback), context);
}
void
add_to_wait_set(rcl_wait_set_t & /*wait_set*/) override {}
bool
is_ready(const rcl_wait_set_t & /*wait_set*/) override
{
return false;
}
std::shared_ptr<void>
take_data() override
{
return std::shared_ptr<void>(nullptr);
}
std::shared_ptr<void>
take_data_by_entity_id(size_t id) override
{
if (id != TimerCallbackType) {
throw std::runtime_error("Internal error, got wrong ID for take data");
}
return nullptr;
}
void
execute(const std::shared_ptr<void> &) override
{
if (timer_ready) {
timer_triggered_waitable_and_waitable_was_executed = true;
}
}
void
set_on_ready_callback(std::function<void(size_t, int)> callback) override
{
ready_callback = callback;
}
void
clear_on_ready_callback() override
{
ready_callback = std::function<void(size_t, int)>();
}
size_t
get_number_of_ready_guard_conditions() override
{
return 0;
}
std::vector<std::shared_ptr<rclcpp::TimerBase>> get_timers() const override
{
return {timer};
}
bool timerTriggeredWaitable() const
{
return timer_triggered_waitable_and_waitable_was_executed;
}
private:
std::atomic_bool timer_triggered_waitable_and_waitable_was_executed = false;
std::atomic_bool timer_ready = false;
rclcpp::TimerBase::SharedPtr timer;
std::function<void(size_t, int)> ready_callback;
};
TEST_F(TestEventsExecutor, waitable_with_timer)
{
auto node = std::make_shared<rclcpp::Node>("node");
auto waitable =
std::make_shared<TestWaitableWithTimer>(rclcpp::contexts::get_global_default_context());
EventsExecutor executor;
executor.add_node(node);
node->get_node_waitables_interface()->add_waitable(waitable,
node->get_node_base_interface()->get_default_callback_group());
std::thread spinner([&executor]() {executor.spin();});
size_t cnt = 0;
while (!waitable->timerTriggeredWaitable()) {
std::this_thread::sleep_for(10ms);
cnt++;
// This should terminate after ~20 ms, so a timeout of 500ms should be plenty
EXPECT_LT(cnt, 51);
if (cnt > 50) {
// timeout case
break;
}
}
executor.cancel();
spinner.join();
EXPECT_TRUE(waitable->timerTriggeredWaitable());
}