rclcpp  master
C++ ROS Client Library API
Public Types | Public Member Functions | Static Public Member Functions | Public Attributes | List of all members
rclcpp::message_memory_strategy::MessageMemoryStrategy< MessageT, Alloc > Class Template Reference

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< MessageAllocmessage_allocator_
 
MessageDeleter message_deleter_
 

Detailed Description

template<typename MessageT, typename Alloc = std::allocator<void>>
class rclcpp::message_memory_strategy::MessageMemoryStrategy< MessageT, Alloc >

Default allocation strategy for messages received by subscriptions.

A message memory strategy must be templated on the type of the subscription it belongs to.

Member Typedef Documentation

◆ MessageAllocTraits

template<typename MessageT, typename Alloc = std::allocator<void>>
using rclcpp::message_memory_strategy::MessageMemoryStrategy< MessageT, Alloc >::MessageAllocTraits = allocator::AllocRebind<MessageT, Alloc>

◆ MessageAlloc

template<typename MessageT, typename Alloc = std::allocator<void>>
using rclcpp::message_memory_strategy::MessageMemoryStrategy< MessageT, Alloc >::MessageAlloc = typename MessageAllocTraits::allocator_type

◆ MessageDeleter

template<typename MessageT, typename Alloc = std::allocator<void>>
using rclcpp::message_memory_strategy::MessageMemoryStrategy< MessageT, Alloc >::MessageDeleter = allocator::Deleter<MessageAlloc, MessageT>

Constructor & Destructor Documentation

◆ MessageMemoryStrategy() [1/2]

template<typename MessageT, typename Alloc = std::allocator<void>>
rclcpp::message_memory_strategy::MessageMemoryStrategy< MessageT, Alloc >::MessageMemoryStrategy ( )
inline

◆ MessageMemoryStrategy() [2/2]

template<typename MessageT, typename Alloc = std::allocator<void>>
rclcpp::message_memory_strategy::MessageMemoryStrategy< MessageT, Alloc >::MessageMemoryStrategy ( std::shared_ptr< Alloc >  allocator)
inlineexplicit

Member Function Documentation

◆ create_default()

template<typename MessageT, typename Alloc = std::allocator<void>>
static SharedPtr rclcpp::message_memory_strategy::MessageMemoryStrategy< MessageT, Alloc >::create_default ( )
inlinestatic

Default factory method.

◆ borrow_message()

template<typename MessageT, typename Alloc = std::allocator<void>>
virtual std::shared_ptr<MessageT> rclcpp::message_memory_strategy::MessageMemoryStrategy< MessageT, Alloc >::borrow_message ( )
inlinevirtual

By default, dynamically allocate a new message.

Returns
Shared pointer to the new message.

Reimplemented in rclcpp::strategies::message_pool_memory_strategy::MessagePoolMemoryStrategy< MessageT, Size, >.

◆ return_message()

template<typename MessageT, typename Alloc = std::allocator<void>>
virtual void rclcpp::message_memory_strategy::MessageMemoryStrategy< MessageT, Alloc >::return_message ( std::shared_ptr< MessageT > &  msg)
inlinevirtual

Release ownership of the message, which will deallocate it if it has no more owners.

Parameters
[in]msgShared pointer to the message we are returning.

Reimplemented in rclcpp::strategies::message_pool_memory_strategy::MessagePoolMemoryStrategy< MessageT, Size, >.

Member Data Documentation

◆ message_allocator_

template<typename MessageT, typename Alloc = std::allocator<void>>
std::shared_ptr<MessageAlloc> rclcpp::message_memory_strategy::MessageMemoryStrategy< MessageT, Alloc >::message_allocator_

◆ message_deleter_

template<typename MessageT, typename Alloc = std::allocator<void>>
MessageDeleter rclcpp::message_memory_strategy::MessageMemoryStrategy< MessageT, Alloc >::message_deleter_

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