Template Class AnySubscriptionCallback

Nested Relationships

Nested Types

Class Documentation

template<typename MessageT, typename AllocatorT = std::allocator<void>>
class AnySubscriptionCallback

Public Functions

inline explicit AnySubscriptionCallback(const AllocatorT &allocator = AllocatorT())
inline AnySubscriptionCallback(const AnySubscriptionCallback &other)
template<typename CallbackT>
inline AnySubscriptionCallback<MessageT, AllocatorT> set(CallbackT callback)

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.

inline void disable()

Disable the callback from being called during dispatch.

inline void enable()

Enable the callback to be called during dispatch.

inline std::unique_ptr<ROSMessageType, ROSMessageTypeDeleter> create_ros_unique_ptr_from_ros_shared_ptr_message(const std::shared_ptr<const ROSMessageType> &message)
inline std::unique_ptr<rclcpp::SerializedMessage, SerializedMessageDeleter> create_serialized_message_unique_ptr_from_shared_ptr(const std::shared_ptr<const rclcpp::SerializedMessage> &serialized_message)
inline std::unique_ptr<SubscribedType, SubscribedTypeDeleter> create_custom_unique_ptr_from_custom_shared_ptr_message(const std::shared_ptr<const SubscribedType> &message)
inline std::unique_ptr<SubscribedType, SubscribedTypeDeleter> convert_ros_message_to_custom_type_unique_ptr(const ROSMessageType &msg)
inline std::unique_ptr<ROSMessageType, ROSMessageTypeDeleter> convert_custom_type_to_ros_message_unique_ptr(const SubscribedType &msg)
template<typename TMsg = ROSMessageType>
inline std::enable_if<!serialization_traits::is_serialized_message_class<TMsg>::value, void>::type dispatch(std::shared_ptr<ROSMessageType> message, const rclcpp::MessageInfo &message_info)
inline void dispatch(std::shared_ptr<const rclcpp::SerializedMessage> serialized_message, const rclcpp::MessageInfo &message_info)
inline void dispatch_intra_process(std::shared_ptr<const SubscribedType> message, const rclcpp::MessageInfo &message_info)
inline void dispatch_intra_process(std::unique_ptr<SubscribedType, SubscribedTypeDeleter> message, const rclcpp::MessageInfo &message_info)
inline constexpr bool use_take_shared_method() const
inline constexpr bool is_serialized_message_callback() const
inline void register_callback_for_tracing()
inline HelperT::variant_type &get_variant()
inline const HelperT::variant_type &get_variant() const