rclcpp
master
C++ ROS Client Library API
|
Subscription implementation, templated on the type of message this subscription receives. More...
#include <subscription.hpp>
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_t * | get_intra_process_subscription_handle () const |
Implemenation detail. More... | |
Public Member Functions inherited from rclcpp::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... | |
rcl_subscription_t * | get_subscription_handle () |
const rcl_subscription_t * | get_subscription_handle () const |
Friends | |
class | rclcpp::node_interfaces::NodeTopicsInterface |
Additional Inherited Members | |
Protected Attributes inherited from rclcpp::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_t > | node_handle_ |
Subscription implementation, templated on the type of message this subscription receives.
using rclcpp::Subscription< MessageT, Alloc >::MessageAllocTraits = allocator::AllocRebind<MessageT, Alloc> |
using rclcpp::Subscription< MessageT, Alloc >::MessageAlloc = typename MessageAllocTraits::allocator_type |
using rclcpp::Subscription< MessageT, Alloc >::MessageDeleter = allocator::Deleter<MessageAlloc, MessageT> |
using rclcpp::Subscription< MessageT, Alloc >::MessageUniquePtr = std::unique_ptr<MessageT, MessageDeleter> |
using rclcpp::Subscription< MessageT, Alloc >::GetMessageCallbackType = std::function<void(uint64_t, uint64_t, uint64_t, MessageUniquePtr &)> |
using rclcpp::Subscription< MessageT, Alloc >::MatchesAnyPublishersCallbackType = std::function<bool(const rmw_gid_t *)> |
|
inline |
Default constructor.
The constructor for a subscription is almost never called directly. Instead, subscriptions should be instantiated through Node::create_subscription.
[in] | node_handle | rcl representation of the node that owns this subscription. |
[in] | topic_name | Name of the topic to subscribe to. |
[in] | subscription_options | options for the subscription. |
[in] | callback | User defined callback to call when a message is received. |
[in] | memory_strategy | The memory strategy to be used for managing message memory. |
|
inline |
Support dynamically setting the message memory strategy.
Behavior may be undefined if called while the subscription could be executing.
[in] | message_memory_strategy | Shared pointer to the memory strategy to set. |
|
inlinevirtual |
Borrow a new message.
Implements rclcpp::SubscriptionBase.
|
inlinevirtual |
Check if we need to handle the message, and execute the callback if we do.
[in] | message | Shared pointer to the message to handle. |
[in] | message_info | Metadata associated with this message. |
Implements rclcpp::SubscriptionBase.
|
inlinevirtual |
Return the loaned message.
message | message to be returned |
Implements rclcpp::SubscriptionBase.
|
inlinevirtual |
Implements rclcpp::SubscriptionBase.
|
inline |
Implemenation detail.
|
inlinevirtual |
Implemenation detail.
Reimplemented from rclcpp::SubscriptionBase.
|
friend |