rclcpp  master
C++ ROS Client Library API
Public Types | Public Member Functions | Friends | List of all members
rclcpp::subscription::Subscription< MessageT, Alloc > Class Template Reference

Subscription implementation, templated on the type of message this subscription receives. More...

#include <subscription.hpp>

Inheritance diagram for rclcpp::subscription::Subscription< MessageT, Alloc >:
rclcpp::subscription::SubscriptionBase

Public Types

using MessageAllocTraits = allocator::AllocRebind< MessageT, Alloc >
 
using MessageAlloc = typename MessageAllocTraits::allocator_type
 
using MessageDeleter = allocator::Deleter< MessageAlloc, MessageT >
 
using MessageUniquePtr = std::unique_ptr< MessageT, MessageDeleter >
 
using GetMessageCallbackType = std::function< void(uint64_t, uint64_t, uint64_t, MessageUniquePtr &)>
 
using MatchesAnyPublishersCallbackType = std::function< bool(const rmw_gid_t *)>
 

Public Member Functions

 Subscription (std::shared_ptr< rcl_node_t > node_handle, const std::string &topic_name, const rcl_subscription_options_t &subscription_options, AnySubscriptionCallback< MessageT, Alloc > callback, typename message_memory_strategy::MessageMemoryStrategy< MessageT, Alloc >::SharedPtr memory_strategy=message_memory_strategy::MessageMemoryStrategy< MessageT, Alloc >::create_default())
 Default constructor. More...
 
void set_message_memory_strategy (typename message_memory_strategy::MessageMemoryStrategy< MessageT, Alloc >::SharedPtr message_memory_strategy)
 Support dynamically setting the message memory strategy. More...
 
std::shared_ptr< void > create_message ()
 Borrow a new message. More...
 
void handle_message (std::shared_ptr< void > &message, const rmw_message_info_t &message_info)
 Check if we need to handle the message, and execute the callback if we do. More...
 
void return_message (std::shared_ptr< void > &message)
 Return the loaned message. More...
 
void handle_intra_process_message (rcl_interfaces::msg::IntraProcessMessage &ipm, const rmw_message_info_t &message_info)
 
void setup_intra_process (uint64_t intra_process_subscription_id, GetMessageCallbackType get_message_callback, MatchesAnyPublishersCallbackType matches_any_publisher_callback, const rcl_subscription_options_t &intra_process_options)
 Implemenation detail. More...
 
const rcl_subscription_tget_intra_process_subscription_handle () const
 Implemenation detail. More...
 
- Public Member Functions inherited from rclcpp::subscription::SubscriptionBase
 SubscriptionBase (std::shared_ptr< rcl_node_t > node_handle, const rosidl_message_type_support_t &type_support_handle, const std::string &topic_name, const rcl_subscription_options_t &subscription_options)
 Default constructor. More...
 
virtual ~SubscriptionBase ()
 Default destructor. More...
 
const char * get_topic_name () const
 Get the topic that this subscription is subscribed on. More...
 
const rcl_subscription_tget_subscription_handle () const
 

Friends

class rclcpp::node_interfaces::NodeTopicsInterface
 

Additional Inherited Members

- Protected Attributes inherited from rclcpp::subscription::SubscriptionBase
rcl_subscription_t intra_process_subscription_handle_ = rcl_get_zero_initialized_subscription()
 
rcl_subscription_t subscription_handle_ = rcl_get_zero_initialized_subscription()
 
std::shared_ptr< rcl_node_tnode_handle_
 

Detailed Description

template<typename MessageT, typename Alloc = std::allocator<void>>
class rclcpp::subscription::Subscription< MessageT, Alloc >

Subscription implementation, templated on the type of message this subscription receives.

Member Typedef Documentation

◆ MessageAllocTraits

template<typename MessageT, typename Alloc = std::allocator<void>>
using rclcpp::subscription::Subscription< MessageT, Alloc >::MessageAllocTraits = allocator::AllocRebind<MessageT, Alloc>

◆ MessageAlloc

template<typename MessageT, typename Alloc = std::allocator<void>>
using rclcpp::subscription::Subscription< MessageT, Alloc >::MessageAlloc = typename MessageAllocTraits::allocator_type

◆ MessageDeleter

template<typename MessageT, typename Alloc = std::allocator<void>>
using rclcpp::subscription::Subscription< MessageT, Alloc >::MessageDeleter = allocator::Deleter<MessageAlloc, MessageT>

◆ MessageUniquePtr

template<typename MessageT, typename Alloc = std::allocator<void>>
using rclcpp::subscription::Subscription< MessageT, Alloc >::MessageUniquePtr = std::unique_ptr<MessageT, MessageDeleter>

◆ GetMessageCallbackType

template<typename MessageT, typename Alloc = std::allocator<void>>
using rclcpp::subscription::Subscription< MessageT, Alloc >::GetMessageCallbackType = std::function<void(uint64_t, uint64_t, uint64_t, MessageUniquePtr &)>

◆ MatchesAnyPublishersCallbackType

template<typename MessageT, typename Alloc = std::allocator<void>>
using rclcpp::subscription::Subscription< MessageT, Alloc >::MatchesAnyPublishersCallbackType = std::function<bool(const rmw_gid_t *)>

Constructor & Destructor Documentation

◆ Subscription()

template<typename MessageT, typename Alloc = std::allocator<void>>
rclcpp::subscription::Subscription< MessageT, Alloc >::Subscription ( std::shared_ptr< rcl_node_t node_handle,
const std::string &  topic_name,
const rcl_subscription_options_t subscription_options,
AnySubscriptionCallback< MessageT, Alloc >  callback,
typename message_memory_strategy::MessageMemoryStrategy< MessageT, Alloc >::SharedPtr  memory_strategy = message_memory_strategy::MessageMemoryStrategy<MessageT, Alloc>::create_default() 
)
inline

Default constructor.

The constructor for a subscription is almost never called directly. Instead, subscriptions should be instantiated through Node::create_subscription.

Parameters
[in]node_handlercl representation of the node that owns this subscription.
[in]topic_nameName of the topic to subscribe to.
[in]subscription_optionsoptions for the subscription.
[in]callbackUser defined callback to call when a message is received.
[in]memory_strategyThe memory strategy to be used for managing message memory.

Member Function Documentation

◆ set_message_memory_strategy()

template<typename MessageT, typename Alloc = std::allocator<void>>
void rclcpp::subscription::Subscription< MessageT, Alloc >::set_message_memory_strategy ( typename message_memory_strategy::MessageMemoryStrategy< MessageT, Alloc >::SharedPtr  message_memory_strategy)
inline

Support dynamically setting the message memory strategy.

Behavior may be undefined if called while the subscription could be executing.

Parameters
[in]message_memory_strategyShared pointer to the memory strategy to set.

◆ create_message()

template<typename MessageT, typename Alloc = std::allocator<void>>
std::shared_ptr<void> rclcpp::subscription::Subscription< MessageT, Alloc >::create_message ( )
inlinevirtual

Borrow a new message.

Returns
Shared pointer to the fresh message.

Implements rclcpp::subscription::SubscriptionBase.

◆ handle_message()

template<typename MessageT, typename Alloc = std::allocator<void>>
void rclcpp::subscription::Subscription< MessageT, Alloc >::handle_message ( std::shared_ptr< void > &  message,
const rmw_message_info_t message_info 
)
inlinevirtual

Check if we need to handle the message, and execute the callback if we do.

Parameters
[in]messageShared pointer to the message to handle.
[in]message_infoMetadata associated with this message.

Implements rclcpp::subscription::SubscriptionBase.

◆ return_message()

template<typename MessageT, typename Alloc = std::allocator<void>>
void rclcpp::subscription::Subscription< MessageT, Alloc >::return_message ( std::shared_ptr< void > &  message)
inlinevirtual

Return the loaned message.

Parameters
messagemessage to be returned

Implements rclcpp::subscription::SubscriptionBase.

◆ handle_intra_process_message()

template<typename MessageT, typename Alloc = std::allocator<void>>
void rclcpp::subscription::Subscription< MessageT, Alloc >::handle_intra_process_message ( rcl_interfaces::msg::IntraProcessMessage &  ipm,
const rmw_message_info_t message_info 
)
inlinevirtual

◆ setup_intra_process()

template<typename MessageT, typename Alloc = std::allocator<void>>
void rclcpp::subscription::Subscription< MessageT, Alloc >::setup_intra_process ( uint64_t  intra_process_subscription_id,
GetMessageCallbackType  get_message_callback,
MatchesAnyPublishersCallbackType  matches_any_publisher_callback,
const rcl_subscription_options_t intra_process_options 
)
inline

Implemenation detail.

◆ get_intra_process_subscription_handle()

template<typename MessageT, typename Alloc = std::allocator<void>>
const rcl_subscription_t* rclcpp::subscription::Subscription< MessageT, Alloc >::get_intra_process_subscription_handle ( ) const
inlinevirtual

Implemenation detail.

Reimplemented from rclcpp::subscription::SubscriptionBase.

Friends And Related Function Documentation

◆ rclcpp::node_interfaces::NodeTopicsInterface

template<typename MessageT, typename Alloc = std::allocator<void>>
friend class rclcpp::node_interfaces::NodeTopicsInterface
friend

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