forked from ros2/rclcpp
-
Notifications
You must be signed in to change notification settings - Fork 0
Expand file tree
/
Copy pathtest_memory_strategy.cpp
More file actions
539 lines (499 loc) · 21.4 KB
/
test_memory_strategy.cpp
File metadata and controls
539 lines (499 loc) · 21.4 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
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
// Copyright 2020 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 <list>
#include <map>
#include <memory>
#include <utility>
#include "rclcpp/strategies/allocator_memory_strategy.hpp"
#include "rclcpp/memory_strategy.hpp"
#include "test_msgs/msg/empty.hpp"
#include "test_msgs/srv/empty.hpp"
using rclcpp::memory_strategy::MemoryStrategy;
typedef std::map<rclcpp::CallbackGroup::WeakPtr,
rclcpp::node_interfaces::NodeBaseInterface::WeakPtr,
std::owner_less<rclcpp::CallbackGroup::WeakPtr>> WeakCallbackGroupsToNodesMap;
/**
* Mock Waitable class
*/
class TestWaitable : public rclcpp::Waitable
{
public:
bool add_to_wait_set(rcl_wait_set_t *) override {return true;}
bool is_ready(rcl_wait_set_t *) override {return true;}
std::shared_ptr<void> take_data() override {return nullptr;}
void execute(std::shared_ptr<void> & data) override {(void)data;}
};
class TestMemoryStrategy : public ::testing::Test
{
public:
TestMemoryStrategy()
: memory_strategy_(nullptr) {}
void SetUp() override
{
rclcpp::init(0, nullptr);
// This doesn't test AllocatorMemoryStrategy directly, so we cast to the base class.
// AllocatorMemoryStrategy is more commonly used than MessagePoolMemoryStrategy
// so we use this derived class for these tests.
memory_strategy_ =
std::make_shared<
rclcpp::memory_strategies::allocator_memory_strategy::AllocatorMemoryStrategy<>>();
}
void TearDown() override
{
rclcpp::shutdown();
}
protected:
std::shared_ptr<MemoryStrategy> memory_strategy()
{
return memory_strategy_;
}
private:
std::shared_ptr<MemoryStrategy> memory_strategy_;
};
TEST_F(TestMemoryStrategy, construct_destruct) {
EXPECT_NE(nullptr, memory_strategy());
}
TEST_F(TestMemoryStrategy, get_subscription_by_handle) {
WeakCallbackGroupsToNodesMap weak_groups_to_nodes;
std::shared_ptr<const rcl_subscription_t> subscription_handle;
rclcpp::SubscriptionBase::SharedPtr found_subscription = nullptr;
{
auto node = std::make_shared<rclcpp::Node>("node", "ns");
auto callback_groups = node->get_node_base_interface()->get_callback_groups();
std::for_each(
callback_groups.begin(), callback_groups.end(),
[&weak_groups_to_nodes, &node](rclcpp::CallbackGroup::WeakPtr weak_group_ptr) {
weak_groups_to_nodes.insert(
std::pair<rclcpp::CallbackGroup::WeakPtr,
rclcpp::node_interfaces::NodeBaseInterface::WeakPtr>(
weak_group_ptr,
node->get_node_base_interface()));
});
memory_strategy()->collect_entities(weak_groups_to_nodes);
{
auto callback_group =
node->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);
auto subscription_callback = [](test_msgs::msg::Empty::ConstSharedPtr) {};
const rclcpp::QoS qos(10);
{
auto subscription = node->create_subscription<
test_msgs::msg::Empty, decltype(subscription_callback)>(
"topic", qos, std::move(subscription_callback));
subscription_handle = subscription->get_subscription_handle();
EXPECT_EQ(
subscription,
memory_strategy()->get_subscription_by_handle(subscription_handle, weak_groups_to_nodes));
} // subscription goes out of scope
EXPECT_EQ(
nullptr,
memory_strategy()->get_subscription_by_handle(subscription_handle, weak_groups_to_nodes));
} // callback_group goes out of scope
EXPECT_EQ(
nullptr,
memory_strategy()->get_subscription_by_handle(subscription_handle, weak_groups_to_nodes));
} // Node goes out of scope
EXPECT_EQ(
nullptr,
memory_strategy()->get_subscription_by_handle(subscription_handle, weak_groups_to_nodes));
}
TEST_F(TestMemoryStrategy, get_service_by_handle) {
WeakCallbackGroupsToNodesMap weak_groups_to_nodes;
std::shared_ptr<const rcl_service_t> service_handle;
rclcpp::ServiceBase::SharedPtr found_service = nullptr;
{
auto node = std::make_shared<rclcpp::Node>("node", "ns");
auto callback_groups = node->get_node_base_interface()->get_callback_groups();
std::for_each(
callback_groups.begin(), callback_groups.end(),
[&weak_groups_to_nodes, &node](rclcpp::CallbackGroup::WeakPtr weak_group_ptr) {
weak_groups_to_nodes.insert(
std::pair<rclcpp::CallbackGroup::WeakPtr,
rclcpp::node_interfaces::NodeBaseInterface::WeakPtr>(
weak_group_ptr,
node->get_node_base_interface()));
});
memory_strategy()->collect_entities(weak_groups_to_nodes);
{
auto callback_group =
node->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);
auto service_callback =
[](const test_msgs::srv::Empty::Request::SharedPtr,
test_msgs::srv::Empty::Response::SharedPtr) {};
const rclcpp::QoS qos(10);
weak_groups_to_nodes.insert(
std::pair<rclcpp::CallbackGroup::WeakPtr,
rclcpp::node_interfaces::NodeBaseInterface::WeakPtr>(
rclcpp::CallbackGroup::WeakPtr(callback_group),
node->get_node_base_interface()));
{
auto service = node->create_service<test_msgs::srv::Empty>(
"service", std::move(service_callback),
rmw_qos_profile_services_default, callback_group);
service_handle = service->get_service_handle();
EXPECT_EQ(
service,
memory_strategy()->get_service_by_handle(service_handle, weak_groups_to_nodes));
} // service goes out of scope
EXPECT_EQ(
nullptr,
memory_strategy()->get_service_by_handle(service_handle, weak_groups_to_nodes));
} // callback_group goes out of scope
EXPECT_EQ(
nullptr,
memory_strategy()->get_service_by_handle(service_handle, weak_groups_to_nodes));
} // Node goes out of scope
EXPECT_EQ(
nullptr,
memory_strategy()->get_service_by_handle(service_handle, weak_groups_to_nodes));
}
TEST_F(TestMemoryStrategy, get_client_by_handle) {
WeakCallbackGroupsToNodesMap weak_groups_to_nodes;
std::shared_ptr<const rcl_client_t> client_handle;
rclcpp::ClientBase::SharedPtr found_client = nullptr;
{
auto node = std::make_shared<rclcpp::Node>("node", "ns");
auto callback_groups = node->get_node_base_interface()->get_callback_groups();
std::for_each(
callback_groups.begin(), callback_groups.end(),
[&weak_groups_to_nodes, &node](rclcpp::CallbackGroup::WeakPtr weak_group_ptr) {
weak_groups_to_nodes.insert(
std::pair<rclcpp::CallbackGroup::WeakPtr,
rclcpp::node_interfaces::NodeBaseInterface::WeakPtr>(
weak_group_ptr,
node->get_node_base_interface()));
});
memory_strategy()->collect_entities(weak_groups_to_nodes);
{
auto callback_group =
node->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);
{
auto client = node->create_client<test_msgs::srv::Empty>(
"service", rmw_qos_profile_services_default, callback_group);
client_handle = client->get_client_handle();
weak_groups_to_nodes.insert(
std::pair<rclcpp::CallbackGroup::WeakPtr,
rclcpp::node_interfaces::NodeBaseInterface::WeakPtr>(
rclcpp::CallbackGroup::WeakPtr(callback_group),
node->get_node_base_interface()));
EXPECT_EQ(
client,
memory_strategy()->get_client_by_handle(client_handle, weak_groups_to_nodes));
} // client goes out of scope
EXPECT_EQ(
nullptr,
memory_strategy()->get_client_by_handle(client_handle, weak_groups_to_nodes));
} // callback_group goes out of scope
EXPECT_EQ(
nullptr,
memory_strategy()->get_client_by_handle(client_handle, weak_groups_to_nodes));
} // Node goes out of scope
EXPECT_EQ(
nullptr,
memory_strategy()->get_client_by_handle(client_handle, weak_groups_to_nodes));
}
TEST_F(TestMemoryStrategy, get_timer_by_handle) {
WeakCallbackGroupsToNodesMap weak_groups_to_nodes;
std::shared_ptr<const rcl_timer_t> timer_handle;
rclcpp::TimerBase::SharedPtr found_timer = nullptr;
{
auto node = std::make_shared<rclcpp::Node>("node", "ns");
auto callback_groups = node->get_node_base_interface()->get_callback_groups();
std::for_each(
callback_groups.begin(), callback_groups.end(),
[&weak_groups_to_nodes, &node](rclcpp::CallbackGroup::WeakPtr weak_group_ptr) {
weak_groups_to_nodes.insert(
std::pair<rclcpp::CallbackGroup::WeakPtr,
rclcpp::node_interfaces::NodeBaseInterface::WeakPtr>(
weak_group_ptr,
node->get_node_base_interface()));
});
memory_strategy()->collect_entities(weak_groups_to_nodes);
{
auto callback_group =
node->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);
{
auto timer_callback = []() {};
auto timer = node->create_wall_timer(
std::chrono::milliseconds(1), timer_callback, callback_group);
weak_groups_to_nodes.insert(
std::pair<rclcpp::CallbackGroup::WeakPtr,
rclcpp::node_interfaces::NodeBaseInterface::WeakPtr>(
rclcpp::CallbackGroup::WeakPtr(callback_group),
node->get_node_base_interface()));
timer_handle = timer->get_timer_handle();
EXPECT_EQ(
timer,
memory_strategy()->get_timer_by_handle(timer_handle, weak_groups_to_nodes));
} // timer goes out of scope
EXPECT_EQ(
nullptr,
memory_strategy()->get_timer_by_handle(timer_handle, weak_groups_to_nodes));
} // callback_group goes out of scope
EXPECT_EQ(
nullptr,
memory_strategy()->get_timer_by_handle(timer_handle, weak_groups_to_nodes));
} // Node goes out of scope
EXPECT_EQ(
nullptr,
memory_strategy()->get_timer_by_handle(timer_handle, weak_groups_to_nodes));
}
TEST_F(TestMemoryStrategy, get_node_by_group) {
WeakCallbackGroupsToNodesMap weak_groups_to_nodes;
rclcpp::CallbackGroup::SharedPtr callback_group = nullptr;
{
auto node = std::make_shared<rclcpp::Node>("node", "ns");
auto node_handle = node->get_node_base_interface();
auto callback_groups = node_handle->get_callback_groups();
std::for_each(
callback_groups.begin(), callback_groups.end(),
[&weak_groups_to_nodes, &node_handle](rclcpp::CallbackGroup::WeakPtr weak_group_ptr) {
weak_groups_to_nodes.insert(
std::pair<rclcpp::CallbackGroup::WeakPtr,
rclcpp::node_interfaces::NodeBaseInterface::WeakPtr>(
weak_group_ptr,
node_handle));
});
memory_strategy()->collect_entities(weak_groups_to_nodes);
EXPECT_EQ(
nullptr,
memory_strategy()->get_node_by_group(nullptr, weak_groups_to_nodes));
callback_group =
node->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);
// Nothing in the weak_groups_to_nodes, so find fails.
EXPECT_EQ(
nullptr,
memory_strategy()->get_node_by_group(callback_group, weak_groups_to_nodes));
weak_groups_to_nodes.insert(
std::pair<rclcpp::CallbackGroup::WeakPtr,
rclcpp::node_interfaces::NodeBaseInterface::WeakPtr>(
rclcpp::CallbackGroup::WeakPtr(callback_group),
node->get_node_base_interface()));
EXPECT_EQ(
node_handle,
memory_strategy()->get_node_by_group(callback_group, weak_groups_to_nodes));
} // Node goes out of scope
// Callback group still exists, so lookup returns nullptr because node is destroyed.
EXPECT_EQ(
nullptr,
memory_strategy()->get_node_by_group(callback_group, weak_groups_to_nodes));
}
TEST_F(TestMemoryStrategy, get_group_by_subscription) {
WeakCallbackGroupsToNodesMap weak_groups_to_nodes;
rclcpp::SubscriptionBase::SharedPtr subscription = nullptr;
rclcpp::CallbackGroup::SharedPtr callback_group = nullptr;
{
auto node = std::make_shared<rclcpp::Node>("node", "ns");
auto callback_groups = node->get_node_base_interface()->get_callback_groups();
std::for_each(
callback_groups.begin(), callback_groups.end(),
[&weak_groups_to_nodes, &node](rclcpp::CallbackGroup::WeakPtr weak_group_ptr) {
weak_groups_to_nodes.insert(
std::pair<rclcpp::CallbackGroup::WeakPtr,
rclcpp::node_interfaces::NodeBaseInterface::WeakPtr>(
weak_group_ptr,
node->get_node_base_interface()));
});
memory_strategy()->collect_entities(weak_groups_to_nodes);
{
// This group is just used to test that a callback group that is held as a weak pointer
// by node, doesn't confuse get_group_by_subscription() when it goes out of scope
auto non_persistant_group =
node->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);
callback_group =
node->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);
auto subscription_callback = [](test_msgs::msg::Empty::ConstSharedPtr) {};
const rclcpp::QoS qos(10);
rclcpp::SubscriptionOptions subscription_options;
// This callback group is held as a shared_ptr in subscription_options, which means it
// stays alive as long as subscription does.
subscription_options.callback_group = callback_group;
subscription = node->create_subscription<
test_msgs::msg::Empty, decltype(subscription_callback)>(
"topic", qos, std::move(subscription_callback), subscription_options);
weak_groups_to_nodes.insert(
std::pair<rclcpp::CallbackGroup::WeakPtr,
rclcpp::node_interfaces::NodeBaseInterface::WeakPtr>(
rclcpp::CallbackGroup::WeakPtr(callback_group),
rclcpp::node_interfaces::NodeBaseInterface::WeakPtr(node->get_node_base_interface())));
EXPECT_EQ(
callback_group,
memory_strategy()->get_group_by_subscription(subscription, weak_groups_to_nodes));
} // callback_group goes out of scope
EXPECT_EQ(
callback_group,
memory_strategy()->get_group_by_subscription(subscription, weak_groups_to_nodes));
} // Node goes out of scope
EXPECT_EQ(
nullptr,
memory_strategy()->get_group_by_subscription(subscription, weak_groups_to_nodes));
}
TEST_F(TestMemoryStrategy, get_group_by_service) {
WeakCallbackGroupsToNodesMap weak_groups_to_nodes;
rclcpp::ServiceBase::SharedPtr service = nullptr;
{
auto node = std::make_shared<rclcpp::Node>("node", "ns");
auto callback_groups = node->get_node_base_interface()->get_callback_groups();
std::for_each(
callback_groups.begin(), callback_groups.end(),
[&weak_groups_to_nodes, &node](rclcpp::CallbackGroup::WeakPtr weak_group_ptr) {
weak_groups_to_nodes.insert(
std::pair<rclcpp::CallbackGroup::WeakPtr,
rclcpp::node_interfaces::NodeBaseInterface::WeakPtr>(
weak_group_ptr,
node->get_node_base_interface()));
});
memory_strategy()->collect_entities(weak_groups_to_nodes);
{
auto callback_group =
node->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);
auto service_callback =
[](const test_msgs::srv::Empty::Request::SharedPtr,
test_msgs::srv::Empty::Response::SharedPtr) {};
const rclcpp::QoS qos(10);
service = node->create_service<test_msgs::srv::Empty>(
"service", std::move(service_callback),
rmw_qos_profile_services_default, callback_group);
weak_groups_to_nodes.insert(
std::pair<rclcpp::CallbackGroup::WeakPtr,
rclcpp::node_interfaces::NodeBaseInterface::WeakPtr>(
rclcpp::CallbackGroup::WeakPtr(callback_group),
rclcpp::node_interfaces::NodeBaseInterface::WeakPtr(node->get_node_base_interface())));
EXPECT_EQ(
callback_group,
memory_strategy()->get_group_by_service(service, weak_groups_to_nodes));
} // callback_group goes out of scope
EXPECT_EQ(
nullptr,
memory_strategy()->get_group_by_service(service, weak_groups_to_nodes));
} // Node goes out of scope
EXPECT_EQ(
nullptr,
memory_strategy()->get_group_by_service(service, weak_groups_to_nodes));
}
TEST_F(TestMemoryStrategy, get_group_by_client) {
WeakCallbackGroupsToNodesMap weak_groups_to_nodes;
rclcpp::ClientBase::SharedPtr client = nullptr;
{
auto node = std::make_shared<rclcpp::Node>("node", "ns");
auto callback_groups = node->get_node_base_interface()->get_callback_groups();
std::for_each(
callback_groups.begin(), callback_groups.end(),
[&weak_groups_to_nodes, &node](rclcpp::CallbackGroup::WeakPtr weak_group_ptr) {
weak_groups_to_nodes.insert(
std::pair<rclcpp::CallbackGroup::WeakPtr,
rclcpp::node_interfaces::NodeBaseInterface::WeakPtr>(
weak_group_ptr,
node->get_node_base_interface()));
});
memory_strategy()->collect_entities(weak_groups_to_nodes);
{
auto callback_group =
node->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);
client = node->create_client<test_msgs::srv::Empty>(
"service", rmw_qos_profile_services_default, callback_group);
weak_groups_to_nodes.insert(
std::pair<rclcpp::CallbackGroup::WeakPtr,
rclcpp::node_interfaces::NodeBaseInterface::WeakPtr>(
rclcpp::CallbackGroup::WeakPtr(callback_group),
rclcpp::node_interfaces::NodeBaseInterface::WeakPtr(node->get_node_base_interface())));
EXPECT_EQ(
callback_group,
memory_strategy()->get_group_by_client(client, weak_groups_to_nodes));
} // callback_group goes out of scope
EXPECT_EQ(
nullptr,
memory_strategy()->get_group_by_client(client, weak_groups_to_nodes));
} // Node goes out of scope
EXPECT_EQ(
nullptr,
memory_strategy()->get_group_by_client(client, weak_groups_to_nodes));
}
TEST_F(TestMemoryStrategy, get_group_by_timer) {
WeakCallbackGroupsToNodesMap weak_groups_to_nodes;
rclcpp::TimerBase::SharedPtr timer = nullptr;
{
auto node = std::make_shared<rclcpp::Node>("node", "ns");
auto callback_groups = node->get_node_base_interface()->get_callback_groups();
std::for_each(
callback_groups.begin(), callback_groups.end(),
[&weak_groups_to_nodes, &node](rclcpp::CallbackGroup::WeakPtr weak_group_ptr) {
weak_groups_to_nodes.insert(
std::pair<rclcpp::CallbackGroup::WeakPtr,
rclcpp::node_interfaces::NodeBaseInterface::WeakPtr>(
weak_group_ptr,
node->get_node_base_interface()));
});
memory_strategy()->collect_entities(weak_groups_to_nodes);
{
auto callback_group =
node->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);
auto timer_callback = []() {};
timer = node->create_wall_timer(
std::chrono::milliseconds(1), timer_callback, callback_group);
weak_groups_to_nodes.insert(
std::pair<rclcpp::CallbackGroup::WeakPtr,
rclcpp::node_interfaces::NodeBaseInterface::WeakPtr>(
rclcpp::CallbackGroup::WeakPtr(callback_group),
rclcpp::node_interfaces::NodeBaseInterface::WeakPtr(node->get_node_base_interface())));
EXPECT_EQ(
callback_group,
memory_strategy()->get_group_by_timer(timer, weak_groups_to_nodes));
} // callback_group goes out of scope
EXPECT_EQ(
nullptr,
memory_strategy()->get_group_by_timer(timer, weak_groups_to_nodes));
} // Node goes out of scope
EXPECT_EQ(
nullptr,
memory_strategy()->get_group_by_timer(timer, weak_groups_to_nodes));
}
TEST_F(TestMemoryStrategy, get_group_by_waitable) {
WeakCallbackGroupsToNodesMap weak_groups_to_nodes;
rclcpp::Waitable::SharedPtr waitable = nullptr;
{
auto node = std::make_shared<rclcpp::Node>("node", "ns");
auto callback_groups = node->get_node_base_interface()->get_callback_groups();
std::for_each(
callback_groups.begin(), callback_groups.end(),
[&weak_groups_to_nodes, &node](rclcpp::CallbackGroup::WeakPtr weak_group_ptr) {
weak_groups_to_nodes.insert(
std::pair<rclcpp::CallbackGroup::WeakPtr,
rclcpp::node_interfaces::NodeBaseInterface::WeakPtr>(
weak_group_ptr,
node->get_node_base_interface()));
});
memory_strategy()->collect_entities(weak_groups_to_nodes);
{
waitable = std::make_shared<TestWaitable>();
auto callback_group =
node->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);
node->get_node_waitables_interface()->add_waitable(waitable, callback_group);
weak_groups_to_nodes.insert(
std::pair<rclcpp::CallbackGroup::WeakPtr,
rclcpp::node_interfaces::NodeBaseInterface::WeakPtr>(
rclcpp::CallbackGroup::WeakPtr(callback_group),
rclcpp::node_interfaces::NodeBaseInterface::WeakPtr(node->get_node_base_interface())));
EXPECT_EQ(
callback_group,
memory_strategy()->get_group_by_waitable(waitable, weak_groups_to_nodes));
} // callback_group goes out of scope
EXPECT_EQ(
nullptr,
memory_strategy()->get_group_by_waitable(waitable, weak_groups_to_nodes));
} // Node goes out of scope
EXPECT_EQ(
nullptr,
memory_strategy()->get_group_by_waitable(waitable, weak_groups_to_nodes));
}