Template Class Subscription
Defined in File subscription.hpp
Inheritance Relationships
Base Type
public rclcpp::SubscriptionBase
(Class SubscriptionBase)
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>
-
using MessageAllocatorTraits = ROSMessageTypeAllocatorTraits
-
using MessageAllocator = ROSMessageTypeAllocator
-
using MessageDeleter = ROSMessageTypeDeleter
-
using MessageUniquePtr = std::unique_ptr<ROSMessageType, ROSMessageTypeDeleter>
Public Functions
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.
See also
- 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.
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_loaned_message(void *loaned_message, const rclcpp::MessageInfo &message_info) override
Return the borrowed message.
- Parameters:
message – [inout] message to be returned
Return the borrowed serialized message.
- Parameters:
message – [inout] serialized message to be returned
-
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.
Friends
- friend class rclcpp::node_interfaces::NodeTopicsInterface
-
using SubscribedType = SubscribedT