rclcpp  beta1
C++ ROS Client Library API
mapped_ring_buffer.hpp
Go to the documentation of this file.
1 // Copyright 2015 Open Source Robotics Foundation, Inc.
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #ifndef RCLCPP__MAPPED_RING_BUFFER_HPP_
16 #define RCLCPP__MAPPED_RING_BUFFER_HPP_
17 
18 #include <algorithm>
19 #include <cstddef>
20 #include <cstdint>
21 #include <memory>
22 #include <mutex>
23 #include <utility>
24 #include <vector>
25 
27 #include "rclcpp/macros.hpp"
29 
30 namespace rclcpp
31 {
32 namespace mapped_ring_buffer
33 {
34 
36 {
37 public:
39 };
40 
42 
58 template<typename T, typename Alloc = std::allocator<void>>
60 {
61 public:
63  using ElemAllocTraits = allocator::AllocRebind<T, Alloc>;
64  using ElemAlloc = typename ElemAllocTraits::allocator_type;
65  using ElemDeleter = allocator::Deleter<ElemAlloc, T>;
66 
67  using ElemUniquePtr = std::unique_ptr<T, ElemDeleter>;
68 
70 
76  explicit MappedRingBuffer(size_t size, std::shared_ptr<Alloc> allocator = nullptr)
77  : elements_(size), head_(0)
78  {
79  if (size == 0) {
80  throw std::invalid_argument("size must be a positive, non-zero value");
81  }
82  if (!allocator) {
83  allocator_ = std::make_shared<ElemAlloc>();
84  } else {
85  allocator_ = std::make_shared<ElemAlloc>(*allocator.get());
86  }
87  }
88 
89  virtual ~MappedRingBuffer() {}
90 
92 
103  void
104  get_copy_at_key(uint64_t key, ElemUniquePtr & value)
105  {
106  std::lock_guard<std::mutex> lock(data_mutex_);
107  auto it = get_iterator_of_key(key);
108  value = nullptr;
109  if (it != elements_.end() && it->in_use) {
110  auto ptr = ElemAllocTraits::allocate(*allocator_.get(), 1);
111  ElemAllocTraits::construct(*allocator_.get(), ptr, *it->value);
112  value = ElemUniquePtr(ptr);
113  }
114  }
115 
117 
136  void
137  get_ownership_at_key(uint64_t key, ElemUniquePtr & value)
138  {
139  std::lock_guard<std::mutex> lock(data_mutex_);
140  auto it = get_iterator_of_key(key);
141  value = nullptr;
142  if (it != elements_.end() && it->in_use) {
143  // Make a copy.
144  auto ptr = ElemAllocTraits::allocate(*allocator_.get(), 1);
145  ElemAllocTraits::construct(*allocator_.get(), ptr, *it->value);
146  auto copy = ElemUniquePtr(ptr);
147  // Return the original.
148  value.swap(it->value);
149  // Store the copy.
150  it->value.swap(copy);
151  }
152  }
153 
155 
165  void
166  pop_at_key(uint64_t key, ElemUniquePtr & value)
167  {
168  std::lock_guard<std::mutex> lock(data_mutex_);
169  auto it = get_iterator_of_key(key);
170  value = nullptr;
171  if (it != elements_.end() && it->in_use) {
172  value.swap(it->value);
173  it->in_use = false;
174  }
175  }
176 
178 
189  bool
190  push_and_replace(uint64_t key, ElemUniquePtr & value)
191  {
192  std::lock_guard<std::mutex> lock(data_mutex_);
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();
198  return did_replace;
199  }
200 
201  bool
202  push_and_replace(uint64_t key, ElemUniquePtr && value)
203  {
204  ElemUniquePtr temp = std::move(value);
205  return push_and_replace(key, temp);
206  }
207 
209  bool
210  has_key(uint64_t key)
211  {
212  std::lock_guard<std::mutex> lock(data_mutex_);
213  return elements_.end() != get_iterator_of_key(key);
214  }
215 
216 private:
218 
219  struct element
220  {
221  uint64_t key;
222  ElemUniquePtr value;
223  bool in_use;
224  };
225 
226  using VectorAlloc = typename std::allocator_traits<Alloc>::template rebind_alloc<element>;
227 
229  get_iterator_of_key(uint64_t key)
230  {
231  // *INDENT-OFF* (prevent uncrustify from making unnecessary indents here)
232  auto it = std::find_if(elements_.begin(), elements_.end(), [key](element & e) -> bool {
233  return e.key == key && e.in_use;
234  });
235  // *INDENT-ON*
236  return it;
237  }
238 
240  size_t head_;
241  std::shared_ptr<ElemAlloc> allocator_;
242  std::mutex data_mutex_;
243 };
244 
245 } // namespace mapped_ring_buffer
246 } // namespace rclcpp
247 
248 #endif // RCLCPP__MAPPED_RING_BUFFER_HPP_
#define RCLCPP_DISABLE_COPY(...)
Definition: macros.hpp:26
T swap(T... args)
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&#39;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
T move(T... args)
bool push_and_replace(uint64_t key, ElemUniquePtr &&value)
Definition: mapped_ring_buffer.hpp:202
T find_if(T... args)
#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