-
Notifications
You must be signed in to change notification settings - Fork 522
Expand file tree
/
Copy pathany_subscription_callback.hpp
More file actions
986 lines (926 loc) · 44.8 KB
/
any_subscription_callback.hpp
File metadata and controls
986 lines (926 loc) · 44.8 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
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
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
986
// Copyright 2014 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.
#ifndef RCLCPP__ANY_SUBSCRIPTION_CALLBACK_HPP_
#define RCLCPP__ANY_SUBSCRIPTION_CALLBACK_HPP_
#include <functional>
#include <memory>
#include <stdexcept>
#include <type_traits>
#include <utility>
#include <variant>
#include "rosidl_runtime_cpp/traits.hpp"
#include "tracetools/tracetools.h"
#include "tracetools/utils.hpp"
#include "rclcpp/allocator/allocator_common.hpp"
#include "rclcpp/detail/subscription_callback_type_helper.hpp"
#include "rclcpp/function_traits.hpp"
#include "rclcpp/message_info.hpp"
#include "rclcpp/serialization.hpp"
#include "rclcpp/serialized_message.hpp"
#include "rclcpp/type_adapter.hpp"
namespace rclcpp
{
namespace detail
{
template<class>
inline constexpr bool always_false_v = false;
template<typename MessageT, typename AllocatorT>
struct MessageDeleterHelper
{
using AllocTraits = allocator::AllocRebind<MessageT, AllocatorT>;
using Alloc = typename AllocTraits::allocator_type;
using Deleter = allocator::Deleter<Alloc, MessageT>;
};
/// Struct which contains all possible callback signatures, with or without a TypeAdapter.s
template<typename MessageT, typename AllocatorT>
struct AnySubscriptionCallbackPossibleTypes
{
/// MessageT::custom_type if MessageT is a TypeAdapter, otherwise just MessageT.
using SubscribedType = typename rclcpp::TypeAdapter<MessageT>::custom_type;
/// MessageT::ros_message_type if MessageT is a TypeAdapter, otherwise just MessageT.
using ROSMessageType = typename rclcpp::TypeAdapter<MessageT>::ros_message_type;
using SubscribedMessageDeleter =
typename MessageDeleterHelper<SubscribedType, AllocatorT>::Deleter;
using ROSMessageDeleter =
typename MessageDeleterHelper<ROSMessageType, AllocatorT>::Deleter;
using SerializedMessageDeleter =
typename MessageDeleterHelper<rclcpp::SerializedMessage, AllocatorT>::Deleter;
using ConstRefCallback =
std::function<void (const SubscribedType &)>;
using ConstRefROSMessageCallback =
std::function<void (const ROSMessageType &)>;
using ConstRefWithInfoCallback =
std::function<void (const SubscribedType &, const rclcpp::MessageInfo &)>;
using ConstRefWithInfoROSMessageCallback =
std::function<void (const ROSMessageType &, const rclcpp::MessageInfo &)>;
using ConstRefSerializedMessageCallback =
std::function<void (const rclcpp::SerializedMessage &)>;
using ConstRefSerializedMessageWithInfoCallback =
std::function<void (const rclcpp::SerializedMessage &, const rclcpp::MessageInfo &)>;
using UniquePtrCallback =
std::function<void (std::unique_ptr<SubscribedType, SubscribedMessageDeleter>)>;
using UniquePtrROSMessageCallback =
std::function<void (std::unique_ptr<ROSMessageType, ROSMessageDeleter>)>;
using UniquePtrWithInfoCallback =
std::function<void (
std::unique_ptr<SubscribedType, SubscribedMessageDeleter>,
const rclcpp::MessageInfo &)>;
using UniquePtrWithInfoROSMessageCallback =
std::function<void (
std::unique_ptr<ROSMessageType, ROSMessageDeleter>,
const rclcpp::MessageInfo &)>;
using UniquePtrSerializedMessageCallback =
std::function<void (std::unique_ptr<rclcpp::SerializedMessage, SerializedMessageDeleter>)>;
using UniquePtrSerializedMessageWithInfoCallback =
std::function<void (
std::unique_ptr<rclcpp::SerializedMessage, SerializedMessageDeleter>,
const rclcpp::MessageInfo &)>;
using SharedConstPtrCallback =
std::function<void (std::shared_ptr<const SubscribedType>)>;
using SharedConstPtrROSMessageCallback =
std::function<void (std::shared_ptr<const ROSMessageType>)>;
using SharedConstPtrWithInfoCallback =
std::function<void (
std::shared_ptr<const SubscribedType>,
const rclcpp::MessageInfo &)>;
using SharedConstPtrWithInfoROSMessageCallback =
std::function<void (
std::shared_ptr<const ROSMessageType>,
const rclcpp::MessageInfo &)>;
using SharedConstPtrSerializedMessageCallback =
std::function<void (std::shared_ptr<const rclcpp::SerializedMessage>)>;
using SharedConstPtrSerializedMessageWithInfoCallback =
std::function<void (
std::shared_ptr<const rclcpp::SerializedMessage>,
const rclcpp::MessageInfo &)>;
using ConstRefSharedConstPtrCallback =
std::function<void (const std::shared_ptr<const SubscribedType> &)>;
using ConstRefSharedConstPtrROSMessageCallback =
std::function<void (const std::shared_ptr<const ROSMessageType> &)>;
using ConstRefSharedConstPtrWithInfoCallback =
std::function<void (
const std::shared_ptr<const SubscribedType> &,
const rclcpp::MessageInfo &)>;
using ConstRefSharedConstPtrWithInfoROSMessageCallback =
std::function<void (
const std::shared_ptr<const ROSMessageType> &,
const rclcpp::MessageInfo &)>;
using ConstRefSharedConstPtrSerializedMessageCallback =
std::function<void (const std::shared_ptr<const rclcpp::SerializedMessage> &)>;
using ConstRefSharedConstPtrSerializedMessageWithInfoCallback =
std::function<void (
const std::shared_ptr<const rclcpp::SerializedMessage> &,
const rclcpp::MessageInfo &)>;
// Deprecated signatures:
using SharedPtrCallback =
std::function<void (std::shared_ptr<SubscribedType>)>;
using SharedPtrROSMessageCallback =
std::function<void (std::shared_ptr<ROSMessageType>)>;
using SharedPtrWithInfoCallback =
std::function<void (std::shared_ptr<SubscribedType>, const rclcpp::MessageInfo &)>;
using SharedPtrWithInfoROSMessageCallback =
std::function<void (
std::shared_ptr<ROSMessageType>,
const rclcpp::MessageInfo &)>;
using SharedPtrSerializedMessageCallback =
std::function<void (std::shared_ptr<rclcpp::SerializedMessage>)>;
using SharedPtrSerializedMessageWithInfoCallback =
std::function<void (std::shared_ptr<rclcpp::SerializedMessage>, const rclcpp::MessageInfo &)>;
};
/// Template helper to select the variant type based on whether or not MessageT is a TypeAdapter.
template<
typename MessageT,
typename AllocatorT,
bool is_adapted_type = rclcpp::TypeAdapter<MessageT>::is_specialized::value,
bool is_serialized_type = serialization_traits::is_serialized_message_class<MessageT>::value
>
struct AnySubscriptionCallbackHelper;
/// Specialization for when MessageT is not a TypeAdapter.
template<typename MessageT, typename AllocatorT>
struct AnySubscriptionCallbackHelper<MessageT, AllocatorT, false, false>
{
using CallbackTypes = AnySubscriptionCallbackPossibleTypes<MessageT, AllocatorT>;
using variant_type = std::variant<
typename CallbackTypes::ConstRefCallback,
typename CallbackTypes::ConstRefWithInfoCallback,
typename CallbackTypes::ConstRefSerializedMessageCallback,
typename CallbackTypes::ConstRefSerializedMessageWithInfoCallback,
typename CallbackTypes::UniquePtrCallback,
typename CallbackTypes::UniquePtrWithInfoCallback,
typename CallbackTypes::UniquePtrSerializedMessageCallback,
typename CallbackTypes::UniquePtrSerializedMessageWithInfoCallback,
typename CallbackTypes::SharedConstPtrCallback,
typename CallbackTypes::SharedConstPtrWithInfoCallback,
typename CallbackTypes::SharedConstPtrSerializedMessageCallback,
typename CallbackTypes::SharedConstPtrSerializedMessageWithInfoCallback,
typename CallbackTypes::ConstRefSharedConstPtrCallback,
typename CallbackTypes::ConstRefSharedConstPtrWithInfoCallback,
typename CallbackTypes::ConstRefSharedConstPtrSerializedMessageCallback,
typename CallbackTypes::ConstRefSharedConstPtrSerializedMessageWithInfoCallback,
typename CallbackTypes::SharedPtrCallback,
typename CallbackTypes::SharedPtrWithInfoCallback,
typename CallbackTypes::SharedPtrSerializedMessageCallback,
typename CallbackTypes::SharedPtrSerializedMessageWithInfoCallback
>;
};
/// Specialization for when MessageT is a TypeAdapter.
template<typename MessageT, typename AllocatorT>
struct AnySubscriptionCallbackHelper<MessageT, AllocatorT, true, false>
{
using CallbackTypes = AnySubscriptionCallbackPossibleTypes<MessageT, AllocatorT>;
using variant_type = std::variant<
typename CallbackTypes::ConstRefCallback,
typename CallbackTypes::ConstRefROSMessageCallback,
typename CallbackTypes::ConstRefWithInfoCallback,
typename CallbackTypes::ConstRefWithInfoROSMessageCallback,
typename CallbackTypes::ConstRefSerializedMessageCallback,
typename CallbackTypes::ConstRefSerializedMessageWithInfoCallback,
typename CallbackTypes::UniquePtrCallback,
typename CallbackTypes::UniquePtrROSMessageCallback,
typename CallbackTypes::UniquePtrWithInfoCallback,
typename CallbackTypes::UniquePtrWithInfoROSMessageCallback,
typename CallbackTypes::UniquePtrSerializedMessageCallback,
typename CallbackTypes::UniquePtrSerializedMessageWithInfoCallback,
typename CallbackTypes::SharedConstPtrCallback,
typename CallbackTypes::SharedConstPtrROSMessageCallback,
typename CallbackTypes::SharedConstPtrWithInfoCallback,
typename CallbackTypes::SharedConstPtrWithInfoROSMessageCallback,
typename CallbackTypes::SharedConstPtrSerializedMessageCallback,
typename CallbackTypes::SharedConstPtrSerializedMessageWithInfoCallback,
typename CallbackTypes::ConstRefSharedConstPtrCallback,
typename CallbackTypes::ConstRefSharedConstPtrROSMessageCallback,
typename CallbackTypes::ConstRefSharedConstPtrWithInfoCallback,
typename CallbackTypes::ConstRefSharedConstPtrWithInfoROSMessageCallback,
typename CallbackTypes::ConstRefSharedConstPtrSerializedMessageCallback,
typename CallbackTypes::ConstRefSharedConstPtrSerializedMessageWithInfoCallback,
typename CallbackTypes::SharedPtrCallback,
typename CallbackTypes::SharedPtrROSMessageCallback,
typename CallbackTypes::SharedPtrWithInfoCallback,
typename CallbackTypes::SharedPtrWithInfoROSMessageCallback,
typename CallbackTypes::SharedPtrSerializedMessageCallback,
typename CallbackTypes::SharedPtrSerializedMessageWithInfoCallback
>;
};
/// Specialization for when MessageT is a SerializedMessage to exclude duplicated declarations.
template<typename MessageT, typename AllocatorT>
struct AnySubscriptionCallbackHelper<MessageT, AllocatorT, false, true>
{
using CallbackTypes = AnySubscriptionCallbackPossibleTypes<MessageT, AllocatorT>;
using variant_type = std::variant<
typename CallbackTypes::ConstRefSerializedMessageCallback,
typename CallbackTypes::ConstRefSerializedMessageWithInfoCallback,
typename CallbackTypes::UniquePtrSerializedMessageCallback,
typename CallbackTypes::UniquePtrSerializedMessageWithInfoCallback,
typename CallbackTypes::SharedConstPtrSerializedMessageCallback,
typename CallbackTypes::SharedConstPtrSerializedMessageWithInfoCallback,
typename CallbackTypes::ConstRefSharedConstPtrSerializedMessageCallback,
typename CallbackTypes::ConstRefSharedConstPtrSerializedMessageWithInfoCallback,
typename CallbackTypes::SharedPtrSerializedMessageCallback,
typename CallbackTypes::SharedPtrSerializedMessageWithInfoCallback
>;
};
} // namespace detail
template<
typename MessageT,
typename AllocatorT = std::allocator<void>
>
class AnySubscriptionCallback
{
private:
/// MessageT::custom_type if MessageT is a TypeAdapter, otherwise just MessageT.
using SubscribedType = typename rclcpp::TypeAdapter<MessageT>::custom_type;
/// MessageT::ros_message_type if MessageT is a TypeAdapter, otherwise just MessageT.
using ROSMessageType = typename rclcpp::TypeAdapter<MessageT>::ros_message_type;
using HelperT = typename rclcpp::detail::AnySubscriptionCallbackHelper<MessageT, AllocatorT>;
using SubscribedTypeDeleterHelper =
rclcpp::detail::MessageDeleterHelper<SubscribedType, AllocatorT>;
using SubscribedTypeAllocatorTraits = typename SubscribedTypeDeleterHelper::AllocTraits;
using SubscribedTypeAllocator = typename SubscribedTypeDeleterHelper::Alloc;
using SubscribedTypeDeleter = typename SubscribedTypeDeleterHelper::Deleter;
using ROSMessageTypeDeleterHelper =
rclcpp::detail::MessageDeleterHelper<ROSMessageType, AllocatorT>;
using ROSMessageTypeAllocatorTraits = typename ROSMessageTypeDeleterHelper::AllocTraits;
using ROSMessageTypeAllocator = typename ROSMessageTypeDeleterHelper::Alloc;
using ROSMessageTypeDeleter = typename ROSMessageTypeDeleterHelper::Deleter;
using SerializedMessageDeleterHelper =
rclcpp::detail::MessageDeleterHelper<rclcpp::SerializedMessage, AllocatorT>;
using SerializedMessageAllocatorTraits = typename SerializedMessageDeleterHelper::AllocTraits;
using SerializedMessageAllocator = typename SerializedMessageDeleterHelper::Alloc;
using SerializedMessageDeleter = typename SerializedMessageDeleterHelper::Deleter;
// See AnySubscriptionCallbackPossibleTypes for the types of these.
using CallbackTypes = detail::AnySubscriptionCallbackPossibleTypes<MessageT, AllocatorT>;
using ConstRefCallback =
typename CallbackTypes::ConstRefCallback;
using ConstRefROSMessageCallback =
typename CallbackTypes::ConstRefROSMessageCallback;
using ConstRefWithInfoCallback =
typename CallbackTypes::ConstRefWithInfoCallback;
using ConstRefWithInfoROSMessageCallback =
typename CallbackTypes::ConstRefWithInfoROSMessageCallback;
using ConstRefSerializedMessageCallback =
typename CallbackTypes::ConstRefSerializedMessageCallback;
using ConstRefSerializedMessageWithInfoCallback =
typename CallbackTypes::ConstRefSerializedMessageWithInfoCallback;
using UniquePtrCallback =
typename CallbackTypes::UniquePtrCallback;
using UniquePtrROSMessageCallback =
typename CallbackTypes::UniquePtrROSMessageCallback;
using UniquePtrWithInfoCallback =
typename CallbackTypes::UniquePtrWithInfoCallback;
using UniquePtrWithInfoROSMessageCallback =
typename CallbackTypes::UniquePtrWithInfoROSMessageCallback;
using UniquePtrSerializedMessageCallback =
typename CallbackTypes::UniquePtrSerializedMessageCallback;
using UniquePtrSerializedMessageWithInfoCallback =
typename CallbackTypes::UniquePtrSerializedMessageWithInfoCallback;
using SharedConstPtrCallback =
typename CallbackTypes::SharedConstPtrCallback;
using SharedConstPtrROSMessageCallback =
typename CallbackTypes::SharedConstPtrROSMessageCallback;
using SharedConstPtrWithInfoCallback =
typename CallbackTypes::SharedConstPtrWithInfoCallback;
using SharedConstPtrWithInfoROSMessageCallback =
typename CallbackTypes::SharedConstPtrWithInfoROSMessageCallback;
using SharedConstPtrSerializedMessageCallback =
typename CallbackTypes::SharedConstPtrSerializedMessageCallback;
using SharedConstPtrSerializedMessageWithInfoCallback =
typename CallbackTypes::SharedConstPtrSerializedMessageWithInfoCallback;
using ConstRefSharedConstPtrCallback =
typename CallbackTypes::ConstRefSharedConstPtrCallback;
using ConstRefSharedConstPtrROSMessageCallback =
typename CallbackTypes::ConstRefSharedConstPtrROSMessageCallback;
using ConstRefSharedConstPtrWithInfoCallback =
typename CallbackTypes::ConstRefSharedConstPtrWithInfoCallback;
using ConstRefSharedConstPtrWithInfoROSMessageCallback =
typename CallbackTypes::ConstRefSharedConstPtrWithInfoROSMessageCallback;
using ConstRefSharedConstPtrSerializedMessageCallback =
typename CallbackTypes::ConstRefSharedConstPtrSerializedMessageCallback;
using ConstRefSharedConstPtrSerializedMessageWithInfoCallback =
typename CallbackTypes::ConstRefSharedConstPtrSerializedMessageWithInfoCallback;
using SharedPtrCallback =
typename CallbackTypes::SharedPtrCallback;
using SharedPtrROSMessageCallback =
typename CallbackTypes::SharedPtrROSMessageCallback;
using SharedPtrWithInfoCallback =
typename CallbackTypes::SharedPtrWithInfoCallback;
using SharedPtrWithInfoROSMessageCallback =
typename CallbackTypes::SharedPtrWithInfoROSMessageCallback;
using SharedPtrSerializedMessageCallback =
typename CallbackTypes::SharedPtrSerializedMessageCallback;
using SharedPtrSerializedMessageWithInfoCallback =
typename CallbackTypes::SharedPtrSerializedMessageWithInfoCallback;
template<typename T>
struct NotNull
{
NotNull(const T * pointer_in, const char * msg)
: pointer(pointer_in)
{
if (pointer == nullptr) {
throw std::invalid_argument(msg);
}
}
const T * pointer;
};
public:
explicit
AnySubscriptionCallback(const AllocatorT & allocator = AllocatorT()) // NOLINT[runtime/explicit]
: subscribed_type_allocator_(allocator),
ros_message_type_allocator_(allocator)
{
allocator::set_allocator_for_deleter(&subscribed_type_deleter_, &subscribed_type_allocator_);
allocator::set_allocator_for_deleter(&ros_message_type_deleter_, &ros_message_type_allocator_);
}
AnySubscriptionCallback(const AnySubscriptionCallback &) = default;
/// Generic function for setting the callback.
/**
* There are specializations that overload this in order to deprecate some
* callback signatures, and also to fix ambiguity between shared_ptr and
* unique_ptr callback signatures when using them with lambda functions.
*/
template<typename CallbackT>
AnySubscriptionCallback<MessageT, AllocatorT>
set(CallbackT callback)
{
// Use the SubscriptionCallbackTypeHelper to determine the actual type of
// the CallbackT, in terms of std::function<...>, which does not happen
// automatically with lambda functions in cases where the arguments can be
// converted to one another, e.g. shared_ptr and unique_ptr.
using scbth = detail::SubscriptionCallbackTypeHelper<MessageT, CallbackT>;
callback_variant_ = static_cast<typename scbth::callback_type>(callback);
// Return copy of self for easier testing, normally will be compiled out.
return *this;
}
std::unique_ptr<ROSMessageType, ROSMessageTypeDeleter>
create_ros_unique_ptr_from_ros_shared_ptr_message(
const std::shared_ptr<const ROSMessageType> & message)
{
auto ptr = ROSMessageTypeAllocatorTraits::allocate(ros_message_type_allocator_, 1);
ROSMessageTypeAllocatorTraits::construct(ros_message_type_allocator_, ptr, *message);
return std::unique_ptr<ROSMessageType, ROSMessageTypeDeleter>(ptr, ros_message_type_deleter_);
}
std::unique_ptr<rclcpp::SerializedMessage, SerializedMessageDeleter>
create_serialized_message_unique_ptr_from_shared_ptr(
const std::shared_ptr<const rclcpp::SerializedMessage> & serialized_message)
{
auto ptr = SerializedMessageAllocatorTraits::allocate(serialized_message_allocator_, 1);
SerializedMessageAllocatorTraits::construct(
serialized_message_allocator_, ptr, *serialized_message);
return std::unique_ptr<
rclcpp::SerializedMessage,
SerializedMessageDeleter
>(ptr, serialized_message_deleter_);
}
std::unique_ptr<SubscribedType, SubscribedTypeDeleter>
create_custom_unique_ptr_from_custom_shared_ptr_message(
const std::shared_ptr<const SubscribedType> & message)
{
auto ptr = SubscribedTypeAllocatorTraits::allocate(subscribed_type_allocator_, 1);
SubscribedTypeAllocatorTraits::construct(subscribed_type_allocator_, ptr, *message);
return std::unique_ptr<SubscribedType, SubscribedTypeDeleter>(ptr, subscribed_type_deleter_);
}
std::unique_ptr<SubscribedType, SubscribedTypeDeleter>
convert_ros_message_to_custom_type_unique_ptr(const ROSMessageType & msg)
{
if constexpr (rclcpp::TypeAdapter<MessageT>::is_specialized::value) {
auto ptr = SubscribedTypeAllocatorTraits::allocate(subscribed_type_allocator_, 1);
SubscribedTypeAllocatorTraits::construct(subscribed_type_allocator_, ptr);
rclcpp::TypeAdapter<MessageT>::convert_to_custom(msg, *ptr);
return std::unique_ptr<SubscribedType, SubscribedTypeDeleter>(ptr, subscribed_type_deleter_);
} else {
throw std::runtime_error(
"convert_ros_message_to_custom_type_unique_ptr "
"unexpectedly called without TypeAdapter");
}
}
std::unique_ptr<ROSMessageType, ROSMessageTypeDeleter>
convert_custom_type_to_ros_message_unique_ptr(const SubscribedType & msg)
{
if constexpr (rclcpp::TypeAdapter<MessageT>::is_specialized::value) {
auto ptr = ROSMessageTypeAllocatorTraits::allocate(ros_message_type_allocator_, 1);
ROSMessageTypeAllocatorTraits::construct(ros_message_type_allocator_, ptr);
rclcpp::TypeAdapter<MessageT>::convert_to_ros_message(msg, *ptr);
return std::unique_ptr<ROSMessageType, ROSMessageTypeDeleter>(ptr, ros_message_type_deleter_);
} else {
static_assert(
!sizeof(MessageT *),
"convert_custom_type_to_ros_message_unique_ptr() "
"unexpectedly called without specialized TypeAdapter");
}
}
// Dispatch when input is a ros message and the output could be anything.
template<typename TMsg = ROSMessageType>
typename std::enable_if<!serialization_traits::is_serialized_message_class<TMsg>::value,
void>::type
dispatch(
std::shared_ptr<ROSMessageType> message,
const rclcpp::MessageInfo & message_info)
{
TRACETOOLS_TRACEPOINT(callback_start, static_cast<const void *>(this), false);
// Check if the variant is "unset", throw if it is.
if (callback_variant_.index() == 0) {
if (std::get<0>(callback_variant_) == nullptr) {
// This can happen if it is default initialized, or if it is assigned nullptr.
throw std::runtime_error("dispatch called on an unset AnySubscriptionCallback");
}
}
// Dispatch.
std::visit(
[&message, &message_info, this](auto && callback) {
using T = std::decay_t<decltype(callback)>;
static constexpr bool is_ta = rclcpp::TypeAdapter<MessageT>::is_specialized::value;
// conditions for output is custom message
if constexpr (is_ta && std::is_same_v<T, ConstRefCallback>) {
// TODO(wjwwood): consider avoiding heap allocation for small messages
// maybe something like:
// if constexpr (rosidl_generator_traits::has_fixed_size<T> && sizeof(T) < N) {
// ... on stack
// }
auto local_message = convert_ros_message_to_custom_type_unique_ptr(*message);
callback(*local_message);
} else if constexpr (is_ta && std::is_same_v<T, ConstRefWithInfoCallback>) { // NOLINT
auto local_message = convert_ros_message_to_custom_type_unique_ptr(*message);
callback(*local_message, message_info);
} else if constexpr (is_ta && std::is_same_v<T, UniquePtrCallback>) {
callback(convert_ros_message_to_custom_type_unique_ptr(*message));
} else if constexpr (is_ta && std::is_same_v<T, UniquePtrWithInfoCallback>) {
callback(convert_ros_message_to_custom_type_unique_ptr(*message), message_info);
} else if constexpr ( // NOLINT[readability/braces]
is_ta && (
std::is_same_v<T, SharedConstPtrCallback>||
std::is_same_v<T, ConstRefSharedConstPtrCallback>||
std::is_same_v<T, SharedPtrCallback>
))
{
callback(convert_ros_message_to_custom_type_unique_ptr(*message));
} else if constexpr ( // NOLINT[readability/braces]
is_ta && (
std::is_same_v<T, SharedConstPtrWithInfoCallback>||
std::is_same_v<T, ConstRefSharedConstPtrWithInfoCallback>||
std::is_same_v<T, SharedPtrWithInfoCallback>
))
{
callback(convert_ros_message_to_custom_type_unique_ptr(*message), message_info);
}
// conditions for output is ros message
else if constexpr (std::is_same_v<T, ConstRefROSMessageCallback>) { // NOLINT
callback(*message);
} else if constexpr (std::is_same_v<T, ConstRefWithInfoROSMessageCallback>) {
callback(*message, message_info);
} else if constexpr (std::is_same_v<T, UniquePtrROSMessageCallback>) {
callback(create_ros_unique_ptr_from_ros_shared_ptr_message(message));
} else if constexpr (std::is_same_v<T, UniquePtrWithInfoROSMessageCallback>) {
callback(create_ros_unique_ptr_from_ros_shared_ptr_message(message), message_info);
} else if constexpr ( // NOLINT[readability/braces]
std::is_same_v<T, SharedConstPtrROSMessageCallback>||
std::is_same_v<T, ConstRefSharedConstPtrROSMessageCallback>||
std::is_same_v<T, SharedPtrROSMessageCallback>)
{
callback(message);
} else if constexpr ( // NOLINT[readability/braces]
std::is_same_v<T, SharedConstPtrWithInfoROSMessageCallback>||
std::is_same_v<T, ConstRefSharedConstPtrWithInfoROSMessageCallback>||
std::is_same_v<T, SharedPtrWithInfoROSMessageCallback>)
{
callback(message, message_info);
}
// condition to catch SerializedMessage types
else if constexpr ( // NOLINT[readability/braces]
std::is_same_v<T, ConstRefSerializedMessageCallback>||
std::is_same_v<T, ConstRefSerializedMessageWithInfoCallback>||
std::is_same_v<T, UniquePtrSerializedMessageCallback>||
std::is_same_v<T, UniquePtrSerializedMessageWithInfoCallback>||
std::is_same_v<T, SharedConstPtrSerializedMessageCallback>||
std::is_same_v<T, SharedConstPtrSerializedMessageWithInfoCallback>||
std::is_same_v<T, ConstRefSharedConstPtrSerializedMessageCallback>||
std::is_same_v<T, ConstRefSharedConstPtrSerializedMessageWithInfoCallback>||
std::is_same_v<T, SharedPtrSerializedMessageCallback>||
std::is_same_v<T, SharedPtrSerializedMessageWithInfoCallback>)
{
throw std::runtime_error(
"Cannot dispatch std::shared_ptr<ROSMessageType> message "
"to rclcpp::SerializedMessage");
}
// condition to catch unhandled callback types
else { // NOLINT[readability/braces]
static_assert(detail::always_false_v<T>, "unhandled callback type");
}
}, callback_variant_);
TRACETOOLS_TRACEPOINT(callback_end, static_cast<const void *>(this));
}
// Dispatch when input is a serialized message and the output could be anything.
void
dispatch(
std::shared_ptr<const rclcpp::SerializedMessage> serialized_message,
const rclcpp::MessageInfo & message_info)
{
TRACETOOLS_TRACEPOINT(callback_start, static_cast<const void *>(this), false);
// Check if the variant is "unset", throw if it is.
if (callback_variant_.index() == 0) {
if (std::get<0>(callback_variant_) == nullptr) {
// This can happen if it is default initialized, or if it is assigned nullptr.
throw std::runtime_error("dispatch called on an unset AnySubscriptionCallback");
}
}
// Dispatch.
std::visit(
[&serialized_message, &message_info, this](auto && callback) {
using T = std::decay_t<decltype(callback)>;
// condition to catch SerializedMessage types
if constexpr (std::is_same_v<T, ConstRefSerializedMessageCallback>) {
callback(*serialized_message);
} else if constexpr (std::is_same_v<T, ConstRefSerializedMessageWithInfoCallback>) {
callback(*serialized_message, message_info);
} else if constexpr (std::is_same_v<T, UniquePtrSerializedMessageCallback>) {
callback(create_serialized_message_unique_ptr_from_shared_ptr(serialized_message));
} else if constexpr (std::is_same_v<T, UniquePtrSerializedMessageWithInfoCallback>) {
callback(
create_serialized_message_unique_ptr_from_shared_ptr(serialized_message),
message_info);
} else if constexpr ( // NOLINT[readability/braces]
std::is_same_v<T, SharedConstPtrSerializedMessageCallback>||
std::is_same_v<T, ConstRefSharedConstPtrSerializedMessageCallback>||
std::is_same_v<T, SharedPtrSerializedMessageCallback>)
{
callback(create_serialized_message_unique_ptr_from_shared_ptr(serialized_message));
} else if constexpr ( // NOLINT[readability/braces]
std::is_same_v<T, SharedConstPtrSerializedMessageWithInfoCallback>||
std::is_same_v<T, ConstRefSharedConstPtrSerializedMessageWithInfoCallback>||
std::is_same_v<T, SharedPtrSerializedMessageWithInfoCallback>)
{
callback(
create_serialized_message_unique_ptr_from_shared_ptr(serialized_message),
message_info);
}
// conditions for output anything else
else if constexpr ( // NOLINT[whitespace/newline]
std::is_same_v<T, ConstRefCallback>||
std::is_same_v<T, ConstRefROSMessageCallback>||
std::is_same_v<T, ConstRefWithInfoCallback>||
std::is_same_v<T, ConstRefWithInfoROSMessageCallback>||
std::is_same_v<T, UniquePtrCallback>||
std::is_same_v<T, UniquePtrROSMessageCallback>||
std::is_same_v<T, UniquePtrWithInfoCallback>||
std::is_same_v<T, UniquePtrWithInfoROSMessageCallback>||
std::is_same_v<T, SharedConstPtrCallback>||
std::is_same_v<T, SharedConstPtrROSMessageCallback>||
std::is_same_v<T, SharedConstPtrWithInfoCallback>||
std::is_same_v<T, SharedConstPtrWithInfoROSMessageCallback>||
std::is_same_v<T, ConstRefSharedConstPtrCallback>||
std::is_same_v<T, ConstRefSharedConstPtrROSMessageCallback>||
std::is_same_v<T, ConstRefSharedConstPtrWithInfoCallback>||
std::is_same_v<T, ConstRefSharedConstPtrWithInfoROSMessageCallback>||
std::is_same_v<T, SharedPtrCallback>||
std::is_same_v<T, SharedPtrROSMessageCallback>||
std::is_same_v<T, SharedPtrWithInfoCallback>||
std::is_same_v<T, SharedPtrWithInfoROSMessageCallback>)
{
throw std::runtime_error(
"cannot dispatch rclcpp::SerializedMessage to "
"non-rclcpp::SerializedMessage callbacks");
}
// condition to catch unhandled callback types
else { // NOLINT[readability/braces]
static_assert(detail::always_false_v<T>, "unhandled callback type");
}
}, callback_variant_);
TRACETOOLS_TRACEPOINT(callback_end, static_cast<const void *>(this));
}
void
dispatch_intra_process(
std::shared_ptr<const SubscribedType> message,
const rclcpp::MessageInfo & message_info)
{
TRACETOOLS_TRACEPOINT(callback_start, static_cast<const void *>(this), true);
// Check if the variant is "unset", throw if it is.
if (callback_variant_.index() == 0) {
if (std::get<0>(callback_variant_) == nullptr) {
// This can happen if it is default initialized, or if it is assigned nullptr.
throw std::runtime_error("dispatch called on an unset AnySubscriptionCallback");
}
}
// Dispatch.
std::visit(
[&message, &message_info, this](auto && callback) {
using T = std::decay_t<decltype(callback)>;
static constexpr bool is_ta = rclcpp::TypeAdapter<MessageT>::is_specialized::value;
// conditions for custom type
if constexpr (is_ta && std::is_same_v<T, ConstRefCallback>) {
callback(*message);
} else if constexpr (is_ta && std::is_same_v<T, ConstRefWithInfoCallback>) { // NOLINT
callback(*message, message_info);
} else if constexpr ( // NOLINT[readability/braces]
is_ta && (
std::is_same_v<T, UniquePtrCallback>||
std::is_same_v<T, SharedPtrCallback>
))
{
callback(create_custom_unique_ptr_from_custom_shared_ptr_message(message));
} else if constexpr ( // NOLINT[readability/braces]
is_ta && (
std::is_same_v<T, UniquePtrWithInfoCallback>||
std::is_same_v<T, SharedPtrWithInfoCallback>
))
{
callback(create_custom_unique_ptr_from_custom_shared_ptr_message(message), message_info);
} else if constexpr ( // NOLINT[readability/braces]
is_ta && (
std::is_same_v<T, SharedConstPtrCallback>||
std::is_same_v<T, ConstRefSharedConstPtrCallback>
))
{
callback(message);
} else if constexpr ( // NOLINT[readability/braces]
is_ta && (
std::is_same_v<T, SharedConstPtrWithInfoCallback>||
std::is_same_v<T, ConstRefSharedConstPtrWithInfoCallback>
))
{
callback(message, message_info);
}
// conditions for ros message type
else if constexpr (std::is_same_v<T, ConstRefROSMessageCallback>) { // NOLINT[readability/braces]
if constexpr (is_ta) {
auto local = convert_custom_type_to_ros_message_unique_ptr(*message);
callback(*local);
} else {
callback(*message);
}
} else if constexpr (std::is_same_v<T, ConstRefWithInfoROSMessageCallback>) { // NOLINT[readability/braces]
if constexpr (is_ta) {
auto local = convert_custom_type_to_ros_message_unique_ptr(*message);
callback(*local, message_info);
} else {
callback(*message, message_info);
}
} else if constexpr ( // NOLINT[readability/braces]
std::is_same_v<T, UniquePtrROSMessageCallback>||
std::is_same_v<T, SharedPtrROSMessageCallback>)
{
if constexpr (is_ta) {
callback(convert_custom_type_to_ros_message_unique_ptr(*message));
} else {
callback(create_ros_unique_ptr_from_ros_shared_ptr_message(message));
}
} else if constexpr ( // NOLINT[readability/braces]
std::is_same_v<T, UniquePtrWithInfoROSMessageCallback>||
std::is_same_v<T, SharedPtrWithInfoROSMessageCallback>)
{
if constexpr (is_ta) {
callback(convert_custom_type_to_ros_message_unique_ptr(*message), message_info);
} else {
callback(create_ros_unique_ptr_from_ros_shared_ptr_message(message), message_info);
}
} else if constexpr ( // NOLINT[readability/braces]
std::is_same_v<T, SharedConstPtrROSMessageCallback>||
std::is_same_v<T, ConstRefSharedConstPtrROSMessageCallback>)
{
if constexpr (is_ta) {
callback(convert_custom_type_to_ros_message_unique_ptr(*message));
} else {
callback(message);
}
} else if constexpr ( // NOLINT[readability/braces]
std::is_same_v<T, SharedConstPtrWithInfoROSMessageCallback>||
std::is_same_v<T, ConstRefSharedConstPtrWithInfoROSMessageCallback>)
{
if constexpr (is_ta) {
callback(convert_custom_type_to_ros_message_unique_ptr(*message), message_info);
} else {
callback(message, message_info);
}
}
// condition to catch SerializedMessage types
else if constexpr ( // NOLINT[readability/braces]
std::is_same_v<T, ConstRefSerializedMessageCallback>||
std::is_same_v<T, ConstRefSerializedMessageWithInfoCallback>||
std::is_same_v<T, UniquePtrSerializedMessageCallback>||
std::is_same_v<T, UniquePtrSerializedMessageWithInfoCallback>||
std::is_same_v<T, SharedConstPtrSerializedMessageCallback>||
std::is_same_v<T, SharedConstPtrSerializedMessageWithInfoCallback>||
std::is_same_v<T, ConstRefSharedConstPtrSerializedMessageCallback>||
std::is_same_v<T, ConstRefSharedConstPtrSerializedMessageWithInfoCallback>||
std::is_same_v<T, SharedPtrSerializedMessageCallback>||
std::is_same_v<T, SharedPtrSerializedMessageWithInfoCallback>)
{
throw std::runtime_error(
"Cannot dispatch std::shared_ptr<const ROSMessageType> message "
"to rclcpp::SerializedMessage");
}
// condition to catch unhandled callback types
else { // NOLINT[readability/braces]
static_assert(detail::always_false_v<T>, "unhandled callback type");
}
}, callback_variant_);
TRACETOOLS_TRACEPOINT(callback_end, static_cast<const void *>(this));
}
void
dispatch_intra_process(
std::unique_ptr<SubscribedType, SubscribedTypeDeleter> message,
const rclcpp::MessageInfo & message_info)
{
TRACETOOLS_TRACEPOINT(callback_start, static_cast<const void *>(this), true);
// Check if the variant is "unset", throw if it is.
if (callback_variant_.index() == 0) {
if (std::get<0>(callback_variant_) == nullptr) {
// This can happen if it is default initialized, or if it is assigned nullptr.
throw std::runtime_error("dispatch called on an unset AnySubscriptionCallback");
}
}
// Dispatch.
std::visit(
[&message, &message_info, this](auto && callback) {
// clang complains that 'this' lambda capture is unused, which is true
// in *some* specializations of this template, but not others. Just
// quiet it down.
(void)this;
using T = std::decay_t<decltype(callback)>;
static constexpr bool is_ta = rclcpp::TypeAdapter<MessageT>::is_specialized::value;
// conditions for custom type
if constexpr (is_ta && std::is_same_v<T, ConstRefCallback>) {
callback(*message);
} else if constexpr (is_ta && std::is_same_v<T, ConstRefWithInfoCallback>) { // NOLINT
callback(*message, message_info);
} else if constexpr ( // NOLINT[readability/braces]
is_ta && (
std::is_same_v<T, UniquePtrCallback>||
std::is_same_v<T, SharedPtrCallback>))
{
callback(std::move(message));
} else if constexpr ( // NOLINT[readability/braces]
is_ta && (
std::is_same_v<T, UniquePtrWithInfoCallback>||
std::is_same_v<T, SharedPtrWithInfoCallback>
))
{
callback(std::move(message), message_info);
} else if constexpr ( // NOLINT[readability/braces]
is_ta && (
std::is_same_v<T, SharedConstPtrCallback>||
std::is_same_v<T, ConstRefSharedConstPtrCallback>
))
{
callback(std::move(message));
} else if constexpr ( // NOLINT[readability/braces]
is_ta && (
std::is_same_v<T, SharedConstPtrWithInfoCallback>||
std::is_same_v<T, ConstRefSharedConstPtrWithInfoCallback>
))
{
callback(std::move(message), message_info);
}
// conditions for ros message type
else if constexpr (std::is_same_v<T, ConstRefROSMessageCallback>) { // NOLINT[readability/braces]
if constexpr (is_ta) {
auto local = convert_custom_type_to_ros_message_unique_ptr(*message);
callback(*local);
} else {
callback(*message);
}
} else if constexpr (std::is_same_v<T, ConstRefWithInfoROSMessageCallback>) { // NOLINT[readability/braces]
if constexpr (is_ta) {
auto local = convert_custom_type_to_ros_message_unique_ptr(*message);
callback(*local, message_info);
} else {
callback(*message, message_info);
}
} else if constexpr ( // NOLINT[readability/braces]
std::is_same_v<T, UniquePtrROSMessageCallback>||
std::is_same_v<T, SharedPtrROSMessageCallback>)
{
if constexpr (is_ta) {
callback(convert_custom_type_to_ros_message_unique_ptr(*message));
} else {
callback(std::move(message));
}
} else if constexpr ( // NOLINT[readability/braces]
std::is_same_v<T, UniquePtrWithInfoROSMessageCallback>||
std::is_same_v<T, SharedPtrWithInfoROSMessageCallback>)
{
if constexpr (is_ta) {
callback(convert_custom_type_to_ros_message_unique_ptr(*message), message_info);
} else {
callback(std::move(message), message_info);
}
} else if constexpr ( // NOLINT[readability/braces]
std::is_same_v<T, SharedConstPtrROSMessageCallback>||
std::is_same_v<T, ConstRefSharedConstPtrROSMessageCallback>)
{
if constexpr (is_ta) {
callback(convert_custom_type_to_ros_message_unique_ptr(*message));
} else {
callback(std::move(message));
}
} else if constexpr ( // NOLINT[readability/braces]
std::is_same_v<T, SharedConstPtrWithInfoROSMessageCallback>||
std::is_same_v<T, ConstRefSharedConstPtrWithInfoROSMessageCallback>)
{
if constexpr (is_ta) {
callback(convert_custom_type_to_ros_message_unique_ptr(*message), message_info);
} else {
callback(std::move(message), message_info);
}
}
// condition to catch SerializedMessage types
else if constexpr ( // NOLINT[readability/braces]
std::is_same_v<T, ConstRefSerializedMessageCallback>||
std::is_same_v<T, ConstRefSerializedMessageWithInfoCallback>||
std::is_same_v<T, UniquePtrSerializedMessageCallback>||
std::is_same_v<T, UniquePtrSerializedMessageWithInfoCallback>||
std::is_same_v<T, SharedConstPtrSerializedMessageCallback>||
std::is_same_v<T, SharedConstPtrSerializedMessageWithInfoCallback>||
std::is_same_v<T, ConstRefSharedConstPtrSerializedMessageCallback>||
std::is_same_v<T, ConstRefSharedConstPtrSerializedMessageWithInfoCallback>||
std::is_same_v<T, SharedPtrSerializedMessageCallback>||
std::is_same_v<T, SharedPtrSerializedMessageWithInfoCallback>)
{
throw std::runtime_error(
"Cannot dispatch std::unique_ptr<ROSMessageType, ROSMessageTypeDeleter> message "
"to rclcpp::SerializedMessage");
}
// condition to catch unhandled callback types
else { // NOLINT[readability/braces]
static_assert(detail::always_false_v<T>, "unhandled callback type");
}
}, callback_variant_);
TRACETOOLS_TRACEPOINT(callback_end, static_cast<const void *>(this));
}
constexpr
bool
use_take_shared_method() const
{
return
std::holds_alternative<SharedConstPtrCallback>(callback_variant_) ||
std::holds_alternative<SharedConstPtrWithInfoCallback>(callback_variant_) ||
std::holds_alternative<ConstRefSharedConstPtrCallback>(callback_variant_) ||
std::holds_alternative<ConstRefSharedConstPtrWithInfoCallback>(callback_variant_);
}
constexpr
bool
is_serialized_message_callback() const
{
return
std::holds_alternative<ConstRefSerializedMessageCallback>(callback_variant_) ||
std::holds_alternative<UniquePtrSerializedMessageCallback>(callback_variant_) ||
std::holds_alternative<SharedConstPtrSerializedMessageCallback>(callback_variant_) ||
std::holds_alternative<ConstRefSharedConstPtrSerializedMessageCallback>(callback_variant_) ||
std::holds_alternative<SharedPtrSerializedMessageCallback>(callback_variant_) ||
std::holds_alternative<ConstRefSerializedMessageWithInfoCallback>(callback_variant_) ||
std::holds_alternative<UniquePtrSerializedMessageWithInfoCallback>(callback_variant_) ||
std::holds_alternative<SharedConstPtrSerializedMessageWithInfoCallback>(callback_variant_) ||
std::holds_alternative<ConstRefSharedConstPtrSerializedMessageWithInfoCallback>(
callback_variant_) ||
std::holds_alternative<SharedPtrSerializedMessageWithInfoCallback>(callback_variant_);
}
void
register_callback_for_tracing()
{
#ifndef TRACETOOLS_DISABLED
std::visit(
[this](auto && callback) {
if (TRACETOOLS_TRACEPOINT_ENABLED(rclcpp_callback_register)) {
char * symbol = tracetools::get_symbol(callback);
TRACETOOLS_DO_TRACEPOINT(
rclcpp_callback_register,
static_cast<const void *>(this),
symbol);
std::free(symbol);
}
}, callback_variant_);
#endif // TRACETOOLS_DISABLED
}
typename HelperT::variant_type &
get_variant()
{
return callback_variant_;
}
const typename HelperT::variant_type &
get_variant() const
{
return callback_variant_;
}
private:
// TODO(wjwwood): switch to inheriting from std::variant (i.e. HelperT::variant_type) once
// inheriting from std::variant is realistic (maybe C++23?), see:
// http://www.open-std.org/jtc1/sc22/wg21/docs/papers/2020/p2162r0.html
// For now, compose the variant into this class as a private attribute.
typename HelperT::variant_type callback_variant_;
SubscribedTypeAllocator subscribed_type_allocator_;
SubscribedTypeDeleter subscribed_type_deleter_;
ROSMessageTypeAllocator ros_message_type_allocator_;
ROSMessageTypeDeleter ros_message_type_deleter_;
SerializedMessageAllocator serialized_message_allocator_;
SerializedMessageDeleter serialized_message_deleter_;
};
} // namespace rclcpp
#endif // RCLCPP__ANY_SUBSCRIPTION_CALLBACK_HPP_