-
Notifications
You must be signed in to change notification settings - Fork 430
/
test_lifecycle_node.cpp
764 lines (648 loc) · 28.7 KB
/
test_lifecycle_node.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
// 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 <gtest/gtest.h>
#include <map>
#include <memory>
#include <set>
#include <string>
#include <vector>
#include <utility>
#include "lifecycle_msgs/msg/state.hpp"
#include "lifecycle_msgs/msg/transition.hpp"
#include "rcl_lifecycle/rcl_lifecycle.h"
#include "rclcpp/rclcpp.hpp"
#include "rclcpp_lifecycle/lifecycle_node.hpp"
#include "./mocking_utils/patch.hpp"
using lifecycle_msgs::msg::State;
using lifecycle_msgs::msg::Transition;
static const std::chrono::nanoseconds DEFAULT_EVENT_TIMEOUT = std::chrono::seconds(3);
static const std::chrono::nanoseconds DEFAULT_EVENT_SLEEP_PERIOD = std::chrono::milliseconds(100);
static
bool wait_for_event(
std::shared_ptr<rclcpp_lifecycle::LifecycleNode> node,
std::function<bool()> predicate,
std::chrono::nanoseconds timeout,
std::chrono::nanoseconds sleep_period)
{
auto start = std::chrono::steady_clock::now();
std::chrono::microseconds time_slept(0);
bool predicate_result;
while (!(predicate_result = predicate()) &&
time_slept < std::chrono::duration_cast<std::chrono::microseconds>(timeout))
{
rclcpp::Event::SharedPtr graph_event = node->get_graph_event();
node->wait_for_graph_change(graph_event, sleep_period);
time_slept = std::chrono::duration_cast<std::chrono::microseconds>(
std::chrono::steady_clock::now() - start);
}
return predicate_result;
}
static
bool wait_for_topic(
std::shared_ptr<rclcpp_lifecycle::LifecycleNode> node,
const std::string & topic,
std::chrono::nanoseconds timeout = DEFAULT_EVENT_TIMEOUT,
std::chrono::nanoseconds sleep_period = DEFAULT_EVENT_SLEEP_PERIOD)
{
return wait_for_event(
node,
[node, topic]()
{
auto topic_names_and_types = node->get_topic_names_and_types();
return topic_names_and_types.end() != topic_names_and_types.find(topic);
},
timeout,
sleep_period);
}
static
bool wait_for_service(
std::shared_ptr<rclcpp_lifecycle::LifecycleNode> node,
const std::string & service,
std::chrono::nanoseconds timeout = DEFAULT_EVENT_TIMEOUT,
std::chrono::nanoseconds sleep_period = DEFAULT_EVENT_SLEEP_PERIOD)
{
return wait_for_event(
node,
[node, service]()
{
auto service_names_and_types = node->get_service_names_and_types();
return service_names_and_types.end() != service_names_and_types.find(service);
},
timeout,
sleep_period);
}
static
bool wait_for_service_by_node(
std::shared_ptr<rclcpp_lifecycle::LifecycleNode> node,
const std::string & node_name,
const std::string & service,
std::chrono::nanoseconds timeout = DEFAULT_EVENT_TIMEOUT,
std::chrono::nanoseconds sleep_period = DEFAULT_EVENT_SLEEP_PERIOD)
{
return wait_for_event(
node,
[node, node_name, service]()
{
auto service_names_and_types_by_node = node->get_service_names_and_types_by_node(
node_name, "");
return service_names_and_types_by_node.end() != service_names_and_types_by_node.find(
service);
},
timeout,
sleep_period);
}
class TestDefaultStateMachine : public ::testing::Test
{
protected:
static void SetUpTestCase()
{
rclcpp::init(0, nullptr);
}
static void TearDownTestCase()
{
rclcpp::shutdown();
}
};
class EmptyLifecycleNode : public rclcpp_lifecycle::LifecycleNode
{
public:
explicit EmptyLifecycleNode(const std::string & node_name)
: rclcpp_lifecycle::LifecycleNode(node_name)
{}
};
struct GoodMood
{
using CallbackReturnT =
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;
static constexpr CallbackReturnT cb_ret = static_cast<CallbackReturnT>(
lifecycle_msgs::msg::Transition::TRANSITION_CALLBACK_SUCCESS);
};
struct BadMood
{
using CallbackReturnT =
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;
static constexpr CallbackReturnT cb_ret = static_cast<CallbackReturnT>(
lifecycle_msgs::msg::Transition::TRANSITION_CALLBACK_FAILURE);
};
template<class Mood = GoodMood>
class MoodyLifecycleNode : public rclcpp_lifecycle::LifecycleNode
{
public:
explicit MoodyLifecycleNode(std::string node_name)
: rclcpp_lifecycle::LifecycleNode(std::move(node_name))
{}
size_t number_of_callbacks = 0;
protected:
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn
on_configure(const rclcpp_lifecycle::State &)
{
EXPECT_EQ(State::TRANSITION_STATE_CONFIGURING, get_current_state().id());
++number_of_callbacks;
return Mood::cb_ret;
}
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn
on_activate(const rclcpp_lifecycle::State &)
{
EXPECT_EQ(State::TRANSITION_STATE_ACTIVATING, get_current_state().id());
++number_of_callbacks;
return Mood::cb_ret;
}
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn
on_deactivate(const rclcpp_lifecycle::State &)
{
EXPECT_EQ(State::TRANSITION_STATE_DEACTIVATING, get_current_state().id());
++number_of_callbacks;
return Mood::cb_ret;
}
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn
on_cleanup(const rclcpp_lifecycle::State &)
{
EXPECT_EQ(State::TRANSITION_STATE_CLEANINGUP, get_current_state().id());
++number_of_callbacks;
return Mood::cb_ret;
}
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn
on_shutdown(const rclcpp_lifecycle::State &)
{
EXPECT_EQ(State::TRANSITION_STATE_SHUTTINGDOWN, get_current_state().id());
++number_of_callbacks;
return Mood::cb_ret;
}
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn
on_error(const rclcpp_lifecycle::State &);
};
template<>
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn
MoodyLifecycleNode<GoodMood>::on_error(const rclcpp_lifecycle::State &)
{
EXPECT_EQ(State::TRANSITION_STATE_ERRORPROCESSING, get_current_state().id());
ADD_FAILURE();
return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS;
}
template<>
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn
MoodyLifecycleNode<BadMood>::on_error(const rclcpp_lifecycle::State &)
{
EXPECT_EQ(State::TRANSITION_STATE_ERRORPROCESSING, get_current_state().id());
++number_of_callbacks;
return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS;
}
TEST_F(TestDefaultStateMachine, empty_initializer) {
auto test_node = std::make_shared<EmptyLifecycleNode>("testnode");
EXPECT_STREQ("testnode", test_node->get_name());
EXPECT_STREQ("/", test_node->get_namespace());
EXPECT_STREQ("/testnode", test_node->get_fully_qualified_name());
EXPECT_EQ(State::PRIMARY_STATE_UNCONFIGURED, test_node->get_current_state().id());
}
TEST_F(TestDefaultStateMachine, empty_initializer_rcl_errors) {
{
auto patch = mocking_utils::inject_on_return(
"lib:rclcpp_lifecycle", rcl_lifecycle_state_machine_init, RCL_RET_ERROR);
EXPECT_THROW(
std::make_shared<EmptyLifecycleNode>("testnode").reset(),
std::runtime_error);
}
{
auto test_node = std::make_shared<EmptyLifecycleNode>("testnode");
auto patch = mocking_utils::inject_on_return(
"lib:rclcpp_lifecycle", rcl_lifecycle_state_machine_fini, RCL_RET_ERROR);
EXPECT_NO_THROW(test_node.reset());
}
}
TEST_F(TestDefaultStateMachine, trigger_transition) {
auto test_node = std::make_shared<EmptyLifecycleNode>("testnode");
EXPECT_EQ(State::PRIMARY_STATE_UNCONFIGURED, test_node->get_current_state().id());
ASSERT_EQ(
State::PRIMARY_STATE_INACTIVE, test_node->trigger_transition(
rclcpp_lifecycle::Transition(Transition::TRANSITION_CONFIGURE)).id());
ASSERT_EQ(
State::PRIMARY_STATE_ACTIVE, test_node->trigger_transition(
rclcpp_lifecycle::Transition(Transition::TRANSITION_ACTIVATE)).id());
ASSERT_EQ(
State::PRIMARY_STATE_INACTIVE, test_node->trigger_transition(
rclcpp_lifecycle::Transition(Transition::TRANSITION_DEACTIVATE)).id());
ASSERT_EQ(
State::PRIMARY_STATE_UNCONFIGURED, test_node->trigger_transition(
rclcpp_lifecycle::Transition(Transition::TRANSITION_CLEANUP)).id());
ASSERT_EQ(
State::PRIMARY_STATE_FINALIZED, test_node->trigger_transition(
rclcpp_lifecycle::Transition(Transition::TRANSITION_UNCONFIGURED_SHUTDOWN)).id());
}
TEST_F(TestDefaultStateMachine, trigger_transition_rcl_errors) {
auto test_node = std::make_shared<EmptyLifecycleNode>("testnode");
{
auto mock = mocking_utils::patch_and_return(
"lib:rclcpp_lifecycle", rcl_lifecycle_state_machine_is_initialized, RCL_RET_ERROR);
EXPECT_EQ(
State::PRIMARY_STATE_UNCONFIGURED,
test_node->trigger_transition(
rclcpp_lifecycle::Transition(Transition::TRANSITION_CONFIGURE)).id());
}
{
auto mock = mocking_utils::patch_and_return(
"lib:rclcpp_lifecycle", rcl_lifecycle_trigger_transition_by_id, RCL_RET_ERROR);
EXPECT_EQ(
State::PRIMARY_STATE_UNCONFIGURED,
test_node->trigger_transition(
rclcpp_lifecycle::Transition(Transition::TRANSITION_CONFIGURE)).id());
}
{
auto mock = mocking_utils::patch_and_return(
"lib:rclcpp_lifecycle", rcl_lifecycle_trigger_transition_by_label, RCL_RET_ERROR);
EXPECT_EQ(
State::TRANSITION_STATE_CONFIGURING,
test_node->trigger_transition(
rclcpp_lifecycle::Transition(Transition::TRANSITION_CONFIGURE)).id());
}
}
TEST_F(TestDefaultStateMachine, trigger_transition_with_error_code) {
auto test_node = std::make_shared<EmptyLifecycleNode>("testnode");
auto success = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS;
auto reset_key = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::ERROR;
auto ret = reset_key;
EXPECT_EQ(State::PRIMARY_STATE_UNCONFIGURED, test_node->get_current_state().id());
test_node->trigger_transition(
rclcpp_lifecycle::Transition(Transition::TRANSITION_CONFIGURE), ret);
ASSERT_EQ(success, ret);
ret = reset_key;
test_node->trigger_transition(
rclcpp_lifecycle::Transition(Transition::TRANSITION_ACTIVATE), ret);
ASSERT_EQ(success, ret);
ret = reset_key;
test_node->trigger_transition(
rclcpp_lifecycle::Transition(Transition::TRANSITION_DEACTIVATE), ret);
ASSERT_EQ(success, ret);
ret = reset_key;
test_node->trigger_transition(
rclcpp_lifecycle::Transition(Transition::TRANSITION_CLEANUP), ret);
ASSERT_EQ(success, ret);
ret = reset_key;
test_node->trigger_transition(
rclcpp_lifecycle::Transition(Transition::TRANSITION_UNCONFIGURED_SHUTDOWN), ret);
ASSERT_EQ(success, ret);
}
TEST_F(TestDefaultStateMachine, call_transitions_with_error_code) {
auto test_node = std::make_shared<EmptyLifecycleNode>("testnode");
auto success = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS;
auto reset_key = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::ERROR;
auto ret = reset_key;
test_node->configure(ret);
EXPECT_EQ(success, ret);
ret = reset_key;
test_node->activate(ret);
EXPECT_EQ(success, ret);
ret = reset_key;
test_node->deactivate(ret);
EXPECT_EQ(success, ret);
ret = reset_key;
test_node->cleanup(ret);
EXPECT_EQ(success, ret);
ret = reset_key;
test_node->shutdown(ret);
EXPECT_EQ(success, ret);
}
TEST_F(TestDefaultStateMachine, call_transitions_without_code) {
auto test_node = std::make_shared<EmptyLifecycleNode>("testnode");
auto configured = test_node->configure();
EXPECT_EQ(configured.id(), State::PRIMARY_STATE_INACTIVE);
auto activated = test_node->activate();
EXPECT_EQ(activated.id(), State::PRIMARY_STATE_ACTIVE);
auto deactivated = test_node->deactivate();
EXPECT_EQ(deactivated.id(), State::PRIMARY_STATE_INACTIVE);
auto unconfigured = test_node->cleanup();
EXPECT_EQ(unconfigured.id(), State::PRIMARY_STATE_UNCONFIGURED);
auto finalized = test_node->shutdown();
EXPECT_EQ(finalized.id(), State::PRIMARY_STATE_FINALIZED);
}
TEST_F(TestDefaultStateMachine, good_mood) {
auto test_node = std::make_shared<MoodyLifecycleNode<GoodMood>>("testnode");
EXPECT_EQ(State::PRIMARY_STATE_UNCONFIGURED, test_node->get_current_state().id());
EXPECT_EQ(
State::PRIMARY_STATE_INACTIVE, test_node->trigger_transition(
rclcpp_lifecycle::Transition(Transition::TRANSITION_CONFIGURE)).id());
EXPECT_EQ(
State::PRIMARY_STATE_ACTIVE, test_node->trigger_transition(
rclcpp_lifecycle::Transition(Transition::TRANSITION_ACTIVATE)).id());
EXPECT_EQ(
State::PRIMARY_STATE_INACTIVE, test_node->trigger_transition(
rclcpp_lifecycle::Transition(Transition::TRANSITION_DEACTIVATE)).id());
EXPECT_EQ(
State::PRIMARY_STATE_UNCONFIGURED, test_node->trigger_transition(
rclcpp_lifecycle::Transition(Transition::TRANSITION_CLEANUP)).id());
EXPECT_EQ(
State::PRIMARY_STATE_FINALIZED, test_node->trigger_transition(
rclcpp_lifecycle::Transition(Transition::TRANSITION_UNCONFIGURED_SHUTDOWN)).id());
// check if all callbacks were successfully overwritten
EXPECT_EQ(5u, test_node->number_of_callbacks);
}
TEST_F(TestDefaultStateMachine, bad_mood) {
auto test_node = std::make_shared<MoodyLifecycleNode<BadMood>>("testnode");
EXPECT_EQ(State::PRIMARY_STATE_UNCONFIGURED, test_node->get_current_state().id());
EXPECT_EQ(
State::PRIMARY_STATE_UNCONFIGURED, test_node->trigger_transition(
rclcpp_lifecycle::Transition(Transition::TRANSITION_CONFIGURE)).id());
// check if all callbacks were successfully overwritten
EXPECT_EQ(1u, test_node->number_of_callbacks);
}
TEST_F(TestDefaultStateMachine, lifecycle_subscriber) {
auto test_node = std::make_shared<MoodyLifecycleNode<GoodMood>>("testnode");
auto cb = [](const std::shared_ptr<const lifecycle_msgs::msg::State> msg) {(void) msg;};
auto lifecycle_sub =
test_node->create_subscription<lifecycle_msgs::msg::State>("~/empty", 10, cb);
SUCCEED();
}
// Parameters are tested more thoroughly in rclcpp's test_node.cpp
// These are provided for coverage of lifecycle node's API
TEST_F(TestDefaultStateMachine, declare_parameters) {
// "start_type_description_service" and "use_sim_time"
const uint64_t builtin_param_count = 2;
const uint64_t expected_param_count = 6 + builtin_param_count;
auto test_node = std::make_shared<EmptyLifecycleNode>("testnode");
auto list_result = test_node->list_parameters({}, 0u);
EXPECT_EQ(list_result.names.size(), builtin_param_count);
EXPECT_STREQ(list_result.names[0].c_str(), "start_type_description_service");
EXPECT_STREQ(list_result.names[1].c_str(), "use_sim_time");
const std::string bool_name = "test_boolean";
const std::string int_name = "test_int";
// Default descriptor overload
test_node->declare_parameter(bool_name, rclcpp::ParameterValue(false));
// Explicit descriptor overload
rcl_interfaces::msg::ParameterDescriptor int_descriptor;
int_descriptor.name = int_name;
int_descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER;
int_descriptor.description = "Example integer parameter";
test_node->declare_parameter(int_name, rclcpp::ParameterValue(42), int_descriptor);
std::map<std::string, std::string> str_parameters;
str_parameters["str_one"] = "stringy_string";
str_parameters["str_two"] = "stringy_string_string";
// Default descriptor overload
test_node->declare_parameters("test_string", str_parameters);
std::map<std::string,
std::pair<double, rcl_interfaces::msg::ParameterDescriptor>> double_parameters;
rcl_interfaces::msg::ParameterDescriptor double_descriptor_one;
double_descriptor_one.name = "double_one";
double_descriptor_one.type = rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE;
double_parameters["double_one"] = std::make_pair(1.0, double_descriptor_one);
rcl_interfaces::msg::ParameterDescriptor double_descriptor_two;
double_descriptor_two.name = "double_two";
double_descriptor_two.type = rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE;
double_parameters["double_two"] = std::make_pair(2.0, double_descriptor_two);
// Explicit descriptor overload
test_node->declare_parameters("test_double", double_parameters);
list_result = test_node->list_parameters({}, 0u);
EXPECT_EQ(list_result.names.size(), expected_param_count);
// The order of these names is not controlled by lifecycle_node, doing set equality
std::set<std::string> expected_names = {
"start_type_description_service",
"test_boolean",
"test_double.double_one",
"test_double.double_two",
"test_int",
"test_string.str_one",
"test_string.str_two",
"use_sim_time",
};
std::set<std::string> actual_names(list_result.names.begin(), list_result.names.end());
EXPECT_EQ(expected_names, actual_names);
}
TEST_F(TestDefaultStateMachine, check_parameters) {
const uint64_t builtin_param_count = 2;
auto test_node = std::make_shared<EmptyLifecycleNode>("testnode");
auto list_result = test_node->list_parameters({}, 0u);
EXPECT_EQ(list_result.names.size(), builtin_param_count);
EXPECT_STREQ(list_result.names[0].c_str(), "start_type_description_service");
EXPECT_STREQ(list_result.names[1].c_str(), "use_sim_time");
const std::string bool_name = "test_boolean";
const std::string int_name = "test_int";
std::vector<std::string> parameter_names = {bool_name, int_name};
EXPECT_FALSE(test_node->has_parameter(bool_name));
EXPECT_FALSE(test_node->has_parameter(int_name));
EXPECT_THROW(
test_node->get_parameters(parameter_names),
rclcpp::exceptions::ParameterNotDeclaredException);
// Default descriptor overload
rcl_interfaces::msg::ParameterDescriptor bool_descriptor;
bool_descriptor.dynamic_typing = true;
test_node->declare_parameter(bool_name, rclcpp::ParameterValue(true), bool_descriptor);
// Explicit descriptor overload
rcl_interfaces::msg::ParameterDescriptor int_descriptor;
int_descriptor.name = int_name;
int_descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER;
int_descriptor.description = "Example integer parameter";
test_node->declare_parameter(int_name, rclcpp::ParameterValue(42), int_descriptor);
// describe parameters
auto descriptors = test_node->describe_parameters(parameter_names);
EXPECT_EQ(descriptors.size(), parameter_names.size());
// This actually throws inside NodeParameters::describe_parameters(), so it's not currently
// possible to cover this method 100%.
EXPECT_THROW(
test_node->describe_parameter("not_a_real_parameter"),
rclcpp::exceptions::ParameterNotDeclaredException);
// describe parameter matches explicit descriptor
auto descriptor = test_node->describe_parameter(int_name);
EXPECT_STREQ(descriptor.name.c_str(), int_descriptor.name.c_str());
EXPECT_EQ(descriptor.type, int_descriptor.type);
EXPECT_STREQ(descriptor.description.c_str(), int_descriptor.description.c_str());
// bool parameter exists and value matches
EXPECT_TRUE(test_node->has_parameter(bool_name));
EXPECT_EQ(test_node->get_parameter(bool_name).as_bool(), true);
// int parameter exists and value matches
EXPECT_TRUE(test_node->has_parameter(int_name));
EXPECT_EQ(test_node->get_parameter(int_name).as_int(), 42);
// Get multiple parameters at a time
auto parameters = test_node->get_parameters(parameter_names);
EXPECT_EQ(parameters.size(), parameter_names.size());
EXPECT_EQ(parameters[0].as_bool(), true);
EXPECT_EQ(parameters[1].as_int(), 42);
// Get multiple parameters at a time with map
std::map<std::string, rclcpp::ParameterValue> parameter_map;
EXPECT_TRUE(test_node->get_parameters({}, parameter_map));
EXPECT_EQ(parameter_map.size(), parameter_names.size() + builtin_param_count);
// Check parameter types
auto parameter_types = test_node->get_parameter_types(parameter_names);
EXPECT_EQ(parameter_types.size(), parameter_names.size());
EXPECT_EQ(parameter_types[0], rcl_interfaces::msg::ParameterType::PARAMETER_BOOL);
EXPECT_EQ(parameter_types[1], rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER);
// Setting parameters
size_t parameters_set = 0;
auto callback = [¶meters_set](const std::vector<rclcpp::Parameter> & parameters) {
parameters_set += parameters.size();
rcl_interfaces::msg::SetParametersResult result;
result.successful = true;
return result;
};
// Hold callback handle. Callback is valid during the lifetime of this object.
auto callback_handle = test_node->add_on_set_parameters_callback(callback);
rclcpp::Parameter bool_parameter(bool_name, rclcpp::ParameterValue(false));
EXPECT_TRUE(test_node->set_parameter(bool_parameter).successful);
EXPECT_EQ(parameters_set, 1u);
rclcpp::Parameter int_parameter(int_name, rclcpp::ParameterValue(7));
test_node->set_parameters({int_parameter});
EXPECT_EQ(parameters_set, 2u);
test_node->remove_on_set_parameters_callback(callback_handle.get());
rclcpp::Parameter bool_parameter2(bool_name, rclcpp::ParameterValue(true));
EXPECT_TRUE(test_node->set_parameter(bool_parameter2).successful);
EXPECT_EQ(parameters_set, 2u);
// List parameters
list_result = test_node->list_parameters({}, 0u);
EXPECT_EQ(list_result.names.size(), parameter_names.size() + builtin_param_count);
size_t index = 0;
EXPECT_STREQ(list_result.names[index++].c_str(), "start_type_description_service");
EXPECT_STREQ(list_result.names[index++].c_str(), parameter_names[0].c_str());
EXPECT_STREQ(list_result.names[index++].c_str(), parameter_names[1].c_str());
EXPECT_STREQ(list_result.names[index++].c_str(), "use_sim_time");
// Undeclare parameter
test_node->undeclare_parameter(bool_name);
EXPECT_FALSE(test_node->has_parameter(bool_name));
rclcpp::Parameter parameter;
EXPECT_FALSE(test_node->get_parameter(bool_name, parameter));
// Bool parameter has been undeclared, atomic setting should fail
parameters = {
rclcpp::Parameter(bool_name, rclcpp::ParameterValue(true)),
rclcpp::Parameter(int_name, rclcpp::ParameterValue(0))};
EXPECT_THROW(
test_node->set_parameters_atomically(parameters),
rclcpp::exceptions::ParameterNotDeclaredException);
// Since setting parameters failed, this should remain the same
EXPECT_EQ(test_node->get_parameter(int_name).as_int(), 7);
// Bool parameter no longer exists, using "or" value
EXPECT_FALSE(
test_node->get_parameter_or(
bool_name, parameter, rclcpp::Parameter(bool_name, rclcpp::ParameterValue(true))));
EXPECT_TRUE(parameter.as_bool());
}
TEST_F(TestDefaultStateMachine, test_getters) {
auto test_node = std::make_shared<EmptyLifecycleNode>("testnode");
auto options = test_node->get_node_options();
EXPECT_EQ(0u, options.arguments().size());
EXPECT_NE(nullptr, test_node->get_node_base_interface());
EXPECT_NE(nullptr, test_node->get_node_clock_interface());
EXPECT_NE(nullptr, test_node->get_node_graph_interface());
EXPECT_NE(nullptr, test_node->get_node_logging_interface());
EXPECT_NE(nullptr, test_node->get_node_time_source_interface());
EXPECT_NE(nullptr, test_node->get_node_timers_interface());
EXPECT_NE(nullptr, test_node->get_node_topics_interface());
EXPECT_NE(nullptr, test_node->get_node_services_interface());
EXPECT_NE(nullptr, test_node->get_node_parameters_interface());
EXPECT_NE(nullptr, test_node->get_node_waitables_interface());
EXPECT_NE(nullptr, test_node->get_graph_event());
EXPECT_NE(nullptr, test_node->get_clock());
EXPECT_LT(0u, test_node->now().nanoseconds());
EXPECT_STREQ("testnode", test_node->get_logger().get_name());
EXPECT_NE(nullptr, const_cast<const EmptyLifecycleNode *>(test_node.get())->get_clock());
EXPECT_NE(nullptr, test_node->get_node_type_descriptions_interface());
}
TEST_F(TestDefaultStateMachine, test_graph_topics) {
auto test_node = std::make_shared<EmptyLifecycleNode>("testnode");
auto names = test_node->get_node_names();
ASSERT_NE(names.end(), std::find(names.begin(), names.end(), std::string("/testnode")));
// Other topics may exist for an rclcpp::Node, but just checking the lifecycle one exists
ASSERT_TRUE(wait_for_topic(test_node, "/testnode/transition_event"));
auto topic_names_and_types = test_node->get_topic_names_and_types();
EXPECT_STREQ(
topic_names_and_types["/testnode/transition_event"][0].c_str(),
"lifecycle_msgs/msg/TransitionEvent");
EXPECT_EQ(1u, test_node->count_publishers("/testnode/transition_event"));
EXPECT_EQ(0u, test_node->count_subscribers("/testnode/transition_event"));
auto publishers_info = test_node->get_publishers_info_by_topic("/testnode/transition_event");
EXPECT_EQ(1u, publishers_info.size());
auto subscriptions_info =
test_node->get_subscriptions_info_by_topic("/testnode/transition_event");
EXPECT_EQ(0u, subscriptions_info.size());
}
TEST_F(TestDefaultStateMachine, test_graph_services) {
auto test_node = std::make_shared<EmptyLifecycleNode>("testnode");
// These are specific to lifecycle nodes, other services are provided by rclcpp::Node
ASSERT_TRUE(wait_for_service(test_node, "/testnode/change_state"));
ASSERT_TRUE(wait_for_service(test_node, "/testnode/get_available_states"));
ASSERT_TRUE(wait_for_service(test_node, "/testnode/get_available_transitions"));
ASSERT_TRUE(wait_for_service(test_node, "/testnode/get_state"));
ASSERT_TRUE(wait_for_service(test_node, "/testnode/get_transition_graph"));
auto service_names_and_types = test_node->get_service_names_and_types();
EXPECT_STREQ(
service_names_and_types["/testnode/change_state"][0].c_str(),
"lifecycle_msgs/srv/ChangeState");
EXPECT_STREQ(
service_names_and_types["/testnode/get_available_states"][0].c_str(),
"lifecycle_msgs/srv/GetAvailableStates");
EXPECT_STREQ(
service_names_and_types["/testnode/get_available_transitions"][0].c_str(),
"lifecycle_msgs/srv/GetAvailableTransitions");
EXPECT_STREQ(
service_names_and_types["/testnode/get_state"][0].c_str(),
"lifecycle_msgs/srv/GetState");
EXPECT_STREQ(
service_names_and_types["/testnode/get_transition_graph"][0].c_str(),
"lifecycle_msgs/srv/GetAvailableTransitions");
}
TEST_F(TestDefaultStateMachine, test_graph_services_by_node) {
auto test_node = std::make_shared<EmptyLifecycleNode>("testnode");
// These are specific to lifecycle nodes, other services are provided by rclcpp::Node
ASSERT_TRUE(wait_for_service_by_node(test_node, "testnode", "/testnode/change_state"));
ASSERT_TRUE(wait_for_service_by_node(test_node, "testnode", "/testnode/get_available_states"));
ASSERT_TRUE(
wait_for_service_by_node(test_node, "testnode", "/testnode/get_available_transitions"));
ASSERT_TRUE(wait_for_service_by_node(test_node, "testnode", "/testnode/get_state"));
ASSERT_TRUE(wait_for_service_by_node(test_node, "testnode", "/testnode/get_transition_graph"));
auto service_names_and_types_by_node =
test_node->get_service_names_and_types_by_node("testnode", "");
EXPECT_STREQ(
service_names_and_types_by_node["/testnode/change_state"][0].c_str(),
"lifecycle_msgs/srv/ChangeState");
EXPECT_STREQ(
service_names_and_types_by_node["/testnode/get_available_states"][0].c_str(),
"lifecycle_msgs/srv/GetAvailableStates");
EXPECT_STREQ(
service_names_and_types_by_node["/testnode/get_available_transitions"][0].c_str(),
"lifecycle_msgs/srv/GetAvailableTransitions");
EXPECT_STREQ(
service_names_and_types_by_node["/testnode/get_state"][0].c_str(),
"lifecycle_msgs/srv/GetState");
EXPECT_STREQ(
service_names_and_types_by_node["/testnode/get_transition_graph"][0].c_str(),
"lifecycle_msgs/srv/GetAvailableTransitions");
}
TEST_F(TestDefaultStateMachine, test_callback_groups) {
auto test_node = std::make_shared<EmptyLifecycleNode>("testnode");
size_t num_groups = 0;
test_node->for_each_callback_group(
[&num_groups](rclcpp::CallbackGroup::SharedPtr group_ptr)
{
(void)group_ptr;
num_groups++;
});
EXPECT_EQ(num_groups, 1u);
auto group = test_node->create_callback_group(
rclcpp::CallbackGroupType::MutuallyExclusive, true);
EXPECT_NE(nullptr, group);
num_groups = 0;
test_node->for_each_callback_group(
[&num_groups](rclcpp::CallbackGroup::SharedPtr group_ptr)
{
(void)group_ptr;
num_groups++;
});
EXPECT_EQ(num_groups, 2u);
}
TEST_F(TestDefaultStateMachine, wait_for_graph_change)
{
auto test_node = std::make_shared<EmptyLifecycleNode>("testnode");
EXPECT_THROW(
test_node->wait_for_graph_change(nullptr, std::chrono::milliseconds(1)),
rclcpp::exceptions::InvalidEventError);
auto event = std::make_shared<rclcpp::Event>();
EXPECT_THROW(
test_node->wait_for_graph_change(event, std::chrono::milliseconds(0)),
rclcpp::exceptions::EventNotRegisteredError);
}