|
2 | 2 |
|
3 | 3 | #include <gtest/gtest.h> |
4 | 4 |
|
| 5 | +#include <rclcpp/experimental/executors/events_executor/events_executor.hpp> |
| 6 | +#include <rclcpp/experimental/executors/events_executor/lock_free_events_queue.hpp> |
5 | 7 | #include <rclcpp/rclcpp.hpp> |
6 | 8 |
|
7 | | -#include "rclcpp/experimental/executors/events_executor/events_executor.hpp" |
8 | | -#include "rclcpp/experimental/executors/events_executor/lock_free_events_queue.hpp" |
| 9 | +#include <atomic> |
| 10 | +#include <chrono> |
| 11 | +#include <future> |
| 12 | +#include <thread> |
9 | 13 |
|
10 | 14 | using rclcpp::experimental::executors::EventsExecutor; |
11 | 15 |
|
| 16 | +static const size_t timeout_seconds{2}; |
| 17 | + |
12 | 18 | class TimersTest |
13 | 19 | : public testing::Test |
14 | 20 | { |
15 | 21 | public: |
16 | | - void SetUp() override |
17 | | - { |
18 | | - rclcpp::init(0, nullptr); |
19 | | - } |
| 22 | + void SetUp() override |
| 23 | + { |
| 24 | + rclcpp::init(0, nullptr); |
| 25 | + } |
| 26 | + |
| 27 | + void TearDown() override |
| 28 | + { |
| 29 | + rclcpp::shutdown(); |
| 30 | + } |
| 31 | + |
| 32 | + void run_timers_test( |
| 33 | + std::unique_ptr<EventsExecutor> &executor, |
| 34 | + std::shared_ptr<rclcpp::Node> &node, |
| 35 | + std::chrono::milliseconds timers_period, |
| 36 | + size_t &count_1, |
| 37 | + size_t &count_2, |
| 38 | + std::atomic<bool> &stop_signal) |
| 39 | + { |
| 40 | + auto timer_1 = rclcpp::create_timer( |
| 41 | + node, |
| 42 | + node->get_clock(), |
| 43 | + rclcpp::Duration(timers_period), |
| 44 | + [&count_1]() |
| 45 | + { |
| 46 | + count_1++; |
| 47 | + }); |
20 | 48 |
|
21 | | - void TearDown() override |
| 49 | + auto timer_2 = rclcpp::create_timer( |
| 50 | + node, |
| 51 | + node->get_clock(), |
| 52 | + rclcpp::Duration(timers_period), |
| 53 | + [&count_2]() |
| 54 | + { |
| 55 | + count_2++; |
| 56 | + }); |
| 57 | + |
| 58 | + std::thread executor_thread([&executor, &stop_signal]() |
22 | 59 | { |
23 | | - rclcpp::shutdown(); |
| 60 | + while (!stop_signal.load() && rclcpp::ok()) |
| 61 | + { |
| 62 | + executor->spin_all(std::chrono::milliseconds(10)); |
| 63 | + std::this_thread::sleep_for(std::chrono::milliseconds(1)); |
| 64 | + } |
| 65 | + }); |
| 66 | + |
| 67 | + while (count_2 < 10u && !stop_signal.load()) |
| 68 | + { |
| 69 | + std::this_thread::sleep_for(std::chrono::milliseconds(10)); |
24 | 70 | } |
| 71 | + |
| 72 | + stop_signal.store(true); |
| 73 | + executor->cancel(); |
| 74 | + executor_thread.join(); |
| 75 | + |
| 76 | + EXPECT_GE(count_2, 10u); |
| 77 | + EXPECT_LE(count_2 - count_1, 1u); |
| 78 | + } |
25 | 79 | }; |
26 | 80 |
|
27 | 81 | TEST_F(TimersTest, TimersWithSamePeriod) |
28 | 82 | { |
29 | | - auto timers_period = std::chrono::milliseconds(50); |
30 | | - auto node = std::make_shared<rclcpp::Node>("test_node"); |
31 | | - auto events_queue = std::make_unique<rclcpp::experimental::executors::LockFreeEventsQueue>(); |
32 | | - auto executor = std::make_unique<EventsExecutor>(std::move(events_queue), true, rclcpp::ExecutorOptions()); |
33 | | - |
34 | | - executor->add_node(node); |
35 | | - |
| 83 | + auto timers_period = std::chrono::milliseconds(5); |
| 84 | + auto node = std::make_shared<rclcpp::Node>("test_node"); |
| 85 | + auto events_queue = std::make_unique<rclcpp::experimental::executors::LockFreeEventsQueue>(); |
| 86 | + auto executor = std::make_unique<EventsExecutor>( |
| 87 | + std::move(events_queue), |
| 88 | + true, |
| 89 | + rclcpp::ExecutorOptions()); |
| 90 | + |
| 91 | + executor->add_node(node); |
| 92 | + |
| 93 | + std::promise<void> promise; |
| 94 | + std::future<void> future = promise.get_future(); |
| 95 | + std::atomic<bool> stop_signal(false); |
| 96 | + std::thread test_thread([this, &promise, &executor, &node, timers_period, &stop_signal]() |
| 97 | + { |
36 | 98 | size_t count_1 = 0; |
37 | | - auto timer_1 = rclcpp::create_timer( |
38 | | - node, |
39 | | - node->get_clock(), |
40 | | - rclcpp::Duration(timers_period), |
41 | | - [&count_1]() { |
42 | | - count_1++; |
43 | | - }); |
44 | | - |
45 | 99 | size_t count_2 = 0; |
46 | | - auto timer_2 = rclcpp::create_timer( |
47 | | - node, |
48 | | - node->get_clock(), |
49 | | - rclcpp::Duration(timers_period), |
50 | | - [&count_2]() { |
51 | | - count_2++; |
52 | | - }); |
53 | 100 |
|
54 | | - { |
55 | | - std::thread executor_thread([&executor](){ |
56 | | - executor->spin(); |
57 | | - }); |
58 | | - |
59 | | - while (count_2 < 10u) { |
60 | | - std::this_thread::sleep_for(std::chrono::milliseconds(10)); |
61 | | - } |
62 | | - executor->cancel(); |
63 | | - executor_thread.join(); |
64 | | - |
65 | | - EXPECT_GE(count_2, 10u); |
66 | | - EXPECT_LE(count_2 - count_1, 1u); |
67 | | - } |
| 101 | + run_timers_test(executor, node, timers_period, count_1, count_2, stop_signal); |
68 | 102 |
|
69 | 103 | count_1 = 0; |
70 | | - timer_1 = rclcpp::create_timer( |
71 | | - node, |
72 | | - node->get_clock(), |
73 | | - rclcpp::Duration(timers_period), |
74 | | - [&count_1]() { |
75 | | - count_1++; |
76 | | - }); |
77 | | - |
78 | 104 | count_2 = 0; |
79 | | - timer_2 = rclcpp::create_timer( |
80 | | - node, |
81 | | - node->get_clock(), |
82 | | - rclcpp::Duration(timers_period), |
83 | | - [&count_2]() { |
84 | | - count_2++; |
85 | | - }); |
86 | | - |
87 | | - { |
88 | | - std::thread executor_thread([&executor](){ |
89 | | - executor->spin(); |
90 | | - }); |
91 | | - |
92 | | - while (count_2 < 10u) { |
93 | | - std::this_thread::sleep_for(std::chrono::milliseconds(10)); |
94 | | - } |
95 | | - executor->cancel(); |
96 | | - executor_thread.join(); |
97 | | - |
98 | | - EXPECT_GE(count_2, 10u); |
99 | | - EXPECT_LE(count_2 - count_1, 1u); |
100 | | - } |
| 105 | + stop_signal.store(false); |
| 106 | + run_timers_test(executor, node, timers_period, count_1, count_2, stop_signal); |
| 107 | + |
| 108 | + promise.set_value(); |
| 109 | + }); |
| 110 | + |
| 111 | + if (future.wait_for(std::chrono::seconds(timeout_seconds)) == std::future_status::timeout) |
| 112 | + { |
| 113 | + stop_signal.store(true); |
| 114 | + executor->cancel(); |
| 115 | + test_thread.join(); |
| 116 | + FAIL() << "Test timed out"; |
| 117 | + } |
| 118 | + else |
| 119 | + { |
| 120 | + test_thread.join(); |
| 121 | + } |
101 | 122 | } |
102 | 123 |
|
103 | 124 | int main(int argc, char **argv) |
104 | 125 | { |
105 | | - ::testing::InitGoogleTest(&argc, argv); |
106 | | - return RUN_ALL_TESTS(); |
| 126 | + ::testing::InitGoogleTest(&argc, argv); |
| 127 | + return RUN_ALL_TESTS(); |
107 | 128 | } |
0 commit comments