15 #ifndef RCLCPP__MAPPED_RING_BUFFER_HPP_ 16 #define RCLCPP__MAPPED_RING_BUFFER_HPP_ 32 namespace mapped_ring_buffer
58 template<
typename T,
typename Alloc = std::allocator<
void>>
77 : elements_(size), head_(0)
83 allocator_ = std::make_shared<ElemAlloc>();
85 allocator_ = std::make_shared<ElemAlloc>(*allocator.get());
107 auto it = get_iterator_of_key(key);
109 if (it != elements_.end() && it->in_use) {
110 auto ptr = ElemAllocTraits::allocate(*allocator_.get(), 1);
111 ElemAllocTraits::construct(*allocator_.get(), ptr, *it->value);
140 auto it = get_iterator_of_key(key);
142 if (it != elements_.end() && it->in_use) {
144 auto ptr = ElemAllocTraits::allocate(*allocator_.get(), 1);
145 ElemAllocTraits::construct(*allocator_.get(), ptr, *it->value);
148 value.
swap(it->value);
150 it->value.swap(copy);
169 auto it = get_iterator_of_key(key);
171 if (it != elements_.end() && it->in_use) {
172 value.
swap(it->value);
193 bool did_replace = elements_[head_].in_use;
194 elements_[head_].key = key;
195 elements_[head_].value.swap(value);
196 elements_[head_].in_use =
true;
197 head_ = (head_ + 1) % elements_.size();
205 return push_and_replace(key, temp);
213 return elements_.end() != get_iterator_of_key(key);
229 get_iterator_of_key(uint64_t key)
232 auto it =
std::find_if(elements_.begin(), elements_.end(), [key](element & e) ->
bool {
233 return e.key == key && e.in_use;
248 #endif // RCLCPP__MAPPED_RING_BUFFER_HPP_
#define RCLCPP_DISABLE_COPY(...)
Definition: macros.hpp:26
typename ElemAllocTraits::allocator_type ElemAlloc
Definition: mapped_ring_buffer.hpp:64
Definition: allocator_common.hpp:24
void pop_at_key(uint64_t key, ElemUniquePtr &value)
Return ownership of the value stored in the ring buffer at the given key.
Definition: mapped_ring_buffer.hpp:166
Ring buffer container of unique_ptr's of T, which can be accessed by a key.
Definition: mapped_ring_buffer.hpp:59
allocator::AllocRebind< T, Alloc > ElemAllocTraits
Definition: mapped_ring_buffer.hpp:63
bool push_and_replace(uint64_t key, ElemUniquePtr &value)
Insert a key-value pair, displacing an existing pair if necessary.
Definition: mapped_ring_buffer.hpp:190
Definition: mapped_ring_buffer.hpp:35
virtual ~MappedRingBuffer()
Definition: mapped_ring_buffer.hpp:89
allocator::Deleter< ElemAlloc, T > ElemDeleter
Definition: mapped_ring_buffer.hpp:65
typename std::allocator_traits< Alloc >::template rebind_traits< T > AllocRebind
Definition: allocator_common.hpp:30
void get_ownership_at_key(uint64_t key, ElemUniquePtr &value)
Return ownership of the value stored in the ring buffer, leaving a copy.
Definition: mapped_ring_buffer.hpp:137
#define RCLCPP_SMART_PTR_DEFINITIONS(...)
Definition: macros.hpp:36
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.
Definition: mapped_ring_buffer.hpp:104
bool push_and_replace(uint64_t key, ElemUniquePtr &&value)
Definition: mapped_ring_buffer.hpp:202
#define RCLCPP_PUBLIC
Definition: visibility_control.hpp:50
typename std::conditional< std::is_same< typename std::allocator_traits< Alloc >::template rebind_alloc< T >, typename std::allocator< void >::template rebind< T >::other >::value, std::default_delete< T >, AllocatorDeleter< Alloc > >::type Deleter
Definition: allocator_deleter.hpp:101
bool has_key(uint64_t key)
Return true if the key is found in the ring buffer, otherwise false.
Definition: mapped_ring_buffer.hpp:210