rclcpp  master
C++ ROS Client Library API
Public Member Functions | List of all members
rclcpp::AnySubscriptionCallback< MessageT, AllocatorT > Class Template Reference

#include <any_subscription_callback.hpp>

Public Member Functions

 AnySubscriptionCallback (const AllocatorT &allocator=AllocatorT())
 
 AnySubscriptionCallback (std::shared_ptr< AllocatorT > allocator)
 
 AnySubscriptionCallback (const AnySubscriptionCallback &)=default
 
template<typename CallbackT >
AnySubscriptionCallback< MessageT, AllocatorT > set (CallbackT callback)
 Generic function for setting the callback. More...
 
void set_deprecated (std::function< void(std::shared_ptr< MessageT >)> callback)
 Function for shared_ptr to non-const MessageT, which is deprecated. More...
 
void set_deprecated (std::function< void(std::shared_ptr< MessageT >, const rclcpp::MessageInfo &)> callback)
 Function for shared_ptr to non-const MessageT with MessageInfo, which is deprecated. More...
 
std::unique_ptr< MessageT, MessageDeleter > create_unique_ptr_from_shared_ptr_message (const std::shared_ptr< const MessageT > &message)
 
void dispatch (std::shared_ptr< MessageT > message, const rclcpp::MessageInfo &message_info)
 
void dispatch_intra_process (std::shared_ptr< const MessageT > message, const rclcpp::MessageInfo &message_info)
 
void dispatch_intra_process (std::unique_ptr< MessageT, MessageDeleter > message, const rclcpp::MessageInfo &message_info)
 
constexpr bool use_take_shared_method () const
 
void register_callback_for_tracing ()
 
HelperT::variant_type & get_variant ()
 
const HelperT::variant_type & get_variant () const
 

Constructor & Destructor Documentation

◆ AnySubscriptionCallback() [1/3]

template<typename MessageT , typename AllocatorT = std::allocator<void>>
rclcpp::AnySubscriptionCallback< MessageT, AllocatorT >::AnySubscriptionCallback ( const AllocatorT &  allocator = AllocatorT())
inlineexplicit

◆ AnySubscriptionCallback() [2/3]

template<typename MessageT , typename AllocatorT = std::allocator<void>>
rclcpp::AnySubscriptionCallback< MessageT, AllocatorT >::AnySubscriptionCallback ( std::shared_ptr< AllocatorT >  allocator)
inlineexplicit

◆ AnySubscriptionCallback() [3/3]

template<typename MessageT , typename AllocatorT = std::allocator<void>>
rclcpp::AnySubscriptionCallback< MessageT, AllocatorT >::AnySubscriptionCallback ( const AnySubscriptionCallback< MessageT, AllocatorT > &  )
default

Member Function Documentation

◆ set()

template<typename MessageT , typename AllocatorT = std::allocator<void>>
template<typename CallbackT >
AnySubscriptionCallback<MessageT, AllocatorT> rclcpp::AnySubscriptionCallback< MessageT, AllocatorT >::set ( CallbackT  callback)
inline

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.

◆ set_deprecated() [1/2]

template<typename MessageT , typename AllocatorT = std::allocator<void>>
void rclcpp::AnySubscriptionCallback< MessageT, AllocatorT >::set_deprecated ( std::function< void(std::shared_ptr< MessageT >)>  callback)
inline

Function for shared_ptr to non-const MessageT, which is deprecated.

◆ set_deprecated() [2/2]

template<typename MessageT , typename AllocatorT = std::allocator<void>>
void rclcpp::AnySubscriptionCallback< MessageT, AllocatorT >::set_deprecated ( std::function< void(std::shared_ptr< MessageT >, const rclcpp::MessageInfo &)>  callback)
inline

Function for shared_ptr to non-const MessageT with MessageInfo, which is deprecated.

◆ create_unique_ptr_from_shared_ptr_message()

template<typename MessageT , typename AllocatorT = std::allocator<void>>
std::unique_ptr<MessageT, MessageDeleter> rclcpp::AnySubscriptionCallback< MessageT, AllocatorT >::create_unique_ptr_from_shared_ptr_message ( const std::shared_ptr< const MessageT > &  message)
inline

◆ dispatch()

template<typename MessageT , typename AllocatorT = std::allocator<void>>
void rclcpp::AnySubscriptionCallback< MessageT, AllocatorT >::dispatch ( std::shared_ptr< MessageT >  message,
const rclcpp::MessageInfo message_info 
)
inline

◆ dispatch_intra_process() [1/2]

template<typename MessageT , typename AllocatorT = std::allocator<void>>
void rclcpp::AnySubscriptionCallback< MessageT, AllocatorT >::dispatch_intra_process ( std::shared_ptr< const MessageT >  message,
const rclcpp::MessageInfo message_info 
)
inline

◆ dispatch_intra_process() [2/2]

template<typename MessageT , typename AllocatorT = std::allocator<void>>
void rclcpp::AnySubscriptionCallback< MessageT, AllocatorT >::dispatch_intra_process ( std::unique_ptr< MessageT, MessageDeleter >  message,
const rclcpp::MessageInfo message_info 
)
inline

◆ use_take_shared_method()

template<typename MessageT , typename AllocatorT = std::allocator<void>>
constexpr bool rclcpp::AnySubscriptionCallback< MessageT, AllocatorT >::use_take_shared_method ( ) const
inlineconstexpr

◆ register_callback_for_tracing()

template<typename MessageT , typename AllocatorT = std::allocator<void>>
void rclcpp::AnySubscriptionCallback< MessageT, AllocatorT >::register_callback_for_tracing ( )
inline

◆ get_variant() [1/2]

template<typename MessageT , typename AllocatorT = std::allocator<void>>
HelperT::variant_type& rclcpp::AnySubscriptionCallback< MessageT, AllocatorT >::get_variant ( )
inline

◆ get_variant() [2/2]

template<typename MessageT , typename AllocatorT = std::allocator<void>>
const HelperT::variant_type& rclcpp::AnySubscriptionCallback< MessageT, AllocatorT >::get_variant ( ) const
inline

The documentation for this class was generated from the following file: