Template Class Subscription

Inheritance Relationships

Base Type

Class Documentation

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 Subscription : public rclcpp::SubscriptionBase

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

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>

Public Functions

inline 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.

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

Parameters:
  • node_base[in] NodeBaseInterface pointer that is used in part of the setup.

  • type_support_handle[in] rosidl type support struct, for the Message type of the topic.

  • topic_name[in] Name of the topic to subscribe to.

  • qos[in] QoS profile for Subcription.

  • callback[in] User defined callback to call when a message is received.

  • options[in] Options for the subscription.

  • message_memory_strategy – The memory strategy to be used for managing message memory.

  • subscription_topic_statistics[in] Optional pointer to a topic statistics subcription.

Throws:

std::invalid_argument – if 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).

inline 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().

inline bool take(ROSMessageType &message_out, rclcpp::MessageInfo &message_info_out)

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.

Parameters:
  • message_out[out] The message into which take will copy the data.

  • message_info_out[out] The message info for the taken message.

Throws:

any – rcl errors from rcl_take,

Returns:

true if data was taken and is valid, otherwise false

template<typename TakeT>
inline 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.

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

inline virtual std::shared_ptr<void> create_message() override

Borrow a new message.

Returns:

Shared pointer to the fresh message.

inline virtual std::shared_ptr<rclcpp::SerializedMessage> create_serialized_message() override

Borrow a new serialized message.

Returns:

Shared pointer to a rcl_message_serialized_t.

inline virtual void disable_callbacks() override

Disable callbacks from being called.

This method will block, until any subscription’s callbacks provided during construction currently being executed are finished.

Note

This method also temporary removes the on new message callback and all on new event callbacks from the rmw layer to prevent them from being called. However, this method will not block and wait until the currently executing on_new_[message]event callbacks are finished.

inline virtual void enable_callbacks() override

Enable the callbacks to be called.

This method is thread safe, and provides a safe way to atomically enable the callbacks in a multithreaded environment.

inline virtual 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.

Parameters:
  • message[in] Shared pointer to the message to handle.

  • message_info[in] Metadata associated with this message.

inline virtual void handle_serialized_message(const std::shared_ptr<rclcpp::SerializedMessage> &serialized_message, const rclcpp::MessageInfo &message_info) override
inline virtual void handle_loaned_message(void *loaned_message, const rclcpp::MessageInfo &message_info) override
inline virtual void return_message(std::shared_ptr<void> &message) override

Return the borrowed message.

Parameters:

message[inout] message to be returned

inline virtual void return_serialized_message(std::shared_ptr<rclcpp::SerializedMessage> &message) override

Return the borrowed serialized message.

Parameters:

message[inout] serialized message to be returned

inline bool use_take_shared_method() const
inline virtual rclcpp::dynamic_typesupport::DynamicMessageType::SharedPtr get_shared_dynamic_message_type() override
inline virtual rclcpp::dynamic_typesupport::DynamicMessage::SharedPtr get_shared_dynamic_message() override
inline virtual rclcpp::dynamic_typesupport::DynamicSerializationSupport::SharedPtr get_shared_dynamic_serialization_support() override
inline virtual rclcpp::dynamic_typesupport::DynamicMessage::SharedPtr create_dynamic_message() override

Borrow a new serialized message (this clones!)

Returns:

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

inline virtual void return_dynamic_message(rclcpp::dynamic_typesupport::DynamicMessage::SharedPtr &message) override
inline virtual void handle_dynamic_message(const rclcpp::dynamic_typesupport::DynamicMessage::SharedPtr &message, const rclcpp::MessageInfo &message_info) override

Friends

friend class rclcpp::node_interfaces::NodeTopicsInterface