forked from ros-navigation/navigation2
-
Notifications
You must be signed in to change notification settings - Fork 1
/
test_actions.cpp
552 lines (447 loc) · 15.4 KB
/
test_actions.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
// Copyright (c) 2019 Intel 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 <chrono>
#include <memory>
#include <thread>
#include "gtest/gtest.h"
#include "nav2_util/node_utils.hpp"
#include "nav2_util/simple_action_server.hpp"
#include "test_msgs/action/fibonacci.hpp"
#include "std_msgs/msg/empty.hpp"
using Fibonacci = test_msgs::action::Fibonacci;
using GoalHandle = rclcpp_action::ServerGoalHandle<Fibonacci>;
using std::placeholders::_1;
using namespace std::chrono_literals;
class FibonacciServerNode : public rclcpp::Node
{
public:
FibonacciServerNode()
: rclcpp::Node("fibonacci_server_node")
{
}
~FibonacciServerNode()
{
}
void on_init()
{
action_server_ = std::make_shared<nav2_util::SimpleActionServer<Fibonacci>>(
shared_from_this(),
"fibonacci",
std::bind(&FibonacciServerNode::execute, this));
deactivate_subs_ = create_subscription<std_msgs::msg::Empty>(
"deactivate_server",
1,
[this](std_msgs::msg::Empty::UniquePtr /*msg*/) {
RCLCPP_INFO(this->get_logger(), "Deactivating");
action_server_->deactivate();
});
activate_subs_ = create_subscription<std_msgs::msg::Empty>(
"activate_server",
1,
[this](std_msgs::msg::Empty::UniquePtr /*msg*/) {
RCLCPP_INFO(this->get_logger(), "Activating");
action_server_->activate();
});
omit_preempt_subs_ = create_subscription<std_msgs::msg::Empty>(
"omit_preemption",
1,
[this](std_msgs::msg::Empty::UniquePtr /*msg*/) {
RCLCPP_INFO(this->get_logger(), "Ignoring preemptions");
do_premptions_ = false;
});
}
void on_term()
{
// when nothing's running make sure everything's dead.
// const std::shared_ptr<const Fibonacci::Goal> a = action_server_->accept_pending_goal();
// const std::shared_ptr<const Fibonacci::Goal> b = action_server_->get_current_goal();
// assert(a == b);
// assert(action_server_->is_cancel_requested() == false);
// auto feedback = std::make_shared<Fibonacci::Feedback>();
// action_server_->publish_feedback(feedback);
action_server_.reset();
}
void execute()
{
rclcpp::Rate loop_rate(10);
preempted:
// Initialize the goal, feedback, and result
auto goal = action_server_->get_current_goal();
auto feedback = std::make_shared<Fibonacci::Feedback>();
auto result = std::make_shared<Fibonacci::Result>();
// Fibonacci-specific initialization
auto & sequence = feedback->sequence;
sequence.push_back(0);
sequence.push_back(1);
for (int i = 1; (i < goal->order) && rclcpp::ok(); ++i) {
// Should be check periodically if this action has been canceled
// or if the server has been deactivated.
if (action_server_->is_cancel_requested() || !action_server_->is_server_active()) {
result->sequence = sequence;
return;
}
// Check if we've gotten an new goal, pre-empting the current one
if (do_premptions_ && action_server_->is_preempt_requested()) {
action_server_->accept_pending_goal();
goto preempted;
}
// Update the sequence
sequence.push_back(sequence[i] + sequence[i - 1]);
// Publish feedback
action_server_->publish_feedback(feedback);
loop_rate.sleep();
}
// Check if goal is done
if (rclcpp::ok()) {
result->sequence = sequence;
action_server_->succeeded_current(result);
}
}
private:
std::shared_ptr<nav2_util::SimpleActionServer<Fibonacci>> action_server_;
rclcpp::Subscription<std_msgs::msg::Empty>::SharedPtr deactivate_subs_;
rclcpp::Subscription<std_msgs::msg::Empty>::SharedPtr activate_subs_;
rclcpp::Subscription<std_msgs::msg::Empty>::SharedPtr omit_preempt_subs_;
bool do_premptions_{true};
};
class RclCppFixture
{
public:
RclCppFixture()
{
}
void Setup()
{
server_thread_ =
std::make_shared<std::thread>(std::bind(&RclCppFixture::server_thread_func, this));
}
~RclCppFixture()
{
server_thread_->join();
}
void server_thread_func()
{
auto node = std::make_shared<FibonacciServerNode>();
node->on_init();
rclcpp::spin(node->get_node_base_interface());
node->on_term();
node.reset();
}
std::shared_ptr<std::thread> server_thread_;
};
RclCppFixture g_rclcppfixture;
class ActionTestNode : public rclcpp::Node
{
public:
ActionTestNode()
: rclcpp::Node(nav2_util::generate_internal_node_name("action_test_node"))
{
}
void on_init()
{
action_client_ = rclcpp_action::create_client<Fibonacci>(shared_from_this(), "fibonacci");
action_client_->wait_for_action_server();
deactivate_pub_ = this->create_publisher<std_msgs::msg::Empty>("deactivate_server", 1);
activate_pub_ = this->create_publisher<std_msgs::msg::Empty>("activate_server", 1);
omit_prempt_pub_ = this->create_publisher<std_msgs::msg::Empty>("omit_preemption", 1);
}
void on_term()
{
action_client_.reset();
}
void deactivate_server()
{
deactivate_pub_->publish(std_msgs::msg::Empty());
}
void activate_server()
{
activate_pub_->publish(std_msgs::msg::Empty());
}
void omit_server_preemptions()
{
omit_prempt_pub_->publish(std_msgs::msg::Empty());
}
rclcpp_action::Client<Fibonacci>::SharedPtr action_client_;
rclcpp::Publisher<std_msgs::msg::Empty>::SharedPtr deactivate_pub_;
rclcpp::Publisher<std_msgs::msg::Empty>::SharedPtr activate_pub_;
rclcpp::Publisher<std_msgs::msg::Empty>::SharedPtr omit_prempt_pub_;
};
class ActionTest : public ::testing::Test
{
protected:
void SetUp() override
{
node_ = std::make_shared<ActionTestNode>();
node_->on_init();
}
void TearDown() override
{
std::cout << " Teardown" << std::endl;
node_->on_term();
std::cout << " Teardown..." << std::endl;
node_.reset();
std::cout << " Teardown complete" << std::endl;
}
std::shared_ptr<ActionTestNode> node_;
};
TEST_F(ActionTest, test_simple_action)
{
node_->activate_server();
// The goal for this invocation
auto goal = Fibonacci::Goal();
goal.order = 12;
// Send the goal
auto future_goal_handle = node_->action_client_->async_send_goal(goal);
EXPECT_EQ(
rclcpp::spin_until_future_complete(
node_,
future_goal_handle), rclcpp::FutureReturnCode::SUCCESS);
auto goal_handle = future_goal_handle.get();
// Wait for the result
auto future_result = node_->action_client_->async_get_result(goal_handle);
EXPECT_EQ(
rclcpp::spin_until_future_complete(node_, future_result),
rclcpp::FutureReturnCode::SUCCESS);
// The final result
rclcpp_action::ClientGoalHandle<Fibonacci>::WrappedResult result = future_result.get();
EXPECT_EQ(result.code, rclcpp_action::ResultCode::SUCCEEDED);
// Sum all of the values in the requested fibonacci series
int sum = 0;
for (auto number : result.result->sequence) {
sum += number;
}
EXPECT_EQ(sum, 376);
SUCCEED();
}
TEST_F(ActionTest, test_simple_action_with_feedback)
{
int feedback_sum = 0;
// A callback to accumulate the intermediate values
auto feedback_callback = [&feedback_sum](
rclcpp_action::ClientGoalHandle<Fibonacci>::SharedPtr /*goal_handle*/,
const std::shared_ptr<const Fibonacci::Feedback> feedback)
{
feedback_sum += feedback->sequence.back();
};
// The goal for this invocation
auto goal = Fibonacci::Goal();
goal.order = 10;
auto send_goal_options = rclcpp_action::Client<Fibonacci>::SendGoalOptions();
send_goal_options.feedback_callback = feedback_callback;
// Send the goal
auto future_goal_handle = node_->action_client_->async_send_goal(goal, send_goal_options);
EXPECT_EQ(
rclcpp::spin_until_future_complete(
node_,
future_goal_handle), rclcpp::FutureReturnCode::SUCCESS);
auto goal_handle = future_goal_handle.get();
// Wait for the result
auto future_result = node_->action_client_->async_get_result(goal_handle);
EXPECT_EQ(
rclcpp::spin_until_future_complete(
node_,
future_result), rclcpp::FutureReturnCode::SUCCESS);
// The final result
rclcpp_action::ClientGoalHandle<Fibonacci>::WrappedResult result = future_result.get();
EXPECT_EQ(result.code, rclcpp_action::ResultCode::SUCCEEDED);
// Sum all of the values in the requested fibonacci series
int sum = 0;
for (auto number : result.result->sequence) {
sum += number;
}
EXPECT_EQ(sum, 143);
EXPECT_GE(feedback_sum, 0); // We should have received *some* feedback
SUCCEED();
}
TEST_F(ActionTest, test_simple_action_activation_cycling)
{
// The goal for this invocation
auto goal = Fibonacci::Goal();
// Sending a goal that will take a long time to calculate
goal.order = 12'000'000;
// Start by sending goal on an active server
// Send the goal
auto future_goal_handle = node_->action_client_->async_send_goal(goal);
EXPECT_EQ(
rclcpp::spin_until_future_complete(
node_,
future_goal_handle), rclcpp::FutureReturnCode::SUCCESS);
// Deactivate while running
node_->deactivate_server();
auto goal_handle = future_goal_handle.get();
// Wait for the result
auto future_result = node_->action_client_->async_get_result(goal_handle);
EXPECT_EQ(
rclcpp::spin_until_future_complete(node_, future_result),
rclcpp::FutureReturnCode::SUCCESS);
// The action should be reported as aborted.
EXPECT_EQ(future_result.get().code, rclcpp_action::ResultCode::ABORTED);
// Cycle back to active
node_->activate_server();
goal.order = 12;
// Send the goal
future_goal_handle = node_->action_client_->async_send_goal(goal);
std::cout << "Sent goal, spinning til complete..." << std::endl;
EXPECT_EQ(
rclcpp::spin_until_future_complete(
node_,
future_goal_handle), rclcpp::FutureReturnCode::SUCCESS);
goal_handle = future_goal_handle.get();
// Wait for the result
future_result = node_->action_client_->async_get_result(goal_handle);
std::cout << "Getting result, spinning til complete..." << std::endl;
EXPECT_EQ(
rclcpp::spin_until_future_complete(node_, future_result),
rclcpp::FutureReturnCode::SUCCESS);
// Now the action should have been successfully executed.
EXPECT_EQ(future_result.get().code, rclcpp_action::ResultCode::SUCCEEDED);
SUCCEED();
}
TEST_F(ActionTest, test_simple_action_preemption)
{
// The goal for this invocation
auto goal = Fibonacci::Goal();
// Sending a goal that will take a long time to calculate
goal.order = 12'000'000;
// Send the goal
auto future_goal_handle = node_->action_client_->async_send_goal(goal);
std::cout << "Sent goal, spinning til complete..." << std::endl;
EXPECT_EQ(
rclcpp::spin_until_future_complete(
node_,
future_goal_handle), rclcpp::FutureReturnCode::SUCCESS);
// Preempt the goal
auto preemption_goal = Fibonacci::Goal();
preemption_goal.order = 1;
// Send the goal
future_goal_handle = node_->action_client_->async_send_goal(preemption_goal);
std::cout << "Sent goal, spinning til complete..." << std::endl;
EXPECT_EQ(
rclcpp::spin_until_future_complete(
node_,
future_goal_handle), rclcpp::FutureReturnCode::SUCCESS);
auto goal_handle = future_goal_handle.get();
// Wait for the result
auto future_result = node_->action_client_->async_get_result(goal_handle);
std::cout << "Getting result, spinning til complete..." << std::endl;
EXPECT_EQ(
rclcpp::spin_until_future_complete(node_, future_result),
rclcpp::FutureReturnCode::SUCCESS);
// The final result
rclcpp_action::ClientGoalHandle<Fibonacci>::WrappedResult result = future_result.get();
EXPECT_EQ(result.code, rclcpp_action::ResultCode::SUCCEEDED);
// Sum all of the values in the requested fibonacci series
int sum = 0;
for (auto number : result.result->sequence) {
sum += number;
}
EXPECT_EQ(sum, 1);
SUCCEED();
}
TEST_F(ActionTest, test_simple_action_preemption_after_succeeded)
{
// Test race condition between successfully completing an action and receiving a preemption.
auto goal = Fibonacci::Goal();
goal.order = 20;
auto preemption = Fibonacci::Goal();
preemption.order = 1;
// Send the goal
auto future_goal_handle = node_->action_client_->async_send_goal(goal);
EXPECT_EQ(
rclcpp::spin_until_future_complete(
node_,
future_goal_handle), rclcpp::FutureReturnCode::SUCCESS);
node_->omit_server_preemptions();
auto future_preempt_handle = node_->action_client_->async_send_goal(preemption);
EXPECT_EQ(
rclcpp::spin_until_future_complete(
node_,
future_goal_handle), rclcpp::FutureReturnCode::SUCCESS);
// Get the results
auto goal_handle = future_goal_handle.get();
// Wait for the result of initial goal
auto future_result = node_->action_client_->async_get_result(goal_handle);
EXPECT_EQ(
rclcpp::spin_until_future_complete(node_, future_result),
rclcpp::FutureReturnCode::SUCCESS);
// The final result
rclcpp_action::ClientGoalHandle<Fibonacci>::WrappedResult result = future_result.get();
EXPECT_EQ(result.code, rclcpp_action::ResultCode::SUCCEEDED);
// Sum all of the values in the requested fibonacci series
int sum = 0;
for (auto number : result.result->sequence) {
sum += number;
}
EXPECT_EQ(sum, 17710);
// Now get the preemption result
goal_handle = future_preempt_handle.get();
// Wait for the result of initial goal
future_result = node_->action_client_->async_get_result(goal_handle);
ASSERT_EQ(
rclcpp::spin_until_future_complete(node_, future_result),
rclcpp::FutureReturnCode::SUCCESS);
// The final result
result = future_result.get();
EXPECT_EQ(result.code, rclcpp_action::ResultCode::SUCCEEDED);
// Sum all of the values in the requested fibonacci series
sum = 0;
for (auto number : result.result->sequence) {
sum += number;
}
EXPECT_EQ(sum, 1);
SUCCEED();
}
TEST_F(ActionTest, test_handle_goal_deactivated)
{
node_->deactivate_server();
auto goal = Fibonacci::Goal();
goal.order = 12;
// Send the goal
auto future_goal_handle = node_->action_client_->async_send_goal(goal);
EXPECT_EQ(
rclcpp::spin_until_future_complete(
node_,
future_goal_handle), rclcpp::FutureReturnCode::SUCCESS);
node_->activate_server();
SUCCEED();
}
TEST_F(ActionTest, test_handle_cancel)
{
auto goal = Fibonacci::Goal();
goal.order = 14000000;
// Send the goal
auto future_goal_handle = node_->action_client_->async_send_goal(goal);
EXPECT_EQ(
rclcpp::spin_until_future_complete(
node_,
future_goal_handle), rclcpp::FutureReturnCode::SUCCESS);
// Cancel the goal
auto cancel_response = node_->action_client_->async_cancel_goal(future_goal_handle.get());
EXPECT_EQ(
rclcpp::spin_until_future_complete(
node_,
cancel_response), rclcpp::FutureReturnCode::SUCCESS);
// Check cancelled
EXPECT_EQ(future_goal_handle.get()->get_status(), rclcpp_action::GoalStatus::STATUS_CANCELING);
SUCCEED();
}
int main(int argc, char ** argv)
{
rclcpp::init(argc, argv);
g_rclcppfixture.Setup();
::testing::InitGoogleTest(&argc, argv);
auto result = RUN_ALL_TESTS();
rclcpp::shutdown();
return result;
}