/
test_executors.cpp
820 lines (691 loc) · 24.5 KB
/
test_executors.cpp
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
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
// Copyright 2017 Open Source Robotics Foundation, Inc.
//
// 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.
/**
* This test checks all implementations of rclcpp::executor to check they pass they basic API
* tests. Anything specific to any executor in particular should go in a separate test file.
*
*/
#include <gtest/gtest.h>
#include <algorithm>
#include <atomic>
#include <chrono>
#include <limits>
#include <memory>
#include <string>
#include <thread>
#include <utility>
#include <vector>
#include "rcl/error_handling.h"
#include "rcl/time.h"
#include "rclcpp/clock.hpp"
#include "rclcpp/detail/add_guard_condition_to_rcl_wait_set.hpp"
#include "rclcpp/duration.hpp"
#include "rclcpp/guard_condition.hpp"
#include "rclcpp/rclcpp.hpp"
#include "test_msgs/msg/empty.hpp"
using namespace std::chrono_literals;
template<typename T>
class TestExecutors : public ::testing::Test
{
public:
void SetUp()
{
rclcpp::init(0, nullptr);
const auto test_info = ::testing::UnitTest::GetInstance()->current_test_info();
std::stringstream test_name;
test_name << test_info->test_case_name() << "_" << test_info->name();
node = std::make_shared<rclcpp::Node>("node", test_name.str());
callback_count = 0;
const std::string topic_name = std::string("topic_") + test_name.str();
publisher = node->create_publisher<test_msgs::msg::Empty>(topic_name, rclcpp::QoS(10));
auto callback = [this](test_msgs::msg::Empty::ConstSharedPtr) {this->callback_count++;};
subscription =
node->create_subscription<test_msgs::msg::Empty>(
topic_name, rclcpp::QoS(10), std::move(callback));
}
void TearDown()
{
publisher.reset();
subscription.reset();
node.reset();
rclcpp::shutdown();
}
rclcpp::Node::SharedPtr node;
rclcpp::Publisher<test_msgs::msg::Empty>::SharedPtr publisher;
rclcpp::Subscription<test_msgs::msg::Empty>::SharedPtr subscription;
int callback_count;
};
// spin_all and spin_some are not implemented correctly in StaticSingleThreadedExecutor, see:
// https://github.com/ros2/rclcpp/issues/1219 for tracking
template<typename T>
class TestExecutorsStable : public TestExecutors<T> {};
using ExecutorTypes =
::testing::Types<
rclcpp::executors::SingleThreadedExecutor,
rclcpp::executors::MultiThreadedExecutor,
rclcpp::executors::StaticSingleThreadedExecutor,
rclcpp::experimental::executors::EventsExecutor>;
class ExecutorTypeNames
{
public:
template<typename T>
static std::string GetName(int idx)
{
(void)idx;
if (std::is_same<T, rclcpp::executors::SingleThreadedExecutor>()) {
return "SingleThreadedExecutor";
}
if (std::is_same<T, rclcpp::executors::MultiThreadedExecutor>()) {
return "MultiThreadedExecutor";
}
if (std::is_same<T, rclcpp::executors::StaticSingleThreadedExecutor>()) {
return "StaticSingleThreadedExecutor";
}
if (std::is_same<T, rclcpp::experimental::executors::EventsExecutor>()) {
return "EventsExecutor";
}
return "";
}
};
// TYPED_TEST_SUITE is deprecated as of gtest 1.9, use TYPED_TEST_SUITE when gtest dependency
// is updated.
TYPED_TEST_SUITE(TestExecutors, ExecutorTypes, ExecutorTypeNames);
// StaticSingleThreadedExecutor is not included in these tests for now, due to:
// https://github.com/ros2/rclcpp/issues/1219
using StandardExecutors =
::testing::Types<
rclcpp::executors::SingleThreadedExecutor,
rclcpp::executors::MultiThreadedExecutor,
rclcpp::experimental::executors::EventsExecutor>;
TYPED_TEST_SUITE(TestExecutorsStable, StandardExecutors, ExecutorTypeNames);
// Make sure that executors detach from nodes when destructing
TYPED_TEST(TestExecutors, detachOnDestruction)
{
using ExecutorType = TypeParam;
{
ExecutorType executor;
executor.add_node(this->node);
}
{
ExecutorType executor;
EXPECT_NO_THROW(executor.add_node(this->node));
}
}
// Make sure that the executor can automatically remove expired nodes correctly
// Currently fails for StaticSingleThreadedExecutor so it is being skipped, see:
// https://github.com/ros2/rclcpp/issues/1231
TYPED_TEST(TestExecutorsStable, addTemporaryNode)
{
using ExecutorType = TypeParam;
ExecutorType executor;
{
// Let node go out of scope before executor.spin()
auto node = std::make_shared<rclcpp::Node>("temporary_node");
executor.add_node(node);
}
// Sleep for a short time to verify executor.spin() is going, and didn't throw.
std::thread spinner([&]() {EXPECT_NO_THROW(executor.spin());});
std::this_thread::sleep_for(50ms);
executor.cancel();
spinner.join();
}
// Make sure that a spinning empty executor can be cancelled
TYPED_TEST(TestExecutors, emptyExecutor)
{
using ExecutorType = TypeParam;
ExecutorType executor;
std::thread spinner([&]() {EXPECT_NO_THROW(executor.spin());});
std::this_thread::sleep_for(50ms);
executor.cancel();
spinner.join();
}
// Check executor throws properly if the same node is added a second time
TYPED_TEST(TestExecutors, addNodeTwoExecutors)
{
using ExecutorType = TypeParam;
ExecutorType executor1;
ExecutorType executor2;
EXPECT_NO_THROW(executor1.add_node(this->node));
EXPECT_THROW(executor2.add_node(this->node), std::runtime_error);
executor1.remove_node(this->node, true);
}
// Check simple spin example
TYPED_TEST(TestExecutors, spinWithTimer)
{
using ExecutorType = TypeParam;
ExecutorType executor;
bool timer_completed = false;
auto timer = this->node->create_wall_timer(1ms, [&]() {timer_completed = true;});
executor.add_node(this->node);
std::thread spinner([&]() {executor.spin();});
auto start = std::chrono::steady_clock::now();
while (!timer_completed && (std::chrono::steady_clock::now() - start) < 10s) {
std::this_thread::sleep_for(1ms);
}
EXPECT_TRUE(timer_completed);
// Cancel needs to be called before join, so that executor.spin() returns.
executor.cancel();
spinner.join();
executor.remove_node(this->node, true);
}
TYPED_TEST(TestExecutors, spinWhileAlreadySpinning)
{
using ExecutorType = TypeParam;
ExecutorType executor;
executor.add_node(this->node);
bool timer_completed = false;
auto timer = this->node->create_wall_timer(1ms, [&]() {timer_completed = true;});
std::thread spinner([&]() {executor.spin();});
// Sleep for a short time to verify executor.spin() is going, and didn't throw.
auto start = std::chrono::steady_clock::now();
while (!timer_completed && (std::chrono::steady_clock::now() - start) < 10s) {
std::this_thread::sleep_for(1ms);
}
EXPECT_TRUE(timer_completed);
EXPECT_THROW(executor.spin(), std::runtime_error);
// Shutdown needs to be called before join, so that executor.spin() returns.
executor.cancel();
spinner.join();
executor.remove_node(this->node, true);
}
// Check executor exits immediately if future is complete.
TYPED_TEST(TestExecutors, testSpinUntilFutureComplete)
{
using ExecutorType = TypeParam;
ExecutorType executor;
executor.add_node(this->node);
// test success of an immediately finishing future
std::promise<bool> promise;
std::future<bool> future = promise.get_future();
promise.set_value(true);
// spin_until_future_complete is expected to exit immediately, but would block up until its
// timeout if the future is not checked before spin_once_impl.
auto start = std::chrono::steady_clock::now();
auto shared_future = future.share();
auto ret = executor.spin_until_future_complete(shared_future, 1s);
executor.remove_node(this->node, true);
// Check it didn't reach timeout
EXPECT_GT(500ms, (std::chrono::steady_clock::now() - start));
EXPECT_EQ(rclcpp::FutureReturnCode::SUCCESS, ret);
}
// Same test, but uses a shared future.
TYPED_TEST(TestExecutors, testSpinUntilSharedFutureComplete)
{
using ExecutorType = TypeParam;
ExecutorType executor;
executor.add_node(this->node);
// test success of an immediately finishing future
std::promise<bool> promise;
std::future<bool> future = promise.get_future();
promise.set_value(true);
// spin_until_future_complete is expected to exit immediately, but would block up until its
// timeout if the future is not checked before spin_once_impl.
auto shared_future = future.share();
auto start = std::chrono::steady_clock::now();
auto ret = executor.spin_until_future_complete(shared_future, 1s);
executor.remove_node(this->node, true);
// Check it didn't reach timeout
EXPECT_GT(500ms, (std::chrono::steady_clock::now() - start));
EXPECT_EQ(rclcpp::FutureReturnCode::SUCCESS, ret);
}
// For a longer running future that should require several iterations of spin_once
TYPED_TEST(TestExecutors, testSpinUntilFutureCompleteNoTimeout)
{
using ExecutorType = TypeParam;
ExecutorType executor;
executor.add_node(this->node);
// This future doesn't immediately terminate, so some work gets performed.
std::future<void> future = std::async(
std::launch::async,
[this]() {
auto start = std::chrono::steady_clock::now();
while (this->callback_count < 1 && (std::chrono::steady_clock::now() - start) < 1s) {
std::this_thread::sleep_for(1ms);
}
});
bool spin_exited = false;
// Timeout set to negative for no timeout.
std::thread spinner([&]() {
auto ret = executor.spin_until_future_complete(future, -1s);
EXPECT_EQ(rclcpp::FutureReturnCode::SUCCESS, ret);
executor.remove_node(this->node, true);
executor.cancel();
spin_exited = true;
});
// Do some work for longer than the future needs.
for (int i = 0; i < 100; ++i) {
this->publisher->publish(test_msgs::msg::Empty());
std::this_thread::sleep_for(1ms);
if (spin_exited) {
break;
}
}
// Not testing accuracy, just want to make sure that some work occurred.
EXPECT_LT(0, this->callback_count);
// If this fails, the test will probably crash because spinner goes out of scope while the thread
// is active. However, it beats letting this run until the gtest timeout.
ASSERT_TRUE(spin_exited);
executor.cancel();
spinner.join();
}
// Check spin_until_future_complete timeout works as expected
TYPED_TEST(TestExecutors, testSpinUntilFutureCompleteWithTimeout)
{
using ExecutorType = TypeParam;
ExecutorType executor;
executor.add_node(this->node);
bool spin_exited = false;
// Needs to run longer than spin_until_future_complete's timeout.
std::future<void> future = std::async(
std::launch::async,
[&spin_exited]() {
auto start = std::chrono::steady_clock::now();
while (!spin_exited && (std::chrono::steady_clock::now() - start) < 1s) {
std::this_thread::sleep_for(1ms);
}
});
// Short timeout
std::thread spinner([&]() {
auto ret = executor.spin_until_future_complete(future, 1ms);
EXPECT_EQ(rclcpp::FutureReturnCode::TIMEOUT, ret);
executor.remove_node(this->node, true);
spin_exited = true;
});
// Do some work for longer than timeout needs.
for (int i = 0; i < 100; ++i) {
this->publisher->publish(test_msgs::msg::Empty());
std::this_thread::sleep_for(1ms);
if (spin_exited) {
break;
}
}
EXPECT_TRUE(spin_exited);
spinner.join();
}
class TestWaitable : public rclcpp::Waitable
{
public:
TestWaitable() = default;
void
add_to_wait_set(rcl_wait_set_t * wait_set) override
{
rclcpp::detail::add_guard_condition_to_rcl_wait_set(*wait_set, gc_);
}
void trigger()
{
gc_.trigger();
}
bool
is_ready(rcl_wait_set_t * wait_set) override
{
(void)wait_set;
return true;
}
std::shared_ptr<void>
take_data() override
{
return nullptr;
}
std::shared_ptr<void>
take_data_by_entity_id(size_t id) override
{
(void) id;
return nullptr;
}
void
execute(std::shared_ptr<void> & data) override
{
(void) data;
count_++;
std::this_thread::sleep_for(3ms);
}
void
set_on_ready_callback(std::function<void(size_t, int)> callback) override
{
auto gc_callback = [callback](size_t count) {
callback(count, 0);
};
gc_.set_on_trigger_callback(gc_callback);
}
void
clear_on_ready_callback() override
{
gc_.set_on_trigger_callback(nullptr);
}
size_t
get_number_of_ready_guard_conditions() override {return 1;}
size_t
get_count()
{
return count_;
}
private:
size_t count_ = 0;
rclcpp::GuardCondition gc_;
};
TYPED_TEST(TestExecutors, spinAll)
{
using ExecutorType = TypeParam;
ExecutorType executor;
auto waitable_interfaces = this->node->get_node_waitables_interface();
auto my_waitable = std::make_shared<TestWaitable>();
waitable_interfaces->add_waitable(my_waitable, nullptr);
executor.add_node(this->node);
// Long timeout, but should not block test if spin_all works as expected as we cancel the
// executor.
bool spin_exited = false;
std::thread spinner([&spin_exited, &executor, this]() {
executor.spin_all(1s);
executor.remove_node(this->node, true);
spin_exited = true;
});
// Do some work until sufficient calls to the waitable occur
auto start = std::chrono::steady_clock::now();
while (
my_waitable->get_count() <= 1 &&
!spin_exited &&
(std::chrono::steady_clock::now() - start < 1s))
{
my_waitable->trigger();
this->publisher->publish(test_msgs::msg::Empty());
std::this_thread::sleep_for(1ms);
}
executor.cancel();
start = std::chrono::steady_clock::now();
while (!spin_exited && (std::chrono::steady_clock::now() - start) < 1s) {
std::this_thread::sleep_for(1ms);
}
EXPECT_LT(1u, my_waitable->get_count());
waitable_interfaces->remove_waitable(my_waitable, nullptr);
ASSERT_TRUE(spin_exited);
spinner.join();
}
TYPED_TEST(TestExecutors, spinSome)
{
using ExecutorType = TypeParam;
ExecutorType executor;
auto waitable_interfaces = this->node->get_node_waitables_interface();
auto my_waitable = std::make_shared<TestWaitable>();
waitable_interfaces->add_waitable(my_waitable, nullptr);
executor.add_node(this->node);
// Long timeout, doesn't block test from finishing because spin_some should exit after the
// first one completes.
bool spin_exited = false;
std::thread spinner([&spin_exited, &executor, this]() {
executor.spin_some(1s);
executor.remove_node(this->node, true);
spin_exited = true;
});
// Do some work until sufficient calls to the waitable occur, but keep going until either
// count becomes too large, spin exits, or the 1 second timeout completes.
auto start = std::chrono::steady_clock::now();
while (
my_waitable->get_count() <= 1 &&
!spin_exited &&
(std::chrono::steady_clock::now() - start < 1s))
{
my_waitable->trigger();
this->publisher->publish(test_msgs::msg::Empty());
std::this_thread::sleep_for(1ms);
}
// The count of "execute" depends on whether the executor starts spinning before (1) or after (0)
// the first iteration of the while loop
EXPECT_LE(1u, my_waitable->get_count());
waitable_interfaces->remove_waitable(my_waitable, nullptr);
EXPECT_TRUE(spin_exited);
// Cancel if it hasn't exited already.
executor.cancel();
spinner.join();
}
// Check spin_node_until_future_complete with node base pointer
TYPED_TEST(TestExecutors, testSpinNodeUntilFutureCompleteNodeBasePtr)
{
using ExecutorType = TypeParam;
ExecutorType executor;
std::promise<bool> promise;
std::future<bool> future = promise.get_future();
promise.set_value(true);
auto shared_future = future.share();
auto ret = rclcpp::executors::spin_node_until_future_complete(
executor, this->node->get_node_base_interface(), shared_future, 1s);
EXPECT_EQ(rclcpp::FutureReturnCode::SUCCESS, ret);
}
// Check spin_node_until_future_complete with node pointer
TYPED_TEST(TestExecutors, testSpinNodeUntilFutureCompleteNodePtr)
{
using ExecutorType = TypeParam;
ExecutorType executor;
std::promise<bool> promise;
std::future<bool> future = promise.get_future();
promise.set_value(true);
auto shared_future = future.share();
auto ret = rclcpp::executors::spin_node_until_future_complete(
executor, this->node, shared_future, 1s);
EXPECT_EQ(rclcpp::FutureReturnCode::SUCCESS, ret);
}
// Check spin_until_future_complete can be properly interrupted.
TYPED_TEST(TestExecutors, testSpinUntilFutureCompleteInterrupted)
{
using ExecutorType = TypeParam;
ExecutorType executor;
executor.add_node(this->node);
bool spin_exited = false;
// This needs to block longer than it takes to get to the shutdown call below and for
// spin_until_future_complete to return
std::future<void> future = std::async(
std::launch::async,
[&spin_exited]() {
auto start = std::chrono::steady_clock::now();
while (!spin_exited && (std::chrono::steady_clock::now() - start) < 1s) {
std::this_thread::sleep_for(1ms);
}
});
// Long timeout
std::thread spinner([&spin_exited, &executor, &future]() {
auto ret = executor.spin_until_future_complete(future, 1s);
EXPECT_EQ(rclcpp::FutureReturnCode::INTERRUPTED, ret);
spin_exited = true;
});
// Do some minimal work
this->publisher->publish(test_msgs::msg::Empty());
std::this_thread::sleep_for(1ms);
// Force interruption
rclcpp::shutdown();
// Give it time to exit
auto start = std::chrono::steady_clock::now();
while (!spin_exited && (std::chrono::steady_clock::now() - start) < 1s) {
std::this_thread::sleep_for(1ms);
}
EXPECT_TRUE(spin_exited);
spinner.join();
}
// This test verifies that the add_node operation is robust wrt race conditions.
// It's mostly meant to prevent regressions in the events-executor, but the operation should be
// thread-safe in all executor implementations.
// The initial implementation of the events-executor contained a bug where the executor
// would end up in an inconsistent state and stop processing interrupt/shutdown notifications.
// Manually adding a node to the executor results in a) producing a notify waitable event
// and b) refreshing the executor collections.
// The inconsistent state would happen if the event was processed before the collections were
// finished to be refreshed: the executor would pick up the event but be unable to process it.
// This would leave the `notify_waitable_event_pushed_` flag to true, preventing additional
// notify waitable events to be pushed.
// The behavior is observable only under heavy load, so this test spawns several worker
// threads. Due to the nature of the bug, this test may still succeed even if the
// bug is present. However repeated runs will show its flakiness nature and indicate
// an eventual regression.
TYPED_TEST(TestExecutors, testRaceConditionAddNode)
{
using ExecutorType = TypeParam;
// rmw_connextdds doesn't support events-executor
if (
std::is_same<ExecutorType, rclcpp::experimental::executors::EventsExecutor>() &&
std::string(rmw_get_implementation_identifier()).find("rmw_connextdds") == 0)
{
GTEST_SKIP();
}
// Spawn some threads to do some heavy work
std::atomic<bool> should_cancel = false;
std::vector<std::thread> stress_threads;
for (size_t i = 0; i < 5 * std::thread::hardware_concurrency(); i++) {
stress_threads.emplace_back(
[&should_cancel, i]() {
// This is just some arbitrary heavy work
volatile size_t total = 0;
for (size_t k = 0; k < 549528914167; k++) {
if (should_cancel) {
break;
}
total += k * (i + 42);
(void)total;
}
});
}
// Create an executor
auto executor = std::make_shared<ExecutorType>();
// Start spinning
auto executor_thread = std::thread(
[executor]() {
executor->spin();
});
// Add a node to the executor
executor->add_node(this->node);
// Cancel the executor (make sure that it's already spinning first)
while (!executor->is_spinning() && rclcpp::ok()) {
continue;
}
executor->cancel();
// Try to join the thread after cancelling the executor
// This is the "test". We want to make sure that we can still cancel the executor
// regardless of the presence of race conditions
executor_thread.join();
// The test is now completed: we can join the stress threads
should_cancel = true;
for (auto & t : stress_threads) {
t.join();
}
}
// Check spin_until_future_complete with node base pointer (instantiates its own executor)
TEST(TestExecutors, testSpinUntilFutureCompleteNodeBasePtr)
{
rclcpp::init(0, nullptr);
{
auto node = std::make_shared<rclcpp::Node>("node");
std::promise<bool> promise;
std::future<bool> future = promise.get_future();
promise.set_value(true);
auto shared_future = future.share();
auto ret = rclcpp::spin_until_future_complete(
node->get_node_base_interface(), shared_future, 1s);
EXPECT_EQ(rclcpp::FutureReturnCode::SUCCESS, ret);
}
rclcpp::shutdown();
}
// Check spin_until_future_complete with node pointer (instantiates its own executor)
TEST(TestExecutors, testSpinUntilFutureCompleteNodePtr)
{
rclcpp::init(0, nullptr);
{
auto node = std::make_shared<rclcpp::Node>("node");
std::promise<bool> promise;
std::future<bool> future = promise.get_future();
promise.set_value(true);
auto shared_future = future.share();
auto ret = rclcpp::spin_until_future_complete(node, shared_future, 1s);
EXPECT_EQ(rclcpp::FutureReturnCode::SUCCESS, ret);
}
rclcpp::shutdown();
}
template<typename T>
class TestIntraprocessExecutors : public ::testing::Test
{
public:
static void SetUpTestCase()
{
rclcpp::init(0, nullptr);
}
static void TearDownTestCase()
{
rclcpp::shutdown();
}
void SetUp()
{
const auto test_info = ::testing::UnitTest::GetInstance()->current_test_info();
std::stringstream test_name;
test_name << test_info->test_case_name() << "_" << test_info->name();
node = std::make_shared<rclcpp::Node>("node", test_name.str());
callback_count = 0u;
const std::string topic_name = std::string("topic_") + test_name.str();
rclcpp::PublisherOptions po;
po.use_intra_process_comm = rclcpp::IntraProcessSetting::Enable;
publisher = node->create_publisher<test_msgs::msg::Empty>(topic_name, rclcpp::QoS(1), po);
auto callback = [this](test_msgs::msg::Empty::ConstSharedPtr) {
this->callback_count.fetch_add(1u);
};
rclcpp::SubscriptionOptions so;
so.use_intra_process_comm = rclcpp::IntraProcessSetting::Enable;
subscription =
node->create_subscription<test_msgs::msg::Empty>(
topic_name, rclcpp::QoS(kNumMessages), std::move(callback), so);
}
void TearDown()
{
publisher.reset();
subscription.reset();
node.reset();
}
const size_t kNumMessages = 100;
rclcpp::Node::SharedPtr node;
rclcpp::Publisher<test_msgs::msg::Empty>::SharedPtr publisher;
rclcpp::Subscription<test_msgs::msg::Empty>::SharedPtr subscription;
std::atomic_size_t callback_count;
};
TYPED_TEST_SUITE(TestIntraprocessExecutors, ExecutorTypes, ExecutorTypeNames);
TYPED_TEST(TestIntraprocessExecutors, testIntraprocessRetrigger) {
// This tests that executors will continue to service intraprocess subscriptions in the case
// that publishers aren't continuing to publish.
// This was previously broken in that intraprocess guard conditions were only triggered on
// publish and the test was added to prevent future regressions.
static constexpr size_t kNumMessages = 100;
using ExecutorType = TypeParam;
ExecutorType executor;
executor.add_node(this->node);
EXPECT_EQ(0u, this->callback_count.load());
this->publisher->publish(test_msgs::msg::Empty());
// Wait for up to 5 seconds for the first message to come available.
const std::chrono::milliseconds sleep_per_loop(10);
int loops = 0;
while (1u != this->callback_count.load() && loops < 500) {
rclcpp::sleep_for(sleep_per_loop);
executor.spin_some();
loops++;
}
EXPECT_EQ(1u, this->callback_count.load());
// reset counter
this->callback_count.store(0u);
for (size_t ii = 0; ii < kNumMessages; ++ii) {
this->publisher->publish(test_msgs::msg::Empty());
}
// Fire a timer every 10ms up to 5 seconds waiting for subscriptions to be read.
loops = 0;
auto timer = this->node->create_wall_timer(
std::chrono::milliseconds(10), [this, &executor, &loops]() {
loops++;
if (kNumMessages == this->callback_count.load() || loops == 500) {
executor.cancel();
}
});
executor.spin();
EXPECT_EQ(kNumMessages, this->callback_count.load());
}