rclcpp  beta1
C++ ROS Client Library API
Classes | Public Types | Public Member Functions | List of all members
rclcpp::mapped_ring_buffer::MappedRingBuffer< T, Alloc > Class Template Reference

Ring buffer container of unique_ptr's of T, which can be accessed by a key. More...

#include <mapped_ring_buffer.hpp>

Inheritance diagram for rclcpp::mapped_ring_buffer::MappedRingBuffer< T, Alloc >:
rclcpp::mapped_ring_buffer::MappedRingBufferBase

Public Types

using ElemAllocTraits = allocator::AllocRebind< T, Alloc >
 
using ElemAlloc = typename ElemAllocTraits::allocator_type
 
using ElemDeleter = allocator::Deleter< ElemAlloc, T >
 
using ElemUniquePtr = std::unique_ptr< T, ElemDeleter >
 

Public Member Functions

 MappedRingBuffer (size_t size, std::shared_ptr< Alloc > allocator=nullptr)
 Constructor. More...
 
virtual ~MappedRingBuffer ()
 
void get_copy_at_key (uint64_t key, ElemUniquePtr &value)
 Return a copy of the value stored in the ring buffer at the given key. More...
 
void get_ownership_at_key (uint64_t key, ElemUniquePtr &value)
 Return ownership of the value stored in the ring buffer, leaving a copy. More...
 
void pop_at_key (uint64_t key, ElemUniquePtr &value)
 Return ownership of the value stored in the ring buffer at the given key. More...
 
bool push_and_replace (uint64_t key, ElemUniquePtr &value)
 Insert a key-value pair, displacing an existing pair if necessary. More...
 
bool push_and_replace (uint64_t key, ElemUniquePtr &&value)
 
bool has_key (uint64_t key)
 Return true if the key is found in the ring buffer, otherwise false. More...
 

Detailed Description

template<typename T, typename Alloc = std::allocator<void>>
class rclcpp::mapped_ring_buffer::MappedRingBuffer< T, Alloc >

Ring buffer container of unique_ptr's of T, which can be accessed by a key.

T must be a CopyConstructable and CopyAssignable. This class can be used in a container by using the base class MappedRingBufferBase. This class must have a positive, non-zero size. This class cannot be resized nor can it reserve additional space after construction. This class is not CopyConstructable nor CopyAssignable.

The key's are not guaranteed to be unique because push_and_replace does not check for colliding keys. It is up to the user to only use unique keys. A side effect of this is that when get_copy_at_key or pop_at_key are called, they return the first encountered instance of the key. But iteration does not begin with the ring buffer's head, and therefore there is no guarantee on which value is returned if a key is used multiple times.

Member Typedef Documentation

§ ElemAllocTraits

template<typename T , typename Alloc = std::allocator<void>>
using rclcpp::mapped_ring_buffer::MappedRingBuffer< T, Alloc >::ElemAllocTraits = allocator::AllocRebind<T, Alloc>

§ ElemAlloc

template<typename T , typename Alloc = std::allocator<void>>
using rclcpp::mapped_ring_buffer::MappedRingBuffer< T, Alloc >::ElemAlloc = typename ElemAllocTraits::allocator_type

§ ElemDeleter

template<typename T , typename Alloc = std::allocator<void>>
using rclcpp::mapped_ring_buffer::MappedRingBuffer< T, Alloc >::ElemDeleter = allocator::Deleter<ElemAlloc, T>

§ ElemUniquePtr

template<typename T , typename Alloc = std::allocator<void>>
using rclcpp::mapped_ring_buffer::MappedRingBuffer< T, Alloc >::ElemUniquePtr = std::unique_ptr<T, ElemDeleter>

Constructor & Destructor Documentation

§ MappedRingBuffer()

template<typename T , typename Alloc = std::allocator<void>>
rclcpp::mapped_ring_buffer::MappedRingBuffer< T, Alloc >::MappedRingBuffer ( size_t  size,
std::shared_ptr< Alloc >  allocator = nullptr 
)
inlineexplicit

Constructor.

The constructor will allocate memory while reserving space.

Parameters
sizesize of the ring buffer; must be positive and non-zero.
allocatoroptional custom allocator

§ ~MappedRingBuffer()

template<typename T , typename Alloc = std::allocator<void>>
virtual rclcpp::mapped_ring_buffer::MappedRingBuffer< T, Alloc >::~MappedRingBuffer ( )
inlinevirtual

Member Function Documentation

§ get_copy_at_key()

template<typename T , typename Alloc = std::allocator<void>>
void rclcpp::mapped_ring_buffer::MappedRingBuffer< T, Alloc >::get_copy_at_key ( uint64_t  key,
ElemUniquePtr value 
)
inline

Return a copy of the value stored in the ring buffer at the given key.

The key is matched if an element in the ring buffer has a matching key. This method will allocate in order to return a copy.

The key is not guaranteed to be unique, see the class docs for more.

The contents of value before the method is called are discarded.

Parameters
keythe key associated with the stored value
valueif the key is found, the value is stored in this parameter

§ get_ownership_at_key()

template<typename T , typename Alloc = std::allocator<void>>
void rclcpp::mapped_ring_buffer::MappedRingBuffer< T, Alloc >::get_ownership_at_key ( uint64_t  key,
ElemUniquePtr value 
)
inline

Return ownership of the value stored in the ring buffer, leaving a copy.

The key is matched if an element in the ring bufer has a matching key. This method will allocate in order to store a copy.

The key is not guaranteed to be unique, see the class docs for more.

The ownership of the currently stored object is returned, but a copy is made and stored in its place. This means that multiple calls to this function for a particular element will result in returning the copied and stored object not the original. This also means that later calls to pop_at_key will not return the originally stored object, since it was returned by the first call to this method.

The contents of value before the method is called are discarded.

Parameters
keythe key associated with the stored value
valueif the key is found, the value is stored in this parameter

§ pop_at_key()

template<typename T , typename Alloc = std::allocator<void>>
void rclcpp::mapped_ring_buffer::MappedRingBuffer< T, Alloc >::pop_at_key ( uint64_t  key,
ElemUniquePtr value 
)
inline

Return ownership of the value stored in the ring buffer at the given key.

The key is matched if an element in the ring buffer has a matching key.

The key is not guaranteed to be unique, see the class docs for more.

The contents of value before the method is called are discarded.

Parameters
keythe key associated with the stored value
valueif the key is found, the value is stored in this parameter

§ push_and_replace() [1/2]

template<typename T , typename Alloc = std::allocator<void>>
bool rclcpp::mapped_ring_buffer::MappedRingBuffer< T, Alloc >::push_and_replace ( uint64_t  key,
ElemUniquePtr value 
)
inline

Insert a key-value pair, displacing an existing pair if necessary.

The key's uniqueness is not checked on insertion. It is up to the user to ensure the key is unique. This method should not allocate memory.

After insertion, if a pair was replaced, then value will contain ownership of that displaced value. Otherwise it will be a nullptr.

Parameters
keythe key associated with the value to be stored
valuethe value to store, and optionally the value displaced

§ push_and_replace() [2/2]

template<typename T , typename Alloc = std::allocator<void>>
bool rclcpp::mapped_ring_buffer::MappedRingBuffer< T, Alloc >::push_and_replace ( uint64_t  key,
ElemUniquePtr &&  value 
)
inline

§ has_key()

template<typename T , typename Alloc = std::allocator<void>>
bool rclcpp::mapped_ring_buffer::MappedRingBuffer< T, Alloc >::has_key ( uint64_t  key)
inline

Return true if the key is found in the ring buffer, otherwise false.


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