ROS 2 rclcpp + rcl - jazzy  jazzy
ROS 2 C++ Client Library with ROS Client Library
Public Types | Public Member Functions | Friends | List of all members
rclcpp::Subscription< MessageT, AllocatorT, SubscribedT, ROSMessageT, MessageMemoryStrategyT > Class Template Reference

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

#include <rclcpp/subscription.hpp>

Inheritance diagram for rclcpp::Subscription< MessageT, AllocatorT, SubscribedT, ROSMessageT, MessageMemoryStrategyT >:
Inheritance graph
[legend]
Collaboration diagram for rclcpp::Subscription< MessageT, AllocatorT, SubscribedT, ROSMessageT, MessageMemoryStrategyT >:
Collaboration graph
[legend]

Public Types

using SubscribedType = SubscribedT
 
using ROSMessageType = ROSMessageT
 
using MessageMemoryStrategyType = MessageMemoryStrategyT
 
using SubscribedTypeAllocatorTraits = allocator::AllocRebind< SubscribedType, AllocatorT >
 
using SubscribedTypeAllocator = typename SubscribedTypeAllocatorTraits::allocator_type
 
using SubscribedTypeDeleter = allocator::Deleter< SubscribedTypeAllocator, SubscribedType >
 
using ROSMessageTypeAllocatorTraits = allocator::AllocRebind< ROSMessageType, AllocatorT >
 
using ROSMessageTypeAllocator = typename ROSMessageTypeAllocatorTraits::allocator_type
 
using ROSMessageTypeDeleter = allocator::Deleter< ROSMessageTypeAllocator, ROSMessageType >
 
using MessageAllocatorTraits = ROSMessageTypeAllocatorTraits
 
using MessageAllocator = ROSMessageTypeAllocator
 
using MessageDeleter = ROSMessageTypeDeleter
 
using ConstMessageSharedPtr = std::shared_ptr< const ROSMessageType >
 
using MessageUniquePtr = std::unique_ptr< ROSMessageType, ROSMessageTypeDeleter >
 
- Public Types inherited from rclcpp::SubscriptionBase
using IntraProcessManagerWeakPtr = std::weak_ptr< rclcpp::experimental::IntraProcessManager >
 

Public Member Functions

 Subscription (rclcpp::node_interfaces::NodeBaseInterface *node_base, const rosidl_message_type_support_t &type_support_handle, const std::string &topic_name, const rclcpp::QoS &qos, AnySubscriptionCallback< MessageT, AllocatorT > callback, const rclcpp::SubscriptionOptionsWithAllocator< AllocatorT > &options, typename MessageMemoryStrategyT::SharedPtr message_memory_strategy, SubscriptionTopicStatisticsSharedPtr subscription_topic_statistics=nullptr)
 Default constructor. More...
 
void post_init_setup (rclcpp::node_interfaces::NodeBaseInterface *node_base, const rclcpp::QoS &qos, const rclcpp::SubscriptionOptionsWithAllocator< AllocatorT > &options)
 Called after construction to continue setup that requires shared_from_this().
 
bool take (ROSMessageType &message_out, rclcpp::MessageInfo &message_info_out)
 Take the next message from the inter-process subscription. More...
 
template<typename TakeT >
std::enable_if_t< !rosidl_generator_traits::is_message< TakeT >::value &&std::is_same_v< TakeT, SubscribedType >, bool > take (TakeT &message_out, rclcpp::MessageInfo &message_info_out)
 Take the next message from the inter-process subscription. More...
 
std::shared_ptr< void > create_message () override
 Borrow a new message. More...
 
std::shared_ptr< rclcpp::SerializedMessagecreate_serialized_message () override
 Borrow a new serialized message. More...
 
void handle_message (std::shared_ptr< void > &message, const rclcpp::MessageInfo &message_info) override
 Check if we need to handle the message, and execute the callback if we do. More...
 
void handle_serialized_message (const std::shared_ptr< rclcpp::SerializedMessage > &serialized_message, const rclcpp::MessageInfo &message_info) override
 
void handle_loaned_message (void *loaned_message, const rclcpp::MessageInfo &message_info) override
 
void return_message (std::shared_ptr< void > &message) override
 Return the borrowed message. More...
 
void return_serialized_message (std::shared_ptr< rclcpp::SerializedMessage > &message) override
 Return the borrowed serialized message. More...
 
bool use_take_shared_method () const
 
rclcpp::dynamic_typesupport::DynamicMessageType::SharedPtr get_shared_dynamic_message_type () override
 
rclcpp::dynamic_typesupport::DynamicMessage::SharedPtr get_shared_dynamic_message () override
 
rclcpp::dynamic_typesupport::DynamicSerializationSupport::SharedPtr get_shared_dynamic_serialization_support () override
 
rclcpp::dynamic_typesupport::DynamicMessage::SharedPtr create_dynamic_message () override
 Borrow a new serialized message (this clones!) More...
 
void return_dynamic_message (rclcpp::dynamic_typesupport::DynamicMessage::SharedPtr &message) override
 
void handle_dynamic_message (const rclcpp::dynamic_typesupport::DynamicMessage::SharedPtr &message, const rclcpp::MessageInfo &message_info) override
 
- Public Member Functions inherited from rclcpp::SubscriptionBase
RCLCPP_PUBLIC SubscriptionBase (rclcpp::node_interfaces::NodeBaseInterface *node_base, const rosidl_message_type_support_t &type_support_handle, const std::string &topic_name, const rcl_subscription_options_t &subscription_options, const SubscriptionEventCallbacks &event_callbacks, bool use_default_callbacks, DeliveredMessageKind delivered_message_kind=DeliveredMessageKind::ROS_MESSAGE)
 Constructor. More...
 
virtual RCLCPP_PUBLIC ~SubscriptionBase ()
 Destructor.
 
RCLCPP_PUBLIC void bind_event_callbacks (const SubscriptionEventCallbacks &event_callbacks, bool use_default_callbacks)
 Add event handlers for passed in event_callbacks.
 
RCLCPP_PUBLIC const char * get_topic_name () const
 Get the topic that this subscription is subscribed on.
 
RCLCPP_PUBLIC std::shared_ptr< rcl_subscription_tget_subscription_handle ()
 
RCLCPP_PUBLIC std::shared_ptr< const rcl_subscription_tget_subscription_handle () const
 
RCLCPP_PUBLIC const std::unordered_map< rcl_subscription_event_type_t, std::shared_ptr< rclcpp::EventHandlerBase > > & get_event_handlers () const
 Get all the QoS event handlers associated with this subscription. More...
 
RCLCPP_PUBLIC rclcpp::QoS get_actual_qos () const
 Get the actual QoS settings, after the defaults have been determined. More...
 
RCLCPP_PUBLIC bool take_type_erased (void *message_out, rclcpp::MessageInfo &message_info_out)
 Take the next inter-process message from the subscription as a type erased pointer. More...
 
RCLCPP_PUBLIC bool take_serialized (rclcpp::SerializedMessage &message_out, rclcpp::MessageInfo &message_info_out)
 Take the next inter-process message, in its serialized form, from the subscription. More...
 
RCLCPP_PUBLIC const rosidl_message_type_support_t & get_message_type_support_handle () const
 
RCLCPP_PUBLIC bool is_serialized () const
 Return if the subscription is serialized. More...
 
RCLCPP_PUBLIC DeliveredMessageKind get_delivered_message_kind () const
 Return the delivered message kind. More...
 
RCLCPP_PUBLIC size_t get_publisher_count () const
 Get matching publisher count. More...
 
RCLCPP_PUBLIC bool can_loan_messages () const
 Check if subscription instance can loan messages. More...
 
RCLCPP_PUBLIC void setup_intra_process (uint64_t intra_process_subscription_id, IntraProcessManagerWeakPtr weak_ipm)
 Implemenation detail.
 
RCLCPP_PUBLIC rclcpp::Waitable::SharedPtr get_intra_process_waitable () const
 Return the waitable for intra-process. More...
 
RCLCPP_PUBLIC bool exchange_in_use_by_wait_set_state (void *pointer_to_subscription_part, bool in_use_state)
 Exchange state of whether or not a part of the subscription is used by a wait set. More...
 
RCLCPP_PUBLIC std::vector< rclcpp::NetworkFlowEndpointget_network_flow_endpoints () const
 Get network flow endpoints. More...
 
void set_on_new_message_callback (std::function< void(size_t)> callback)
 Set a callback to be called when each new message is received. More...
 
void clear_on_new_message_callback ()
 Unset the callback registered for new messages, if any.
 
void set_on_new_intra_process_message_callback (std::function< void(size_t)> callback)
 Set a callback to be called when each new intra-process message is received. More...
 
void clear_on_new_intra_process_message_callback ()
 Unset the callback registered for new intra-process messages, if any.
 
void set_on_new_qos_event_callback (std::function< void(size_t)> callback, rcl_subscription_event_type_t event_type)
 Set a callback to be called when each new qos event instance occurs. More...
 
void clear_on_new_qos_event_callback (rcl_subscription_event_type_t event_type)
 Unset the callback registered for new qos events, if any.
 
RCLCPP_PUBLIC bool is_cft_enabled () const
 Check if content filtered topic feature of the subscription instance is enabled. More...
 
RCLCPP_PUBLIC void set_content_filter (const std::string &filter_expression, const std::vector< std::string > &expression_parameters={})
 Set the filter expression and expression parameters for the subscription. More...
 
RCLCPP_PUBLIC rclcpp::ContentFilterOptions get_content_filter () const
 Get the filter expression and expression parameters for the subscription. More...
 
RCLCPP_PUBLIC bool take_dynamic_message (rclcpp::dynamic_typesupport::DynamicMessage &message_out, rclcpp::MessageInfo &message_info_out)
 

Friends

class rclcpp::node_interfaces::NodeTopicsInterface
 

Additional Inherited Members

- Protected Member Functions inherited from rclcpp::SubscriptionBase
template<typename EventCallbackT >
void add_event_handler (const EventCallbackT &callback, const rcl_subscription_event_type_t event_type)
 
RCLCPP_PUBLIC void default_incompatible_qos_callback (QOSRequestedIncompatibleQoSInfo &info) const
 
RCLCPP_PUBLIC void default_incompatible_type_callback (IncompatibleTypeInfo &info) const
 
RCLCPP_PUBLIC bool matches_any_intra_process_publishers (const rmw_gid_t *sender_gid) const
 
RCLCPP_PUBLIC void set_on_new_message_callback (rcl_event_callback_t callback, const void *user_data)
 
- Protected Attributes inherited from rclcpp::SubscriptionBase
rclcpp::node_interfaces::NodeBaseInterface *const node_base_
 
std::shared_ptr< rcl_node_tnode_handle_
 
std::recursive_mutex callback_mutex_
 
std::function< void(size_t)> on_new_message_callback_ {nullptr}
 
std::shared_ptr< rcl_subscription_tsubscription_handle_
 
std::shared_ptr< rcl_subscription_tintra_process_subscription_handle_
 
rclcpp::Logger node_logger_
 
std::unordered_map< rcl_subscription_event_type_t, std::shared_ptr< rclcpp::EventHandlerBase > > event_handlers_
 
bool use_intra_process_
 
IntraProcessManagerWeakPtr weak_ipm_
 
uint64_t intra_process_subscription_id_
 
std::shared_ptr< rclcpp::experimental::SubscriptionIntraProcessBasesubscription_intra_process_
 
const SubscriptionEventCallbacks event_callbacks_
 

Detailed Description

template<typename MessageT, typename AllocatorT = std::allocator<void>, typename SubscribedT = typename rclcpp::TypeAdapter<MessageT>::custom_type, typename ROSMessageT = typename rclcpp::TypeAdapter<MessageT>::ros_message_type, typename MessageMemoryStrategyT = rclcpp::message_memory_strategy::MessageMemoryStrategy< ROSMessageT, AllocatorT >>
class rclcpp::Subscription< MessageT, AllocatorT, SubscribedT, ROSMessageT, MessageMemoryStrategyT >

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

Definition at line 75 of file subscription.hpp.

Constructor & Destructor Documentation

◆ Subscription()

template<typename MessageT , typename AllocatorT = std::allocator<void>, typename SubscribedT = typename rclcpp::TypeAdapter<MessageT>::custom_type, typename ROSMessageT = typename rclcpp::TypeAdapter<MessageT>::ros_message_type, typename MessageMemoryStrategyT = rclcpp::message_memory_strategy::MessageMemoryStrategy< ROSMessageT, AllocatorT >>
rclcpp::Subscription< MessageT, AllocatorT, SubscribedT, ROSMessageT, MessageMemoryStrategyT >::Subscription ( rclcpp::node_interfaces::NodeBaseInterface node_base,
const rosidl_message_type_support_t &  type_support_handle,
const std::string &  topic_name,
const rclcpp::QoS qos,
AnySubscriptionCallback< MessageT, AllocatorT >  callback,
const rclcpp::SubscriptionOptionsWithAllocator< AllocatorT > &  options,
typename MessageMemoryStrategyT::SharedPtr  message_memory_strategy,
SubscriptionTopicStatisticsSharedPtr  subscription_topic_statistics = nullptr 
)
inline

Default constructor.

The constructor for a subscription is almost never called directly. Instead, subscriptions should be instantiated through the function rclcpp::create_subscription().

Parameters
[in]node_baseNodeBaseInterface pointer that is used in part of the setup.
[in]type_support_handlerosidl type support struct, for the Message type of the topic.
[in]topic_nameName of the topic to subscribe to.
[in]qosQoS profile for Subcription.
[in]callbackUser defined callback to call when a message is received.
[in]optionsOptions for the subscription.
[in]message_memory_strategyThe memory strategy to be used for managing message memory.
[in]subscription_topic_statisticsOptional pointer to a topic statistics subcription.
Exceptions
std::invalid_argumentif the QoS is uncompatible with intra-process (if one of the following conditions are true: qos_profile.history == RMW_QOS_POLICY_HISTORY_KEEP_ALL, qos_profile.depth == 0 or qos_profile.durability != RMW_QOS_POLICY_DURABILITY_VOLATILE).

Definition at line 131 of file subscription.hpp.

References rclcpp::SubscriptionBase::get_actual_qos(), and rclcpp::SubscriptionBase::setup_intra_process().

Here is the call graph for this function:

Member Function Documentation

◆ create_dynamic_message()

template<typename MessageT , typename AllocatorT = std::allocator<void>, typename SubscribedT = typename rclcpp::TypeAdapter<MessageT>::custom_type, typename ROSMessageT = typename rclcpp::TypeAdapter<MessageT>::ros_message_type, typename MessageMemoryStrategyT = rclcpp::message_memory_strategy::MessageMemoryStrategy< ROSMessageT, AllocatorT >>
rclcpp::dynamic_typesupport::DynamicMessage::SharedPtr rclcpp::Subscription< MessageT, AllocatorT, SubscribedT, ROSMessageT, MessageMemoryStrategyT >::create_dynamic_message ( )
inlineoverridevirtual

Borrow a new serialized message (this clones!)

Returns
Shared pointer to a rclcpp::dynamic_typesupport::DynamicMessage.

Implements rclcpp::SubscriptionBase.

Definition at line 429 of file subscription.hpp.

◆ create_message()

template<typename MessageT , typename AllocatorT = std::allocator<void>, typename SubscribedT = typename rclcpp::TypeAdapter<MessageT>::custom_type, typename ROSMessageT = typename rclcpp::TypeAdapter<MessageT>::ros_message_type, typename MessageMemoryStrategyT = rclcpp::message_memory_strategy::MessageMemoryStrategy< ROSMessageT, AllocatorT >>
std::shared_ptr<void> rclcpp::Subscription< MessageT, AllocatorT, SubscribedT, ROSMessageT, MessageMemoryStrategyT >::create_message ( )
inlineoverridevirtual

Borrow a new message.

Returns
Shared pointer to the fresh message.

Implements rclcpp::SubscriptionBase.

Definition at line 281 of file subscription.hpp.

◆ create_serialized_message()

template<typename MessageT , typename AllocatorT = std::allocator<void>, typename SubscribedT = typename rclcpp::TypeAdapter<MessageT>::custom_type, typename ROSMessageT = typename rclcpp::TypeAdapter<MessageT>::ros_message_type, typename MessageMemoryStrategyT = rclcpp::message_memory_strategy::MessageMemoryStrategy< ROSMessageT, AllocatorT >>
std::shared_ptr<rclcpp::SerializedMessage> rclcpp::Subscription< MessageT, AllocatorT, SubscribedT, ROSMessageT, MessageMemoryStrategyT >::create_serialized_message ( )
inlineoverridevirtual

Borrow a new serialized message.

Returns
Shared pointer to a rcl_message_serialized_t.

Implements rclcpp::SubscriptionBase.

Definition at line 291 of file subscription.hpp.

◆ handle_message()

template<typename MessageT , typename AllocatorT = std::allocator<void>, typename SubscribedT = typename rclcpp::TypeAdapter<MessageT>::custom_type, typename ROSMessageT = typename rclcpp::TypeAdapter<MessageT>::ros_message_type, typename MessageMemoryStrategyT = rclcpp::message_memory_strategy::MessageMemoryStrategy< ROSMessageT, AllocatorT >>
void rclcpp::Subscription< MessageT, AllocatorT, SubscribedT, ROSMessageT, MessageMemoryStrategyT >::handle_message ( std::shared_ptr< void > &  message,
const rclcpp::MessageInfo message_info 
)
inlineoverridevirtual

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::SubscriptionBase.

Definition at line 297 of file subscription.hpp.

References rclcpp::MessageInfo::get_rmw_message_info().

Here is the call graph for this function:

◆ return_message()

template<typename MessageT , typename AllocatorT = std::allocator<void>, typename SubscribedT = typename rclcpp::TypeAdapter<MessageT>::custom_type, typename ROSMessageT = typename rclcpp::TypeAdapter<MessageT>::ros_message_type, typename MessageMemoryStrategyT = rclcpp::message_memory_strategy::MessageMemoryStrategy< ROSMessageT, AllocatorT >>
void rclcpp::Subscription< MessageT, AllocatorT, SubscribedT, ROSMessageT, MessageMemoryStrategyT >::return_message ( std::shared_ptr< void > &  message)
inlineoverridevirtual

Return the borrowed message.

Parameters
[in,out]messagemessage to be returned

Implements rclcpp::SubscriptionBase.

Definition at line 382 of file subscription.hpp.

◆ return_serialized_message()

template<typename MessageT , typename AllocatorT = std::allocator<void>, typename SubscribedT = typename rclcpp::TypeAdapter<MessageT>::custom_type, typename ROSMessageT = typename rclcpp::TypeAdapter<MessageT>::ros_message_type, typename MessageMemoryStrategyT = rclcpp::message_memory_strategy::MessageMemoryStrategy< ROSMessageT, AllocatorT >>
void rclcpp::Subscription< MessageT, AllocatorT, SubscribedT, ROSMessageT, MessageMemoryStrategyT >::return_serialized_message ( std::shared_ptr< rclcpp::SerializedMessage > &  message)
inlineoverridevirtual

Return the borrowed serialized message.

Parameters
[in,out]messageserialized message to be returned

Implements rclcpp::SubscriptionBase.

Definition at line 393 of file subscription.hpp.

◆ take() [1/2]

template<typename MessageT , typename AllocatorT = std::allocator<void>, typename SubscribedT = typename rclcpp::TypeAdapter<MessageT>::custom_type, typename ROSMessageT = typename rclcpp::TypeAdapter<MessageT>::ros_message_type, typename MessageMemoryStrategyT = rclcpp::message_memory_strategy::MessageMemoryStrategy< ROSMessageT, AllocatorT >>
bool rclcpp::Subscription< MessageT, AllocatorT, SubscribedT, ROSMessageT, MessageMemoryStrategyT >::take ( ROSMessageType &  message_out,
rclcpp::MessageInfo message_info_out 
)
inline

Take the next message from the inter-process subscription.

Data may be taken (written) into the message_out and message_info_out even if false is returned. Specifically in the case of dropping redundant intra-process data, where data is received via both intra-process and inter-process (due to the underlying middleware being unabled to avoid this duplicate delivery) and so inter-process data from those intra-process publishers is ignored, but it has to be taken to know if it came from an intra-process publisher or not, and therefore could be dropped.

See also
SubscriptionBase::take_type_erased()
Parameters
[out]message_outThe message into which take will copy the data.
[out]message_info_outThe message info for the taken message.
Returns
true if data was taken and is valid, otherwise false
Exceptions
anyrcl errors from rcl_take,
See also
rclcpp::exceptions::throw_from_rcl_error()

Definition at line 252 of file subscription.hpp.

References rclcpp::SubscriptionBase::take_type_erased().

Here is the call graph for this function:

◆ take() [2/2]

template<typename MessageT , typename AllocatorT = std::allocator<void>, typename SubscribedT = typename rclcpp::TypeAdapter<MessageT>::custom_type, typename ROSMessageT = typename rclcpp::TypeAdapter<MessageT>::ros_message_type, typename MessageMemoryStrategyT = rclcpp::message_memory_strategy::MessageMemoryStrategy< ROSMessageT, AllocatorT >>
template<typename TakeT >
std::enable_if_t< !rosidl_generator_traits::is_message<TakeT>::value && std::is_same_v<TakeT, SubscribedType>, bool > rclcpp::Subscription< MessageT, AllocatorT, SubscribedT, ROSMessageT, MessageMemoryStrategyT >::take ( TakeT &  message_out,
rclcpp::MessageInfo message_info_out 
)
inline

Take the next message from the inter-process subscription.

This version takes a SubscribedType which is different from the ROSMessageType when a rclcpp::TypeAdapter is in used.

See also
take(ROSMessageType &, rclcpp::MessageInfo &)

Definition at line 270 of file subscription.hpp.

References rclcpp::SubscriptionBase::take_type_erased().

Here is the call graph for this function:

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