rclcpp  master
C++ ROS Client Library API
Public Types | Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
rclcpp::SubscriptionBase Class Referenceabstract

#include <subscription_base.hpp>

Inheritance diagram for rclcpp::SubscriptionBase:
Inheritance graph
[legend]
Collaboration diagram for rclcpp::SubscriptionBase:
Collaboration graph
[legend]

Public Types

using IntraProcessManagerWeakPtr = std::weak_ptr< rclcpp::experimental::IntraProcessManager >
 

Public Member Functions

 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, bool is_serialized=false)
 Constructor. More...
 
virtual ~SubscriptionBase ()
 Destructor. More...
 
const char * get_topic_name () const
 Get the topic that this subscription is subscribed on. More...
 
std::shared_ptr< rcl_subscription_tget_subscription_handle ()
 
std::shared_ptr< const rcl_subscription_tget_subscription_handle () const
 
const std::vector< std::shared_ptr< rclcpp::QOSEventHandlerBase > > & get_event_handlers () const
 Get all the QoS event handlers associated with this subscription. More...
 
rclcpp::QoS get_actual_qos () const
 Get the actual QoS settings, after the defaults have been determined. More...
 
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...
 
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...
 
virtual std::shared_ptr< void > create_message ()=0
 Borrow a new message. More...
 
virtual std::shared_ptr< rclcpp::SerializedMessagecreate_serialized_message ()=0
 Borrow a new serialized message. More...
 
virtual void handle_message (std::shared_ptr< void > &message, const rclcpp::MessageInfo &message_info)=0
 Check if we need to handle the message, and execute the callback if we do. More...
 
virtual void handle_loaned_message (void *loaned_message, const rclcpp::MessageInfo &message_info)=0
 
virtual void return_message (std::shared_ptr< void > &message)=0
 Return the message borrowed in create_message. More...
 
virtual void return_serialized_message (std::shared_ptr< rclcpp::SerializedMessage > &message)=0
 Return the message borrowed in create_serialized_message. More...
 
const rosidl_message_type_support_t & get_message_type_support_handle () const
 
bool is_serialized () const
 Return if the subscription is serialized. More...
 
size_t get_publisher_count () const
 Get matching publisher count. More...
 
bool can_loan_messages () const
 Check if subscription instance can loan messages. More...
 
void setup_intra_process (uint64_t intra_process_subscription_id, IntraProcessManagerWeakPtr weak_ipm)
 Implemenation detail. More...
 
rclcpp::Waitable::SharedPtr get_intra_process_waitable () const
 Return the waitable for intra-process. More...
 
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...
 
std::vector< rclcpp::NetworkFlowEndpointget_network_flow_endpoints () const
 Get network flow endpoints. More...
 
- Public Member Functions inherited from std::enable_shared_from_this< SubscriptionBase >
enable_shared_from_this (T... args)
 
operator= (T... args)
 
shared_from_this (T... args)
 
~enable_shared_from_this (T... args)
 

Protected Member Functions

template<typename EventCallbackT >
void add_event_handler (const EventCallbackT &callback, const rcl_subscription_event_type_t event_type)
 
void default_incompatible_qos_callback (QOSRequestedIncompatibleQoSInfo &info) const
 
bool matches_any_intra_process_publishers (const rmw_gid_t *sender_gid) const
 

Protected Attributes

rclcpp::node_interfaces::NodeBaseInterface *const node_base_
 
std::shared_ptr< rcl_node_tnode_handle_
 
std::shared_ptr< rcl_subscription_tsubscription_handle_
 
std::shared_ptr< rcl_subscription_tintra_process_subscription_handle_
 
std::vector< std::shared_ptr< rclcpp::QOSEventHandlerBase > > event_handlers_
 
bool use_intra_process_
 
IntraProcessManagerWeakPtr weak_ipm_
 
uint64_t intra_process_subscription_id_
 

Detailed Description

Virtual base class for subscriptions. This pattern allows us to iterate over different template specializations of Subscription, among other things.

Member Typedef Documentation

◆ IntraProcessManagerWeakPtr

Constructor & Destructor Documentation

◆ SubscriptionBase()

rclcpp::SubscriptionBase::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,
bool  is_serialized = false 
)

Constructor.

This accepts rcl_subscription_options_t instead of rclcpp::SubscriptionOptions because rclcpp::SubscriptionOptions::to_rcl_subscription_options depends on the message type.

Parameters
[in]node_baseNodeBaseInterface pointer used in parts 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]subscription_optionsOptions for the subscription.
[in]is_serializedis true if the message will be delivered still serialized

◆ ~SubscriptionBase()

virtual rclcpp::SubscriptionBase::~SubscriptionBase ( )
virtual

Destructor.

Member Function Documentation

◆ get_topic_name()

const char* rclcpp::SubscriptionBase::get_topic_name ( ) const

Get the topic that this subscription is subscribed on.

◆ get_subscription_handle() [1/2]

std::shared_ptr<rcl_subscription_t> rclcpp::SubscriptionBase::get_subscription_handle ( )

◆ get_subscription_handle() [2/2]

std::shared_ptr<const rcl_subscription_t> rclcpp::SubscriptionBase::get_subscription_handle ( ) const

◆ get_event_handlers()

const std::vector<std::shared_ptr<rclcpp::QOSEventHandlerBase> >& rclcpp::SubscriptionBase::get_event_handlers ( ) const

Get all the QoS event handlers associated with this subscription.

Returns
The vector of QoS event handlers.

◆ get_actual_qos()

rclcpp::QoS rclcpp::SubscriptionBase::get_actual_qos ( ) const

Get the actual QoS settings, after the defaults have been determined.

The actual configuration applied when using RMW_QOS_POLICY_*_SYSTEM_DEFAULT can only be resolved after the creation of the publisher, and it depends on the underlying rmw implementation. If the underlying setting in use can't be represented in ROS terms, it will be set to RMW_QOS_POLICY_*_UNKNOWN. May throw runtime_error when an unexpected error occurs.

Returns
The actual qos settings.
Exceptions
std::runtime_errorif failed to get qos settings

◆ take_type_erased()

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

See also
Subscription::take() for details on how this function works.

The only difference is that it takes a type erased pointer rather than a reference to the exact message type.

This type erased version facilitates using the subscriptions in a type agnostic way using SubscriptionBase::create_message() and SubscriptionBase::handle_message().

Parameters
[out]message_outThe type erased message pointer 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()

◆ take_serialized()

bool rclcpp::SubscriptionBase::take_serialized ( rclcpp::SerializedMessage message_out,
rclcpp::MessageInfo message_info_out 
)

Take the next inter-process message, in its serialized form, from the subscription.

For now, if data is taken (written) into the message_out and message_info_out then true will be returned. Unlike Subscription::take(), taking data serialized is not possible via intra-process for the time being, so it will not need to de-duplicate data in any case.

Parameters
[out]message_outThe serialized message data structure used to store the taken message.
[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()

◆ create_message()

virtual std::shared_ptr<void> rclcpp::SubscriptionBase::create_message ( )
pure virtual

◆ create_serialized_message()

virtual std::shared_ptr<rclcpp::SerializedMessage> rclcpp::SubscriptionBase::create_serialized_message ( )
pure virtual

Borrow a new serialized message.

Returns
Shared pointer to a rcl_message_serialized_t.

Implemented in rclcpp::Subscription< CallbackMessageT, AllocatorT, MessageMemoryStrategyT >, rclcpp::Subscription< rcl_interfaces::msg::ParameterEvent >, and rclcpp::GenericSubscription.

◆ handle_message()

virtual void rclcpp::SubscriptionBase::handle_message ( std::shared_ptr< void > &  message,
const rclcpp::MessageInfo message_info 
)
pure virtual

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.

Implemented in rclcpp::Subscription< CallbackMessageT, AllocatorT, MessageMemoryStrategyT >, rclcpp::Subscription< rcl_interfaces::msg::ParameterEvent >, and rclcpp::GenericSubscription.

◆ handle_loaned_message()

virtual void rclcpp::SubscriptionBase::handle_loaned_message ( void *  loaned_message,
const rclcpp::MessageInfo message_info 
)
pure virtual

◆ return_message()

virtual void rclcpp::SubscriptionBase::return_message ( std::shared_ptr< void > &  message)
pure virtual

Return the message borrowed in create_message.

Parameters
[in]messageShared pointer to the returned message.

Implemented in rclcpp::Subscription< CallbackMessageT, AllocatorT, MessageMemoryStrategyT >, rclcpp::Subscription< rcl_interfaces::msg::ParameterEvent >, and rclcpp::GenericSubscription.

◆ return_serialized_message()

virtual void rclcpp::SubscriptionBase::return_serialized_message ( std::shared_ptr< rclcpp::SerializedMessage > &  message)
pure virtual

Return the message borrowed in create_serialized_message.

Parameters
[in]messageShared pointer to the returned message.

Implemented in rclcpp::Subscription< CallbackMessageT, AllocatorT, MessageMemoryStrategyT >, rclcpp::Subscription< rcl_interfaces::msg::ParameterEvent >, and rclcpp::GenericSubscription.

◆ get_message_type_support_handle()

const rosidl_message_type_support_t& rclcpp::SubscriptionBase::get_message_type_support_handle ( ) const

◆ is_serialized()

bool rclcpp::SubscriptionBase::is_serialized ( ) const

Return if the subscription is serialized.

Returns
true if the subscription is serialized, false otherwise

◆ get_publisher_count()

size_t rclcpp::SubscriptionBase::get_publisher_count ( ) const

Get matching publisher count.

Returns
The number of publishers on this topic.

◆ can_loan_messages()

bool rclcpp::SubscriptionBase::can_loan_messages ( ) const

Check if subscription instance can loan messages.

Depending on the middleware and the message type, this will return true if the middleware can allocate a ROS message instance.

Returns
boolean flag indicating if middleware can loan messages.

◆ setup_intra_process()

void rclcpp::SubscriptionBase::setup_intra_process ( uint64_t  intra_process_subscription_id,
IntraProcessManagerWeakPtr  weak_ipm 
)

Implemenation detail.

◆ get_intra_process_waitable()

rclcpp::Waitable::SharedPtr rclcpp::SubscriptionBase::get_intra_process_waitable ( ) const

Return the waitable for intra-process.

Returns
the waitable sharedpointer for intra-process, or nullptr if intra-process is not setup.
Exceptions
std::runtime_errorif the intra process manager is destroyed

◆ exchange_in_use_by_wait_set_state()

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

Used to ensure parts of the subscription are not used with multiple wait sets simultaneously.

Parameters
[in]pointer_to_subscription_partaddress of a subscription part
[in]in_use_statethe new state to exchange, true means "now in use", and false means "no longer in use".
Returns
the current "in use" state.
Exceptions
std::invalid_argumentIf pointer_to_subscription_part is nullptr.
std::runtime_errorIf the pointer given is not a pointer to one of the parts of the subscription which can be used with a wait set.

◆ get_network_flow_endpoints()

std::vector<rclcpp::NetworkFlowEndpoint> rclcpp::SubscriptionBase::get_network_flow_endpoints ( ) const

Get network flow endpoints.

Describes network flow endpoints that this subscription is receiving messages on

Returns
vector of NetworkFlowEndpoint

◆ add_event_handler()

template<typename EventCallbackT >
void rclcpp::SubscriptionBase::add_event_handler ( const EventCallbackT &  callback,
const rcl_subscription_event_type_t  event_type 
)
inlineprotected

◆ default_incompatible_qos_callback()

void rclcpp::SubscriptionBase::default_incompatible_qos_callback ( QOSRequestedIncompatibleQoSInfo info) const
protected

◆ matches_any_intra_process_publishers()

bool rclcpp::SubscriptionBase::matches_any_intra_process_publishers ( const rmw_gid_t sender_gid) const
protected

Member Data Documentation

◆ node_base_

rclcpp::node_interfaces::NodeBaseInterface* const rclcpp::SubscriptionBase::node_base_
protected

◆ node_handle_

std::shared_ptr<rcl_node_t> rclcpp::SubscriptionBase::node_handle_
protected

◆ subscription_handle_

std::shared_ptr<rcl_subscription_t> rclcpp::SubscriptionBase::subscription_handle_
protected

◆ intra_process_subscription_handle_

std::shared_ptr<rcl_subscription_t> rclcpp::SubscriptionBase::intra_process_subscription_handle_
protected

◆ event_handlers_

std::vector<std::shared_ptr<rclcpp::QOSEventHandlerBase> > rclcpp::SubscriptionBase::event_handlers_
protected

◆ use_intra_process_

bool rclcpp::SubscriptionBase::use_intra_process_
protected

◆ weak_ipm_

IntraProcessManagerWeakPtr rclcpp::SubscriptionBase::weak_ipm_
protected

◆ intra_process_subscription_id_

uint64_t rclcpp::SubscriptionBase::intra_process_subscription_id_
protected

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