rclcpp
master
C++ ROS Client Library API
|
Default allocation strategy for messages received by subscriptions. More...
#include <message_memory_strategy.hpp>
Public Types | |
using | MessageAllocTraits = allocator::AllocRebind< MessageT, Alloc > |
using | MessageAlloc = typename MessageAllocTraits::allocator_type |
using | MessageDeleter = allocator::Deleter< MessageAlloc, MessageT > |
Public Member Functions | |
MessageMemoryStrategy () | |
MessageMemoryStrategy (std::shared_ptr< Alloc > allocator) | |
virtual std::shared_ptr< MessageT > | borrow_message () |
By default, dynamically allocate a new message. More... | |
virtual void | return_message (std::shared_ptr< MessageT > &msg) |
Release ownership of the message, which will deallocate it if it has no more owners. More... | |
Static Public Member Functions | |
static SharedPtr | create_default () |
Default factory method. More... | |
Public Attributes | |
std::shared_ptr< MessageAlloc > | message_allocator_ |
MessageDeleter | message_deleter_ |
Default allocation strategy for messages received by subscriptions.
A message memory strategy must be templated on the type of the subscription it belongs to.
using rclcpp::message_memory_strategy::MessageMemoryStrategy< MessageT, Alloc >::MessageAllocTraits = allocator::AllocRebind<MessageT, Alloc> |
using rclcpp::message_memory_strategy::MessageMemoryStrategy< MessageT, Alloc >::MessageAlloc = typename MessageAllocTraits::allocator_type |
using rclcpp::message_memory_strategy::MessageMemoryStrategy< MessageT, Alloc >::MessageDeleter = allocator::Deleter<MessageAlloc, MessageT> |
|
inline |
|
inlineexplicit |
|
inlinestatic |
Default factory method.
|
inlinevirtual |
By default, dynamically allocate a new message.
Reimplemented in rclcpp::strategies::message_pool_memory_strategy::MessagePoolMemoryStrategy< MessageT, Size, >.
|
inlinevirtual |
Release ownership of the message, which will deallocate it if it has no more owners.
[in] | msg | Shared pointer to the message we are returning. |
Reimplemented in rclcpp::strategies::message_pool_memory_strategy::MessagePoolMemoryStrategy< MessageT, Size, >.
std::shared_ptr<MessageAlloc> rclcpp::message_memory_strategy::MessageMemoryStrategy< MessageT, Alloc >::message_allocator_ |
MessageDeleter rclcpp::message_memory_strategy::MessageMemoryStrategy< MessageT, Alloc >::message_deleter_ |