ROS 2 rclcpp + rcl - humble  humble
ROS 2 C++ Client Library with ROS Client Library
any_subscription_callback.hpp
1 // Copyright 2014 Open Source Robotics Foundation, Inc.
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #ifndef RCLCPP__ANY_SUBSCRIPTION_CALLBACK_HPP_
16 #define RCLCPP__ANY_SUBSCRIPTION_CALLBACK_HPP_
17 
18 #include <functional>
19 #include <memory>
20 #include <stdexcept>
21 #include <type_traits>
22 #include <utility>
23 #include <variant> // NOLINT[build/include_order]
24 
25 #include "rosidl_runtime_cpp/traits.hpp"
26 #include "tracetools/tracetools.h"
27 #include "tracetools/utils.hpp"
28 
29 #include "rclcpp/allocator/allocator_common.hpp"
30 #include "rclcpp/detail/subscription_callback_type_helper.hpp"
31 #include "rclcpp/function_traits.hpp"
32 #include "rclcpp/message_info.hpp"
33 #include "rclcpp/serialized_message.hpp"
34 #include "rclcpp/type_adapter.hpp"
35 
36 
37 template<class>
38 inline constexpr bool always_false_v = false;
39 
40 namespace rclcpp
41 {
42 
43 namespace detail
44 {
45 
46 template<typename MessageT, typename AllocatorT>
48 {
49  using AllocTraits = allocator::AllocRebind<MessageT, AllocatorT>;
50  using Alloc = typename AllocTraits::allocator_type;
51  using Deleter = allocator::Deleter<Alloc, MessageT>;
52 };
53 
55 template<typename MessageT, typename AllocatorT>
57 {
59  using SubscribedType = typename rclcpp::TypeAdapter<MessageT>::custom_type;
61  using ROSMessageType = typename rclcpp::TypeAdapter<MessageT>::ros_message_type;
62 
63  using SubscribedMessageDeleter =
64  typename MessageDeleterHelper<SubscribedType, AllocatorT>::Deleter;
65  using ROSMessageDeleter =
66  typename MessageDeleterHelper<ROSMessageType, AllocatorT>::Deleter;
67  using SerializedMessageDeleter =
68  typename MessageDeleterHelper<rclcpp::SerializedMessage, AllocatorT>::Deleter;
69 
70  using ConstRefCallback =
71  std::function<void (const SubscribedType &)>;
72  using ConstRefROSMessageCallback =
73  std::function<void (const ROSMessageType &)>;
74  using ConstRefWithInfoCallback =
75  std::function<void (const SubscribedType &, const rclcpp::MessageInfo &)>;
76  using ConstRefWithInfoROSMessageCallback =
77  std::function<void (const ROSMessageType &, const rclcpp::MessageInfo &)>;
78  using ConstRefSerializedMessageCallback =
79  std::function<void (const rclcpp::SerializedMessage &)>;
80  using ConstRefSerializedMessageWithInfoCallback =
81  std::function<void (const rclcpp::SerializedMessage &, const rclcpp::MessageInfo &)>;
82 
83  using UniquePtrCallback =
84  std::function<void (std::unique_ptr<SubscribedType, SubscribedMessageDeleter>)>;
85  using UniquePtrROSMessageCallback =
86  std::function<void (std::unique_ptr<ROSMessageType, ROSMessageDeleter>)>;
87  using UniquePtrWithInfoCallback =
88  std::function<void (
89  std::unique_ptr<SubscribedType, SubscribedMessageDeleter>,
90  const rclcpp::MessageInfo &)>;
91  using UniquePtrWithInfoROSMessageCallback =
92  std::function<void (
93  std::unique_ptr<ROSMessageType, ROSMessageDeleter>,
94  const rclcpp::MessageInfo &)>;
95  using UniquePtrSerializedMessageCallback =
96  std::function<void (std::unique_ptr<rclcpp::SerializedMessage, SerializedMessageDeleter>)>;
97  using UniquePtrSerializedMessageWithInfoCallback =
98  std::function<void (
99  std::unique_ptr<rclcpp::SerializedMessage, SerializedMessageDeleter>,
100  const rclcpp::MessageInfo &)>;
101 
102  using SharedConstPtrCallback =
103  std::function<void (std::shared_ptr<const SubscribedType>)>;
104  using SharedConstPtrROSMessageCallback =
105  std::function<void (std::shared_ptr<const ROSMessageType>)>;
106  using SharedConstPtrWithInfoCallback =
107  std::function<void (
108  std::shared_ptr<const SubscribedType>,
109  const rclcpp::MessageInfo &)>;
110  using SharedConstPtrWithInfoROSMessageCallback =
111  std::function<void (
112  std::shared_ptr<const ROSMessageType>,
113  const rclcpp::MessageInfo &)>;
114  using SharedConstPtrSerializedMessageCallback =
115  std::function<void (std::shared_ptr<const rclcpp::SerializedMessage>)>;
116  using SharedConstPtrSerializedMessageWithInfoCallback =
117  std::function<void (
118  std::shared_ptr<const rclcpp::SerializedMessage>,
119  const rclcpp::MessageInfo &)>;
120 
121  using ConstRefSharedConstPtrCallback =
122  std::function<void (const std::shared_ptr<const SubscribedType> &)>;
123  using ConstRefSharedConstPtrROSMessageCallback =
124  std::function<void (const std::shared_ptr<const ROSMessageType> &)>;
125  using ConstRefSharedConstPtrWithInfoCallback =
126  std::function<void (
127  const std::shared_ptr<const SubscribedType> &,
128  const rclcpp::MessageInfo &)>;
129  using ConstRefSharedConstPtrWithInfoROSMessageCallback =
130  std::function<void (
131  const std::shared_ptr<const ROSMessageType> &,
132  const rclcpp::MessageInfo &)>;
133  using ConstRefSharedConstPtrSerializedMessageCallback =
134  std::function<void (const std::shared_ptr<const rclcpp::SerializedMessage> &)>;
135  using ConstRefSharedConstPtrSerializedMessageWithInfoCallback =
136  std::function<void (
137  const std::shared_ptr<const rclcpp::SerializedMessage> &,
138  const rclcpp::MessageInfo &)>;
139 
140  // Deprecated signatures:
141  using SharedPtrCallback =
142  std::function<void (std::shared_ptr<SubscribedType>)>;
143  using SharedPtrROSMessageCallback =
144  std::function<void (std::shared_ptr<ROSMessageType>)>;
145  using SharedPtrWithInfoCallback =
146  std::function<void (std::shared_ptr<SubscribedType>, const rclcpp::MessageInfo &)>;
147  using SharedPtrWithInfoROSMessageCallback =
148  std::function<void (
149  std::shared_ptr<ROSMessageType>,
150  const rclcpp::MessageInfo &)>;
151  using SharedPtrSerializedMessageCallback =
152  std::function<void (std::shared_ptr<rclcpp::SerializedMessage>)>;
153  using SharedPtrSerializedMessageWithInfoCallback =
154  std::function<void (std::shared_ptr<rclcpp::SerializedMessage>, const rclcpp::MessageInfo &)>;
155 };
156 
158 template<
159  typename MessageT,
160  typename AllocatorT,
162 >
164 
166 template<typename MessageT, typename AllocatorT>
167 struct AnySubscriptionCallbackHelper<MessageT, AllocatorT, false>
168 {
170 
171  using variant_type = std::variant<
172  typename CallbackTypes::ConstRefCallback,
173  typename CallbackTypes::ConstRefWithInfoCallback,
174  typename CallbackTypes::ConstRefSerializedMessageCallback,
175  typename CallbackTypes::ConstRefSerializedMessageWithInfoCallback,
176  typename CallbackTypes::UniquePtrCallback,
177  typename CallbackTypes::UniquePtrWithInfoCallback,
178  typename CallbackTypes::UniquePtrSerializedMessageCallback,
179  typename CallbackTypes::UniquePtrSerializedMessageWithInfoCallback,
180  typename CallbackTypes::SharedConstPtrCallback,
181  typename CallbackTypes::SharedConstPtrWithInfoCallback,
182  typename CallbackTypes::SharedConstPtrSerializedMessageCallback,
183  typename CallbackTypes::SharedConstPtrSerializedMessageWithInfoCallback,
184  typename CallbackTypes::ConstRefSharedConstPtrCallback,
185  typename CallbackTypes::ConstRefSharedConstPtrWithInfoCallback,
186  typename CallbackTypes::ConstRefSharedConstPtrSerializedMessageCallback,
187  typename CallbackTypes::ConstRefSharedConstPtrSerializedMessageWithInfoCallback,
188  typename CallbackTypes::SharedPtrCallback,
189  typename CallbackTypes::SharedPtrWithInfoCallback,
190  typename CallbackTypes::SharedPtrSerializedMessageCallback,
191  typename CallbackTypes::SharedPtrSerializedMessageWithInfoCallback
192  >;
193 };
194 
196 template<typename MessageT, typename AllocatorT>
197 struct AnySubscriptionCallbackHelper<MessageT, AllocatorT, true>
198 {
200 
201  using variant_type = std::variant<
202  typename CallbackTypes::ConstRefCallback,
203  typename CallbackTypes::ConstRefROSMessageCallback,
204  typename CallbackTypes::ConstRefWithInfoCallback,
205  typename CallbackTypes::ConstRefWithInfoROSMessageCallback,
206  typename CallbackTypes::ConstRefSerializedMessageCallback,
207  typename CallbackTypes::ConstRefSerializedMessageWithInfoCallback,
208  typename CallbackTypes::UniquePtrCallback,
209  typename CallbackTypes::UniquePtrROSMessageCallback,
210  typename CallbackTypes::UniquePtrWithInfoCallback,
211  typename CallbackTypes::UniquePtrWithInfoROSMessageCallback,
212  typename CallbackTypes::UniquePtrSerializedMessageCallback,
213  typename CallbackTypes::UniquePtrSerializedMessageWithInfoCallback,
214  typename CallbackTypes::SharedConstPtrCallback,
215  typename CallbackTypes::SharedConstPtrROSMessageCallback,
216  typename CallbackTypes::SharedConstPtrWithInfoCallback,
217  typename CallbackTypes::SharedConstPtrWithInfoROSMessageCallback,
218  typename CallbackTypes::SharedConstPtrSerializedMessageCallback,
219  typename CallbackTypes::SharedConstPtrSerializedMessageWithInfoCallback,
220  typename CallbackTypes::ConstRefSharedConstPtrCallback,
221  typename CallbackTypes::ConstRefSharedConstPtrROSMessageCallback,
222  typename CallbackTypes::ConstRefSharedConstPtrWithInfoCallback,
223  typename CallbackTypes::ConstRefSharedConstPtrWithInfoROSMessageCallback,
224  typename CallbackTypes::ConstRefSharedConstPtrSerializedMessageCallback,
225  typename CallbackTypes::ConstRefSharedConstPtrSerializedMessageWithInfoCallback,
226  typename CallbackTypes::SharedPtrCallback,
227  typename CallbackTypes::SharedPtrROSMessageCallback,
228  typename CallbackTypes::SharedPtrWithInfoCallback,
229  typename CallbackTypes::SharedPtrWithInfoROSMessageCallback,
230  typename CallbackTypes::SharedPtrSerializedMessageCallback,
231  typename CallbackTypes::SharedPtrSerializedMessageWithInfoCallback
232  >;
233 };
234 
235 } // namespace detail
236 
237 template<
238  typename MessageT,
239  typename AllocatorT = std::allocator<void>
240 >
242 {
243 private:
245  using SubscribedType = typename rclcpp::TypeAdapter<MessageT>::custom_type;
247  using ROSMessageType = typename rclcpp::TypeAdapter<MessageT>::ros_message_type;
248 
250 
253  using SubscribedTypeAllocatorTraits = typename SubscribedTypeDeleterHelper::AllocTraits;
254  using SubscribedTypeAllocator = typename SubscribedTypeDeleterHelper::Alloc;
255  using SubscribedTypeDeleter = typename SubscribedTypeDeleterHelper::Deleter;
256 
259  using ROSMessageTypeAllocatorTraits = typename ROSMessageTypeDeleterHelper::AllocTraits;
260  using ROSMessageTypeAllocator = typename ROSMessageTypeDeleterHelper::Alloc;
261  using ROSMessageTypeDeleter = typename ROSMessageTypeDeleterHelper::Deleter;
262 
265  using SerializedMessageAllocatorTraits = typename SerializedMessageDeleterHelper::AllocTraits;
266  using SerializedMessageAllocator = typename SerializedMessageDeleterHelper::Alloc;
267  using SerializedMessageDeleter = typename SerializedMessageDeleterHelper::Deleter;
268 
269  // See AnySubscriptionCallbackPossibleTypes for the types of these.
271 
272  using ConstRefCallback =
273  typename CallbackTypes::ConstRefCallback;
274  using ConstRefROSMessageCallback =
275  typename CallbackTypes::ConstRefROSMessageCallback;
276  using ConstRefWithInfoCallback =
277  typename CallbackTypes::ConstRefWithInfoCallback;
278  using ConstRefWithInfoROSMessageCallback =
279  typename CallbackTypes::ConstRefWithInfoROSMessageCallback;
280  using ConstRefSerializedMessageCallback =
281  typename CallbackTypes::ConstRefSerializedMessageCallback;
282  using ConstRefSerializedMessageWithInfoCallback =
283  typename CallbackTypes::ConstRefSerializedMessageWithInfoCallback;
284  using UniquePtrCallback =
285  typename CallbackTypes::UniquePtrCallback;
286  using UniquePtrROSMessageCallback =
287  typename CallbackTypes::UniquePtrROSMessageCallback;
288  using UniquePtrWithInfoCallback =
289  typename CallbackTypes::UniquePtrWithInfoCallback;
290  using UniquePtrWithInfoROSMessageCallback =
291  typename CallbackTypes::UniquePtrWithInfoROSMessageCallback;
292  using UniquePtrSerializedMessageCallback =
293  typename CallbackTypes::UniquePtrSerializedMessageCallback;
294  using UniquePtrSerializedMessageWithInfoCallback =
295  typename CallbackTypes::UniquePtrSerializedMessageWithInfoCallback;
296  using SharedConstPtrCallback =
297  typename CallbackTypes::SharedConstPtrCallback;
298  using SharedConstPtrROSMessageCallback =
299  typename CallbackTypes::SharedConstPtrROSMessageCallback;
300  using SharedConstPtrWithInfoCallback =
301  typename CallbackTypes::SharedConstPtrWithInfoCallback;
302  using SharedConstPtrWithInfoROSMessageCallback =
303  typename CallbackTypes::SharedConstPtrWithInfoROSMessageCallback;
304  using SharedConstPtrSerializedMessageCallback =
305  typename CallbackTypes::SharedConstPtrSerializedMessageCallback;
306  using SharedConstPtrSerializedMessageWithInfoCallback =
307  typename CallbackTypes::SharedConstPtrSerializedMessageWithInfoCallback;
308  using ConstRefSharedConstPtrCallback =
309  typename CallbackTypes::ConstRefSharedConstPtrCallback;
310  using ConstRefSharedConstPtrROSMessageCallback =
311  typename CallbackTypes::ConstRefSharedConstPtrROSMessageCallback;
312  using ConstRefSharedConstPtrWithInfoCallback =
313  typename CallbackTypes::ConstRefSharedConstPtrWithInfoCallback;
314  using ConstRefSharedConstPtrWithInfoROSMessageCallback =
315  typename CallbackTypes::ConstRefSharedConstPtrWithInfoROSMessageCallback;
316  using ConstRefSharedConstPtrSerializedMessageCallback =
317  typename CallbackTypes::ConstRefSharedConstPtrSerializedMessageCallback;
318  using ConstRefSharedConstPtrSerializedMessageWithInfoCallback =
319  typename CallbackTypes::ConstRefSharedConstPtrSerializedMessageWithInfoCallback;
320  using SharedPtrCallback =
321  typename CallbackTypes::SharedPtrCallback;
322  using SharedPtrROSMessageCallback =
323  typename CallbackTypes::SharedPtrROSMessageCallback;
324  using SharedPtrWithInfoCallback =
325  typename CallbackTypes::SharedPtrWithInfoCallback;
326  using SharedPtrWithInfoROSMessageCallback =
327  typename CallbackTypes::SharedPtrWithInfoROSMessageCallback;
328  using SharedPtrSerializedMessageCallback =
329  typename CallbackTypes::SharedPtrSerializedMessageCallback;
330  using SharedPtrSerializedMessageWithInfoCallback =
331  typename CallbackTypes::SharedPtrSerializedMessageWithInfoCallback;
332 
333  template<typename T>
334  struct NotNull
335  {
336  NotNull(const T * pointer_in, const char * msg)
337  : pointer(pointer_in)
338  {
339  if (pointer == nullptr) {
340  throw std::invalid_argument(msg);
341  }
342  }
343 
344  const T * pointer;
345  };
346 
347 public:
348  explicit
349  AnySubscriptionCallback(const AllocatorT & allocator = AllocatorT()) // NOLINT[runtime/explicit]
350  : subscribed_type_allocator_(allocator),
351  ros_message_type_allocator_(allocator)
352  {
353  allocator::set_allocator_for_deleter(&subscribed_type_deleter_, &subscribed_type_allocator_);
354  allocator::set_allocator_for_deleter(&ros_message_type_deleter_, &ros_message_type_allocator_);
355  }
356 
358 
360 
365  template<typename CallbackT>
367  set(CallbackT callback)
368  {
369  // Use the SubscriptionCallbackTypeHelper to determine the actual type of
370  // the CallbackT, in terms of std::function<...>, which does not happen
371  // automatically with lambda functions in cases where the arguments can be
372  // converted to one another, e.g. shared_ptr and unique_ptr.
374 
375  // Determine if the given CallbackT is a deprecated signature or not.
376  constexpr auto is_deprecated =
378  typename scbth::callback_type,
379  std::function<void(std::shared_ptr<MessageT>)>
380  >::value
381  ||
383  typename scbth::callback_type,
384  std::function<void(std::shared_ptr<MessageT>, const rclcpp::MessageInfo &)>
385  >::value;
386 
387  // Use the discovered type to force the type of callback when assigning
388  // into the variant.
389  if constexpr (is_deprecated) {
390  // If deprecated, call sub-routine that is deprecated.
391  set_deprecated(static_cast<typename scbth::callback_type>(callback));
392  } else {
393  // Otherwise just assign it.
394  callback_variant_ = static_cast<typename scbth::callback_type>(callback);
395  }
396 
397  // Return copy of self for easier testing, normally will be compiled out.
398  return *this;
399  }
400 
402  template<typename SetT>
403 #if !defined(RCLCPP_AVOID_DEPRECATIONS_FOR_UNIT_TESTS)
404  // suppress deprecation warnings in `test_any_subscription_callback.cpp`
405  [[deprecated("use 'void(std::shared_ptr<const MessageT>)' instead")]]
406 #endif
407  void
408  set_deprecated(std::function<void(std::shared_ptr<SetT>)> callback)
409  {
410  callback_variant_ = callback;
411  }
412 
414  template<typename SetT>
415 #if !defined(RCLCPP_AVOID_DEPRECATIONS_FOR_UNIT_TESTS)
416  // suppress deprecation warnings in `test_any_subscription_callback.cpp`
417  [[deprecated(
418  "use 'void(std::shared_ptr<const MessageT>, const rclcpp::MessageInfo &)' instead"
419  )]]
420 #endif
421  void
422  set_deprecated(std::function<void(std::shared_ptr<SetT>, const rclcpp::MessageInfo &)> callback)
423  {
424  callback_variant_ = callback;
425  }
426 
427  std::unique_ptr<ROSMessageType, ROSMessageTypeDeleter>
428  create_ros_unique_ptr_from_ros_shared_ptr_message(
429  const std::shared_ptr<const ROSMessageType> & message)
430  {
431  auto ptr = ROSMessageTypeAllocatorTraits::allocate(ros_message_type_allocator_, 1);
432  ROSMessageTypeAllocatorTraits::construct(ros_message_type_allocator_, ptr, *message);
433  return std::unique_ptr<ROSMessageType, ROSMessageTypeDeleter>(ptr, ros_message_type_deleter_);
434  }
435 
436  std::unique_ptr<rclcpp::SerializedMessage, SerializedMessageDeleter>
437  create_serialized_message_unique_ptr_from_shared_ptr(
438  const std::shared_ptr<const rclcpp::SerializedMessage> & serialized_message)
439  {
440  auto ptr = SerializedMessageAllocatorTraits::allocate(serialized_message_allocator_, 1);
441  SerializedMessageAllocatorTraits::construct(
442  serialized_message_allocator_, ptr, *serialized_message);
443  return std::unique_ptr<
445  SerializedMessageDeleter
446  >(ptr, serialized_message_deleter_);
447  }
448 
449  std::unique_ptr<SubscribedType, SubscribedTypeDeleter>
450  create_custom_unique_ptr_from_custom_shared_ptr_message(
451  const std::shared_ptr<const SubscribedType> & message)
452  {
453  auto ptr = SubscribedTypeAllocatorTraits::allocate(subscribed_type_allocator_, 1);
454  SubscribedTypeAllocatorTraits::construct(subscribed_type_allocator_, ptr, *message);
455  return std::unique_ptr<SubscribedType, SubscribedTypeDeleter>(ptr, subscribed_type_deleter_);
456  }
457 
458  std::unique_ptr<SubscribedType, SubscribedTypeDeleter>
459  convert_ros_message_to_custom_type_unique_ptr(const ROSMessageType & msg)
460  {
462  auto ptr = SubscribedTypeAllocatorTraits::allocate(subscribed_type_allocator_, 1);
463  SubscribedTypeAllocatorTraits::construct(subscribed_type_allocator_, ptr);
465  return std::unique_ptr<SubscribedType, SubscribedTypeDeleter>(ptr, subscribed_type_deleter_);
466  } else {
467  throw std::runtime_error(
468  "convert_ros_message_to_custom_type_unique_ptr "
469  "unexpectedly called without TypeAdapter");
470  }
471  }
472 
473  std::unique_ptr<ROSMessageType, ROSMessageTypeDeleter>
474  convert_custom_type_to_ros_message_unique_ptr(const SubscribedType & msg)
475  {
477  auto ptr = ROSMessageTypeAllocatorTraits::allocate(ros_message_type_allocator_, 1);
478  ROSMessageTypeAllocatorTraits::construct(ros_message_type_allocator_, ptr);
480  return std::unique_ptr<ROSMessageType, ROSMessageTypeDeleter>(ptr, ros_message_type_deleter_);
481  } else {
482  static_assert(
483  !sizeof(MessageT *),
484  "convert_custom_type_to_ros_message_unique_ptr() "
485  "unexpectedly called without specialized TypeAdapter");
486  }
487  }
488 
489  // Dispatch when input is a ros message and the output could be anything.
490  void
491  dispatch(
492  std::shared_ptr<ROSMessageType> message,
493  const rclcpp::MessageInfo & message_info)
494  {
495  TRACEPOINT(callback_start, static_cast<const void *>(this), false);
496  // Check if the variant is "unset", throw if it is.
497  if (callback_variant_.index() == 0) {
498  if (std::get<0>(callback_variant_) == nullptr) {
499  // This can happen if it is default initialized, or if it is assigned nullptr.
500  throw std::runtime_error("dispatch called on an unset AnySubscriptionCallback");
501  }
502  }
503  // Dispatch.
504  std::visit(
505  [&message, &message_info, this](auto && callback) {
506  using T = std::decay_t<decltype(callback)>;
507  static constexpr bool is_ta = rclcpp::TypeAdapter<MessageT>::is_specialized::value;
508 
509  // conditions for output is custom message
510  if constexpr (is_ta && std::is_same_v<T, ConstRefCallback>) {
511  // TODO(wjwwood): consider avoiding heap allocation for small messages
512  // maybe something like:
513  // if constexpr (rosidl_generator_traits::has_fixed_size<T> && sizeof(T) < N) {
514  // ... on stack
515  // }
516  auto local_message = convert_ros_message_to_custom_type_unique_ptr(*message);
517  callback(*local_message);
518  } else if constexpr (is_ta && std::is_same_v<T, ConstRefWithInfoCallback>) { // NOLINT
519  auto local_message = convert_ros_message_to_custom_type_unique_ptr(*message);
520  callback(*local_message, message_info);
521  } else if constexpr (is_ta && std::is_same_v<T, UniquePtrCallback>) {
522  callback(convert_ros_message_to_custom_type_unique_ptr(*message));
523  } else if constexpr (is_ta && std::is_same_v<T, UniquePtrWithInfoCallback>) {
524  callback(convert_ros_message_to_custom_type_unique_ptr(*message), message_info);
525  } else if constexpr ( // NOLINT[readability/braces]
526  is_ta && (
527  std::is_same_v<T, SharedConstPtrCallback>||
528  std::is_same_v<T, ConstRefSharedConstPtrCallback>||
529  std::is_same_v<T, SharedPtrCallback>
530  ))
531  {
532  callback(convert_ros_message_to_custom_type_unique_ptr(*message));
533  } else if constexpr ( // NOLINT[readability/braces]
534  is_ta && (
535  std::is_same_v<T, SharedConstPtrWithInfoCallback>||
536  std::is_same_v<T, ConstRefSharedConstPtrWithInfoCallback>||
537  std::is_same_v<T, SharedPtrWithInfoCallback>
538  ))
539  {
540  callback(convert_ros_message_to_custom_type_unique_ptr(*message), message_info);
541  }
542  // conditions for output is ros message
543  else if constexpr (std::is_same_v<T, ConstRefROSMessageCallback>) { // NOLINT
544  callback(*message);
545  } else if constexpr (std::is_same_v<T, ConstRefWithInfoROSMessageCallback>) {
546  callback(*message, message_info);
547  } else if constexpr (std::is_same_v<T, UniquePtrROSMessageCallback>) {
548  callback(create_ros_unique_ptr_from_ros_shared_ptr_message(message));
549  } else if constexpr (std::is_same_v<T, UniquePtrWithInfoROSMessageCallback>) {
550  callback(create_ros_unique_ptr_from_ros_shared_ptr_message(message), message_info);
551  } else if constexpr ( // NOLINT[readability/braces]
552  std::is_same_v<T, SharedConstPtrROSMessageCallback>||
553  std::is_same_v<T, ConstRefSharedConstPtrROSMessageCallback>||
554  std::is_same_v<T, SharedPtrROSMessageCallback>)
555  {
556  callback(message);
557  } else if constexpr ( // NOLINT[readability/braces]
558  std::is_same_v<T, SharedConstPtrWithInfoROSMessageCallback>||
559  std::is_same_v<T, ConstRefSharedConstPtrWithInfoROSMessageCallback>||
560  std::is_same_v<T, SharedPtrWithInfoROSMessageCallback>)
561  {
562  callback(message, message_info);
563  }
564  // condition to catch SerializedMessage types
565  else if constexpr ( // NOLINT[readability/braces]
566  std::is_same_v<T, ConstRefSerializedMessageCallback>||
567  std::is_same_v<T, ConstRefSerializedMessageWithInfoCallback>||
568  std::is_same_v<T, UniquePtrSerializedMessageCallback>||
569  std::is_same_v<T, UniquePtrSerializedMessageWithInfoCallback>||
570  std::is_same_v<T, SharedConstPtrSerializedMessageCallback>||
571  std::is_same_v<T, SharedConstPtrSerializedMessageWithInfoCallback>||
572  std::is_same_v<T, ConstRefSharedConstPtrSerializedMessageCallback>||
573  std::is_same_v<T, ConstRefSharedConstPtrSerializedMessageWithInfoCallback>||
574  std::is_same_v<T, SharedPtrSerializedMessageCallback>||
575  std::is_same_v<T, SharedPtrSerializedMessageWithInfoCallback>)
576  {
577  throw std::runtime_error(
578  "Cannot dispatch std::shared_ptr<ROSMessageType> message "
579  "to rclcpp::SerializedMessage");
580  }
581  // condition to catch unhandled callback types
582  else { // NOLINT[readability/braces]
583  static_assert(always_false_v<T>, "unhandled callback type");
584  }
585  }, callback_variant_);
586  TRACEPOINT(callback_end, static_cast<const void *>(this));
587  }
588 
589  // Dispatch when input is a serialized message and the output could be anything.
590  void
591  dispatch(
592  std::shared_ptr<rclcpp::SerializedMessage> serialized_message,
593  const rclcpp::MessageInfo & message_info)
594  {
595  TRACEPOINT(callback_start, static_cast<const void *>(this), false);
596  // Check if the variant is "unset", throw if it is.
597  if (callback_variant_.index() == 0) {
598  if (std::get<0>(callback_variant_) == nullptr) {
599  // This can happen if it is default initialized, or if it is assigned nullptr.
600  throw std::runtime_error("dispatch called on an unset AnySubscriptionCallback");
601  }
602  }
603  // Dispatch.
604  std::visit(
605  [&serialized_message, &message_info, this](auto && callback) {
606  using T = std::decay_t<decltype(callback)>;
607 
608  // condition to catch SerializedMessage types
609  if constexpr (std::is_same_v<T, ConstRefSerializedMessageCallback>) {
610  callback(*serialized_message);
611  } else if constexpr (std::is_same_v<T, ConstRefSerializedMessageWithInfoCallback>) {
612  callback(*serialized_message, message_info);
613  } else if constexpr (std::is_same_v<T, UniquePtrSerializedMessageCallback>) {
614  callback(create_serialized_message_unique_ptr_from_shared_ptr(serialized_message));
615  } else if constexpr (std::is_same_v<T, UniquePtrSerializedMessageWithInfoCallback>) {
616  callback(
617  create_serialized_message_unique_ptr_from_shared_ptr(serialized_message),
618  message_info);
619  } else if constexpr ( // NOLINT[readability/braces]
620  std::is_same_v<T, SharedConstPtrSerializedMessageCallback>||
621  std::is_same_v<T, ConstRefSharedConstPtrSerializedMessageCallback>||
622  std::is_same_v<T, SharedPtrSerializedMessageCallback>)
623  {
624  callback(create_serialized_message_unique_ptr_from_shared_ptr(serialized_message));
625  } else if constexpr ( // NOLINT[readability/braces]
626  std::is_same_v<T, SharedConstPtrSerializedMessageWithInfoCallback>||
627  std::is_same_v<T, ConstRefSharedConstPtrSerializedMessageWithInfoCallback>||
628  std::is_same_v<T, SharedPtrSerializedMessageWithInfoCallback>)
629  {
630  callback(
631  create_serialized_message_unique_ptr_from_shared_ptr(serialized_message),
632  message_info);
633  }
634  // conditions for output anything else
635  else if constexpr ( // NOLINT[whitespace/newline]
636  std::is_same_v<T, ConstRefCallback>||
637  std::is_same_v<T, ConstRefROSMessageCallback>||
638  std::is_same_v<T, ConstRefWithInfoCallback>||
639  std::is_same_v<T, ConstRefWithInfoROSMessageCallback>||
640  std::is_same_v<T, UniquePtrCallback>||
641  std::is_same_v<T, UniquePtrROSMessageCallback>||
642  std::is_same_v<T, UniquePtrWithInfoCallback>||
643  std::is_same_v<T, UniquePtrWithInfoROSMessageCallback>||
644  std::is_same_v<T, SharedConstPtrCallback>||
645  std::is_same_v<T, SharedConstPtrROSMessageCallback>||
646  std::is_same_v<T, SharedConstPtrWithInfoCallback>||
647  std::is_same_v<T, SharedConstPtrWithInfoROSMessageCallback>||
648  std::is_same_v<T, ConstRefSharedConstPtrCallback>||
649  std::is_same_v<T, ConstRefSharedConstPtrROSMessageCallback>||
650  std::is_same_v<T, ConstRefSharedConstPtrWithInfoCallback>||
651  std::is_same_v<T, ConstRefSharedConstPtrWithInfoROSMessageCallback>||
652  std::is_same_v<T, SharedPtrCallback>||
653  std::is_same_v<T, SharedPtrROSMessageCallback>||
654  std::is_same_v<T, SharedPtrWithInfoCallback>||
655  std::is_same_v<T, SharedPtrWithInfoROSMessageCallback>)
656  {
657  throw std::runtime_error(
658  "cannot dispatch rclcpp::SerializedMessage to "
659  "non-rclcpp::SerializedMessage callbacks");
660  }
661  // condition to catch unhandled callback types
662  else { // NOLINT[readability/braces]
663  static_assert(always_false_v<T>, "unhandled callback type");
664  }
665  }, callback_variant_);
666  TRACEPOINT(callback_end, static_cast<const void *>(this));
667  }
668 
669  void
670  dispatch_intra_process(
671  std::shared_ptr<const SubscribedType> message,
672  const rclcpp::MessageInfo & message_info)
673  {
674  TRACEPOINT(callback_start, static_cast<const void *>(this), true);
675  // Check if the variant is "unset", throw if it is.
676  if (callback_variant_.index() == 0) {
677  if (std::get<0>(callback_variant_) == nullptr) {
678  // This can happen if it is default initialized, or if it is assigned nullptr.
679  throw std::runtime_error("dispatch called on an unset AnySubscriptionCallback");
680  }
681  }
682  // Dispatch.
683  std::visit(
684  [&message, &message_info, this](auto && callback) {
685  using T = std::decay_t<decltype(callback)>;
686  static constexpr bool is_ta = rclcpp::TypeAdapter<MessageT>::is_specialized::value;
687 
688  // conditions for custom type
689  if constexpr (is_ta && std::is_same_v<T, ConstRefCallback>) {
690  callback(*message);
691  } else if constexpr (is_ta && std::is_same_v<T, ConstRefWithInfoCallback>) { // NOLINT
692  callback(*message, message_info);
693  } else if constexpr ( // NOLINT[readability/braces]
694  is_ta && (
695  std::is_same_v<T, UniquePtrCallback>||
696  std::is_same_v<T, SharedPtrCallback>
697  ))
698  {
699  callback(create_custom_unique_ptr_from_custom_shared_ptr_message(message));
700  } else if constexpr ( // NOLINT[readability/braces]
701  is_ta && (
702  std::is_same_v<T, UniquePtrWithInfoCallback>||
703  std::is_same_v<T, SharedPtrWithInfoCallback>
704  ))
705  {
706  callback(create_custom_unique_ptr_from_custom_shared_ptr_message(message), message_info);
707  } else if constexpr ( // NOLINT[readability/braces]
708  is_ta && (
709  std::is_same_v<T, SharedConstPtrCallback>||
710  std::is_same_v<T, ConstRefSharedConstPtrCallback>
711  ))
712  {
713  callback(message);
714  } else if constexpr ( // NOLINT[readability/braces]
715  is_ta && (
716  std::is_same_v<T, SharedConstPtrWithInfoCallback>||
717  std::is_same_v<T, ConstRefSharedConstPtrWithInfoCallback>
718  ))
719  {
720  callback(message, message_info);
721  }
722  // conditions for ros message type
723  else if constexpr (std::is_same_v<T, ConstRefROSMessageCallback>) { // NOLINT[readability/braces]
724  if constexpr (is_ta) {
725  auto local = convert_custom_type_to_ros_message_unique_ptr(*message);
726  callback(*local);
727  } else {
728  callback(*message);
729  }
730  } else if constexpr (std::is_same_v<T, ConstRefWithInfoROSMessageCallback>) { // NOLINT[readability/braces]
731  if constexpr (is_ta) {
732  auto local = convert_custom_type_to_ros_message_unique_ptr(*message);
733  callback(*local, message_info);
734  } else {
735  callback(*message, message_info);
736  }
737  } else if constexpr ( // NOLINT[readability/braces]
738  std::is_same_v<T, UniquePtrROSMessageCallback>||
739  std::is_same_v<T, SharedPtrROSMessageCallback>)
740  {
741  if constexpr (is_ta) {
742  callback(convert_custom_type_to_ros_message_unique_ptr(*message));
743  } else {
744  callback(create_ros_unique_ptr_from_ros_shared_ptr_message(message));
745  }
746  } else if constexpr ( // NOLINT[readability/braces]
747  std::is_same_v<T, UniquePtrWithInfoROSMessageCallback>||
748  std::is_same_v<T, SharedPtrWithInfoROSMessageCallback>)
749  {
750  if constexpr (is_ta) {
751  callback(convert_custom_type_to_ros_message_unique_ptr(*message), message_info);
752  } else {
753  callback(create_ros_unique_ptr_from_ros_shared_ptr_message(message), message_info);
754  }
755  } else if constexpr ( // NOLINT[readability/braces]
756  std::is_same_v<T, SharedConstPtrROSMessageCallback>||
757  std::is_same_v<T, ConstRefSharedConstPtrROSMessageCallback>)
758  {
759  if constexpr (is_ta) {
760  callback(convert_custom_type_to_ros_message_unique_ptr(*message));
761  } else {
762  callback(message);
763  }
764  } else if constexpr ( // NOLINT[readability/braces]
765  std::is_same_v<T, SharedConstPtrWithInfoROSMessageCallback>||
766  std::is_same_v<T, ConstRefSharedConstPtrWithInfoROSMessageCallback>)
767  {
768  if constexpr (is_ta) {
769  callback(convert_custom_type_to_ros_message_unique_ptr(*message), message_info);
770  } else {
771  callback(message, message_info);
772  }
773  }
774  // condition to catch SerializedMessage types
775  else if constexpr ( // NOLINT[readability/braces]
776  std::is_same_v<T, ConstRefSerializedMessageCallback>||
777  std::is_same_v<T, ConstRefSerializedMessageWithInfoCallback>||
778  std::is_same_v<T, UniquePtrSerializedMessageCallback>||
779  std::is_same_v<T, UniquePtrSerializedMessageWithInfoCallback>||
780  std::is_same_v<T, SharedConstPtrSerializedMessageCallback>||
781  std::is_same_v<T, SharedConstPtrSerializedMessageWithInfoCallback>||
782  std::is_same_v<T, ConstRefSharedConstPtrSerializedMessageCallback>||
783  std::is_same_v<T, ConstRefSharedConstPtrSerializedMessageWithInfoCallback>||
784  std::is_same_v<T, SharedPtrSerializedMessageCallback>||
785  std::is_same_v<T, SharedPtrSerializedMessageWithInfoCallback>)
786  {
787  throw std::runtime_error(
788  "Cannot dispatch std::shared_ptr<const ROSMessageType> message "
789  "to rclcpp::SerializedMessage");
790  }
791  // condition to catch unhandled callback types
792  else { // NOLINT[readability/braces]
793  static_assert(always_false_v<T>, "unhandled callback type");
794  }
795  }, callback_variant_);
796  TRACEPOINT(callback_end, static_cast<const void *>(this));
797  }
798 
799  void
800  dispatch_intra_process(
801  std::unique_ptr<SubscribedType, SubscribedTypeDeleter> message,
802  const rclcpp::MessageInfo & message_info)
803  {
804  TRACEPOINT(callback_start, static_cast<const void *>(this), true);
805  // Check if the variant is "unset", throw if it is.
806  if (callback_variant_.index() == 0) {
807  if (std::get<0>(callback_variant_) == nullptr) {
808  // This can happen if it is default initialized, or if it is assigned nullptr.
809  throw std::runtime_error("dispatch called on an unset AnySubscriptionCallback");
810  }
811  }
812  // Dispatch.
813  std::visit(
814  [&message, &message_info, this](auto && callback) {
815  // clang complains that 'this' lambda capture is unused, which is true
816  // in *some* specializations of this template, but not others. Just
817  // quiet it down.
818  (void)this;
819 
820  using T = std::decay_t<decltype(callback)>;
821  static constexpr bool is_ta = rclcpp::TypeAdapter<MessageT>::is_specialized::value;
822 
823  // conditions for custom type
824  if constexpr (is_ta && std::is_same_v<T, ConstRefCallback>) {
825  callback(*message);
826  } else if constexpr (is_ta && std::is_same_v<T, ConstRefWithInfoCallback>) { // NOLINT
827  callback(*message, message_info);
828  } else if constexpr ( // NOLINT[readability/braces]
829  is_ta && (
830  std::is_same_v<T, UniquePtrCallback>||
831  std::is_same_v<T, SharedPtrCallback>))
832  {
833  callback(std::move(message));
834  } else if constexpr ( // NOLINT[readability/braces]
835  is_ta && (
836  std::is_same_v<T, UniquePtrWithInfoCallback>||
837  std::is_same_v<T, SharedPtrWithInfoCallback>
838  ))
839  {
840  callback(std::move(message), message_info);
841  } else if constexpr ( // NOLINT[readability/braces]
842  is_ta && (
843  std::is_same_v<T, SharedConstPtrCallback>||
844  std::is_same_v<T, ConstRefSharedConstPtrCallback>
845  ))
846  {
847  callback(std::move(message));
848  } else if constexpr ( // NOLINT[readability/braces]
849  is_ta && (
850  std::is_same_v<T, SharedConstPtrWithInfoCallback>||
851  std::is_same_v<T, ConstRefSharedConstPtrWithInfoCallback>
852  ))
853  {
854  callback(std::move(message), message_info);
855  }
856  // conditions for ros message type
857  else if constexpr (std::is_same_v<T, ConstRefROSMessageCallback>) { // NOLINT[readability/braces]
858  if constexpr (is_ta) {
859  auto local = convert_custom_type_to_ros_message_unique_ptr(*message);
860  callback(*local);
861  } else {
862  callback(*message);
863  }
864  } else if constexpr (std::is_same_v<T, ConstRefWithInfoROSMessageCallback>) { // NOLINT[readability/braces]
865  if constexpr (is_ta) {
866  auto local = convert_custom_type_to_ros_message_unique_ptr(*message);
867  callback(*local, message_info);
868  } else {
869  callback(*message, message_info);
870  }
871  } else if constexpr ( // NOLINT[readability/braces]
872  std::is_same_v<T, UniquePtrROSMessageCallback>||
873  std::is_same_v<T, SharedPtrROSMessageCallback>)
874  {
875  if constexpr (is_ta) {
876  callback(convert_custom_type_to_ros_message_unique_ptr(*message));
877  } else {
878  callback(std::move(message));
879  }
880  } else if constexpr ( // NOLINT[readability/braces]
881  std::is_same_v<T, UniquePtrWithInfoROSMessageCallback>||
882  std::is_same_v<T, SharedPtrWithInfoROSMessageCallback>)
883  {
884  if constexpr (is_ta) {
885  callback(convert_custom_type_to_ros_message_unique_ptr(*message), message_info);
886  } else {
887  callback(std::move(message), message_info);
888  }
889  } else if constexpr ( // NOLINT[readability/braces]
890  std::is_same_v<T, SharedConstPtrROSMessageCallback>||
891  std::is_same_v<T, ConstRefSharedConstPtrROSMessageCallback>)
892  {
893  if constexpr (is_ta) {
894  callback(convert_custom_type_to_ros_message_unique_ptr(*message));
895  } else {
896  callback(std::move(message));
897  }
898  } else if constexpr ( // NOLINT[readability/braces]
899  std::is_same_v<T, SharedConstPtrWithInfoROSMessageCallback>||
900  std::is_same_v<T, ConstRefSharedConstPtrWithInfoROSMessageCallback>)
901  {
902  if constexpr (is_ta) {
903  callback(convert_custom_type_to_ros_message_unique_ptr(*message), message_info);
904  } else {
905  callback(std::move(message), message_info);
906  }
907  }
908  // condition to catch SerializedMessage types
909  else if constexpr ( // NOLINT[readability/braces]
910  std::is_same_v<T, ConstRefSerializedMessageCallback>||
911  std::is_same_v<T, ConstRefSerializedMessageWithInfoCallback>||
912  std::is_same_v<T, UniquePtrSerializedMessageCallback>||
913  std::is_same_v<T, UniquePtrSerializedMessageWithInfoCallback>||
914  std::is_same_v<T, SharedConstPtrSerializedMessageCallback>||
915  std::is_same_v<T, SharedConstPtrSerializedMessageWithInfoCallback>||
916  std::is_same_v<T, ConstRefSharedConstPtrSerializedMessageCallback>||
917  std::is_same_v<T, ConstRefSharedConstPtrSerializedMessageWithInfoCallback>||
918  std::is_same_v<T, SharedPtrSerializedMessageCallback>||
919  std::is_same_v<T, SharedPtrSerializedMessageWithInfoCallback>)
920  {
921  throw std::runtime_error(
922  "Cannot dispatch std::unique_ptr<ROSMessageType, ROSMessageTypeDeleter> message "
923  "to rclcpp::SerializedMessage");
924  }
925  // condition to catch unhandled callback types
926  else { // NOLINT[readability/braces]
927  static_assert(always_false_v<T>, "unhandled callback type");
928  }
929  }, callback_variant_);
930  TRACEPOINT(callback_end, static_cast<const void *>(this));
931  }
932 
933  constexpr
934  bool
935  use_take_shared_method() const
936  {
937  return
938  std::holds_alternative<SharedConstPtrCallback>(callback_variant_) ||
939  std::holds_alternative<SharedConstPtrWithInfoCallback>(callback_variant_) ||
940  std::holds_alternative<ConstRefSharedConstPtrCallback>(callback_variant_) ||
941  std::holds_alternative<ConstRefSharedConstPtrWithInfoCallback>(callback_variant_);
942  }
943 
944  constexpr
945  bool
946  is_serialized_message_callback() const
947  {
948  return
949  std::holds_alternative<ConstRefSerializedMessageCallback>(callback_variant_) ||
950  std::holds_alternative<UniquePtrSerializedMessageCallback>(callback_variant_) ||
951  std::holds_alternative<SharedConstPtrSerializedMessageCallback>(callback_variant_) ||
952  std::holds_alternative<ConstRefSharedConstPtrSerializedMessageCallback>(callback_variant_) ||
953  std::holds_alternative<SharedPtrSerializedMessageCallback>(callback_variant_) ||
954  std::holds_alternative<ConstRefSerializedMessageWithInfoCallback>(callback_variant_) ||
955  std::holds_alternative<UniquePtrSerializedMessageWithInfoCallback>(callback_variant_) ||
956  std::holds_alternative<SharedConstPtrSerializedMessageWithInfoCallback>(callback_variant_) ||
957  std::holds_alternative<ConstRefSharedConstPtrSerializedMessageWithInfoCallback>(
958  callback_variant_) ||
959  std::holds_alternative<SharedPtrSerializedMessageWithInfoCallback>(callback_variant_);
960  }
961 
962  void
963  register_callback_for_tracing()
964  {
965 #ifndef TRACETOOLS_DISABLED
966  std::visit(
967  [this](auto && callback) {
968  TRACEPOINT(
969  rclcpp_callback_register,
970  static_cast<const void *>(this),
971  tracetools::get_symbol(callback));
972  }, callback_variant_);
973 #endif // TRACETOOLS_DISABLED
974  }
975 
976  typename HelperT::variant_type &
977  get_variant()
978  {
979  return callback_variant_;
980  }
981 
982  const typename HelperT::variant_type &
983  get_variant() const
984  {
985  return callback_variant_;
986  }
987 
988 private:
989  // TODO(wjwwood): switch to inheriting from std::variant (i.e. HelperT::variant_type) once
990  // inheriting from std::variant is realistic (maybe C++23?), see:
991  // http://www.open-std.org/jtc1/sc22/wg21/docs/papers/2020/p2162r0.html
992  // For now, compose the variant into this class as a private attribute.
993  typename HelperT::variant_type callback_variant_;
994 
995  SubscribedTypeAllocator subscribed_type_allocator_;
996  SubscribedTypeDeleter subscribed_type_deleter_;
997  ROSMessageTypeAllocator ros_message_type_allocator_;
998  ROSMessageTypeDeleter ros_message_type_deleter_;
999  SerializedMessageAllocator serialized_message_allocator_;
1000  SerializedMessageDeleter serialized_message_deleter_;
1001 };
1002 
1003 } // namespace rclcpp
1004 
1005 #endif // RCLCPP__ANY_SUBSCRIPTION_CALLBACK_HPP_
AnySubscriptionCallback< MessageT, AllocatorT > set(CallbackT callback)
Generic function for setting the callback.
void set_deprecated(std::function< void(std::shared_ptr< SetT >, const rclcpp::MessageInfo &)> callback)
Function for shared_ptr to non-const MessageT with MessageInfo, which is deprecated.
void set_deprecated(std::function< void(std::shared_ptr< SetT >)> callback)
Function for shared_ptr to non-const MessageT, which is deprecated.
Additional meta data about messages taken from subscriptions.
Object oriented version of rcl_serialized_message_t with destructor to avoid memory leaks.
Versions of rosidl_typesupport_cpp::get_message_type_support_handle that handle adapted types.
Template structure used to adapt custom, user-defined types to ROS types.
Template helper to select the variant type based on whether or not MessageT is a TypeAdapter.
Struct which contains all possible callback signatures, with or without a TypeAdapter....
typename rclcpp::TypeAdapter< MessageT >::custom_type SubscribedType
MessageT::custom_type if MessageT is a TypeAdapter, otherwise just MessageT.
typename rclcpp::TypeAdapter< MessageT >::ros_message_type ROSMessageType
MessageT::ros_message_type if MessageT is a TypeAdapter, otherwise just MessageT.
Template metaprogramming helper used to resolve the callback argument into a std::function.