-
Notifications
You must be signed in to change notification settings - Fork 53
Expand file tree
/
Copy pathtest_executor.cpp
More file actions
274 lines (240 loc) · 8.02 KB
/
test_executor.cpp
File metadata and controls
274 lines (240 loc) · 8.02 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
// Copyright 2015 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.
#include <atomic>
#include <chrono>
#include <cinttypes>
#include <future>
#include <memory>
#include <stdexcept>
#include <string>
#include <vector>
#include "gtest/gtest.h"
#include "rclcpp/exceptions.hpp"
#include "rclcpp/rclcpp.hpp"
#include "test_rclcpp/utils.hpp"
#include "test_rclcpp/msg/u_int32.hpp"
#include "test_rclcpp/srv/add_two_ints.hpp"
using namespace std::chrono_literals;
class test_executor : public ::testing::Test
{
public:
static void SetUpTestCase()
{
rclcpp::init(0, nullptr);
}
static void TearDownTestCase()
{
rclcpp::shutdown();
}
};
TEST_F(test_executor, recursive_spin_call)
{
rclcpp::executors::SingleThreadedExecutor executor;
auto node = rclcpp::Node::make_shared("recursive_spin_call");
auto timer = node->create_wall_timer(
0s,
[&executor]() {
ASSERT_THROW(executor.spin_some(), std::runtime_error);
ASSERT_THROW(executor.spin_once(), std::runtime_error);
ASSERT_THROW(executor.spin(), std::runtime_error);
executor.cancel();
});
executor.add_node(node);
executor.spin();
}
TEST_F(test_executor, spin_some_max_duration)
{
rclcpp::executors::SingleThreadedExecutor executor;
auto node = rclcpp::Node::make_shared("spin_some_max_duration");
auto lambda = []() {
std::this_thread::sleep_for(100ms);
};
std::vector<std::shared_ptr<rclcpp::WallTimer<decltype(lambda)>>> timers;
// creating 20 timers which will try to do 100 ms of work each
// only about 1s worth of them should actually be performed
for (int i = 0; i < 20; i++) {
auto timer = node->create_wall_timer(0s, lambda);
timers.push_back(timer);
}
executor.add_node(node);
const auto max_duration = 1s;
const auto start = std::chrono::steady_clock::now();
executor.spin_some(max_duration);
const auto end = std::chrono::steady_clock::now();
ASSERT_LT(max_duration, end - start);
ASSERT_GT(max_duration + 500ms, end - start);
}
TEST_F(test_executor, multithreaded_spin_call)
{
rclcpp::executors::SingleThreadedExecutor executor;
auto node = rclcpp::Node::make_shared("multithreaded_spin_call");
std::mutex m;
bool ready = false;
std::condition_variable cv;
std::thread t(
[&executor, &m, &cv, &ready]() {
std::unique_lock<std::mutex> lock(m);
cv.wait(lock, [&ready] {return ready;});
ASSERT_THROW(executor.spin_some(), std::runtime_error);
ASSERT_THROW(executor.spin_once(), std::runtime_error);
ASSERT_THROW(executor.spin(), std::runtime_error);
executor.cancel();
});
auto timer = node->create_wall_timer(
0s,
[&m, &cv, &ready]() {
if (!ready) {
{
std::lock_guard<std::mutex> lock(m);
ready = true;
}
cv.notify_one();
}
});
executor.add_node(node);
executor.spin();
t.join();
}
// Try spinning 2 single-threaded executors in two separate threads.
TEST_F(test_executor, multiple_executors)
{
std::atomic_uint counter1;
counter1 = 0;
std::atomic_uint counter2;
counter2 = 0;
const uint32_t counter_goal = 20;
// Initialize executor 1.
rclcpp::executors::SingleThreadedExecutor executor1;
// I'm not a huge fan of unspecified capture variables in a lambda, but it
// is necessary in this case. On MacOS High Sierra and later, clang
// complains if we try to pass "counter_goal" as a specific lambda capture
// since it is a const. On the other hand, MSVC 2017 (19.12.25834.0)
// complains if you do *not* have the capture. To let both compilers be
// happy, we just let the compiler figure out the captures it wants; this
// is doubly OK because this is just for a test.
auto callback1 = [&]() {
if (counter1 == counter_goal) {
executor1.cancel();
return;
}
++counter1;
};
auto node1 = rclcpp::Node::make_shared("multiple_executors_1");
auto timer1 = node1->create_wall_timer(1ms, callback1);
executor1.add_node(node1);
// Initialize executor 2.
rclcpp::executors::SingleThreadedExecutor executor2;
// This lambda has the same problem & solution as the callback1 lambda above.
auto callback2 = [&]() {
if (counter2 == counter_goal) {
executor2.cancel();
return;
}
++counter2;
};
auto node2 = rclcpp::Node::make_shared("multiple_executors_2");
auto timer2 = node2->create_wall_timer(1ms, callback2);
executor2.add_node(node2);
auto spin_executor2 = [&executor2]() {
executor2.spin();
};
// Launch both executors
std::thread execution_thread(spin_executor2);
executor1.spin();
execution_thread.join();
EXPECT_EQ(counter1.load(), counter_goal);
EXPECT_EQ(counter2.load(), counter_goal);
// Try to add node1 to executor2. It should throw, since node1 was already added to executor1.
ASSERT_THROW(executor2.add_node(node1), std::runtime_error);
}
// Check that the executor is notified when a node adds a new timer, publisher, subscription,
// service or client.
TEST_F(test_executor, notify)
{
rclcpp::executors::SingleThreadedExecutor executor;
auto executor_spin_lambda = [&executor]() {
executor.spin();
};
auto node = rclcpp::Node::make_shared("test_executor_notify");
executor.add_node(node);
{
std::thread spin_thread(executor_spin_lambda);
std::promise<void> timer_promise;
std::shared_future<void> timer_future(timer_promise.get_future());
auto timer = node->create_wall_timer(
1ms,
[&timer_promise](rclcpp::TimerBase & timer)
{
timer_promise.set_value();
timer.cancel();
});
EXPECT_EQ(std::future_status::ready, timer_future.wait_for(50ms));
executor.cancel();
spin_thread.join();
}
{
std::thread spin_thread(executor_spin_lambda);
bool subscription_triggered = false;
auto sub_callback =
[&executor, &subscription_triggered](test_rclcpp::msg::UInt32::ConstSharedPtr msg) -> void
{
subscription_triggered = true;
EXPECT_EQ(msg->data, 42u);
executor.cancel();
};
auto subscription = node->create_subscription<test_rclcpp::msg::UInt32>(
"test_executor_notify_subscription",
10,
sub_callback);
test_rclcpp::wait_for_subscriber(node, "test_executor_notify_subscription");
auto publisher = node->create_publisher<test_rclcpp::msg::UInt32>(
"test_executor_notify_subscription", 10);
auto timer = node->create_wall_timer(
1ms,
[&publisher]()
{
test_rclcpp::msg::UInt32 pub_msg;
pub_msg.data = 42;
publisher->publish(pub_msg);
});
spin_thread.join();
EXPECT_TRUE(subscription_triggered);
}
{
std::thread spin_thread(executor_spin_lambda);
auto service = node->create_service<test_rclcpp::srv::AddTwoInts>(
"test_executor_notify_service",
[](
test_rclcpp::srv::AddTwoInts::Request::SharedPtr request,
test_rclcpp::srv::AddTwoInts::Response::SharedPtr response)
{
response->sum = request->a + request->b;
});
auto client = node->create_client<test_rclcpp::srv::AddTwoInts>(
"test_executor_notify_service"
);
if (!client->wait_for_service(20s)) {
ASSERT_TRUE(false) << "service not available after waiting";
}
auto request = std::make_shared<test_rclcpp::srv::AddTwoInts::Request>();
request->a = 4;
request->b = 2;
auto future_result = client->async_send_request(request);
EXPECT_EQ(future_result.get()->sum, 6);
executor.cancel();
spin_thread.join();
}
}
// test removing a node
// test notify with multiple nodes