readerwriterqueue.h
Go to the documentation of this file.
1 // ©2013-2016 Cameron Desrochers.
2 // Distributed under the simplified BSD license (see the license file that
3 // should have come with this header).
4 
5 #pragma once
6 
7 #include <cassert>
8 #include <cstdint>
9 #include <cstdlib> // For malloc/free/abort & size_t
10 #include <new>
11 #include <stdexcept>
12 #include <type_traits>
13 #include <utility>
14 #include "atomicops.h"
15 #if __cplusplus > 199711L || _MSC_VER >= 1700 // C++11 or VS2012
16 #include <chrono>
17 #endif
18 
19 // A lock-free queue for a single-consumer, single-producer architecture.
20 // The queue is also wait-free in the common path (except if more memory
21 // needs to be allocated, in which case malloc is called).
22 // Allocates memory sparingly (O(lg(n) times, amortized), and only once if
23 // the original maximum size estimate is never exceeded.
24 // Tested on x86/x64 processors, but semantics should be correct for all
25 // architectures (given the right implementations in atomicops.h), provided
26 // that aligned integer and pointer accesses are naturally atomic.
27 // Note that there should only be one consumer thread and producer thread;
28 // Switching roles of the threads, or using multiple consecutive threads for
29 // one role, is not safe unless properly synchronized.
30 // Using the queue exclusively from one thread is fine, though a bit silly.
31 
32 #ifndef MOODYCAMEL_CACHE_LINE_SIZE
33 #define MOODYCAMEL_CACHE_LINE_SIZE 64
34 #endif
35 
36 #ifndef MOODYCAMEL_EXCEPTIONS_ENABLED
37 #if (defined(_MSC_VER) && defined(_CPPUNWIND)) || (defined(__GNUC__) && defined(__EXCEPTIONS)) || \
38  (!defined(_MSC_VER) && !defined(__GNUC__))
39 #define MOODYCAMEL_EXCEPTIONS_ENABLED
40 #endif
41 #endif
42 
43 #ifdef AE_VCPP
44 #pragma warning(push)
45 #pragma warning(disable : 4324) // structure was padded due to __declspec(align())
46 #pragma warning(disable : 4820) // padding was added
47 #pragma warning(disable : 4127) // conditional expression is constant
48 #endif
49 
50 namespace moodycamel
51 {
52 template <typename T, size_t MAX_BLOCK_SIZE = 512>
54 {
55  // Design: Based on a queue-of-queues. The low-level queues are just
56  // circular buffers with front and tail indices indicating where the
57  // next element to dequeue is and where the next element can be enqueued,
58  // respectively. Each low-level queue is called a "block". Each block
59  // wastes exactly one element's worth of space to keep the design simple
60  // (if front == tail then the queue is empty, and can't be full).
61  // The high-level queue is a circular linked list of blocks; again there
62  // is a front and tail, but this time they are pointers to the blocks.
63  // The front block is where the next element to be dequeued is, provided
64  // the block is not empty. The back block is where elements are to be
65  // enqueued, provided the block is not full.
66  // The producer thread owns all the tail indices/pointers. The consumer
67  // thread owns all the front indices/pointers. Both threads read each
68  // other's variables, but only the owning thread updates them. E.g. After
69  // the consumer reads the producer's tail, the tail may change before the
70  // consumer is done dequeuing_ an object, but the consumer knows the tail
71  // will never go backwards, only forwards.
72  // If there is no room to enqueue an object, an additional block (of
73  // equal size to the last block) is added. Blocks are never removed.
74 
75 public:
76  // Constructs a queue that can hold maxSize elements without further
77  // allocations. If more than MAX_BLOCK_SIZE elements are requested,
78  // then several blocks of MAX_BLOCK_SIZE each are reserved (including
79  // at least one extra buffer block).
80  explicit ReaderWriterQueue(size_t max_size = 15)
81 #ifndef NDEBUG
82  : enqueuing_(false), dequeuing_(false)
83 #endif
84  {
85  assert(max_size > 0);
86  assert(MAX_BLOCK_SIZE == ceilToPow2(MAX_BLOCK_SIZE) && "MAX_BLOCK_SIZE must be a power of 2");
87  assert(MAX_BLOCK_SIZE >= 2 && "MAX_BLOCK_SIZE must be at least 2");
88 
89  Block* first_block = nullptr;
90 
91  largest_block_size_ = ceilToPow2(max_size + 1); // We need a spare slot to fit maxSize elements in the block
92  if (largest_block_size_ > MAX_BLOCK_SIZE * 2)
93  {
94  // We need a spare block in case the producer is writing to a different block the consumer is reading from, and
95  // wants to enqueue the maximum number of elements. We also need a spare element in each block to avoid the
96  // ambiguity
97  // between front == tail meaning "empty" and "full".
98  // So the effective number of slots that are guaranteed to be usable at any time is the block size - 1 times the
99  // number of blocks - 1. Solving for maxSize and applying a ceiling to the division gives us (after simplifying):
100  size_t initial_block_count = (max_size + MAX_BLOCK_SIZE * 2 - 3) / (MAX_BLOCK_SIZE - 1);
101  largest_block_size_ = MAX_BLOCK_SIZE;
102  Block* last_block = nullptr;
103  for (size_t i = 0; i != initial_block_count; ++i)
104  {
105  auto block = makeBlock(largest_block_size_);
106  if (block == nullptr)
107  {
108 #ifdef MOODYCAMEL_EXCEPTIONS_ENABLED
109  throw std::bad_alloc();
110 #else
111  abort();
112 #endif
113  }
114  if (first_block == nullptr)
115  {
116  first_block = block;
117  }
118  else
119  {
120  last_block->next = block;
121  }
122  last_block = block;
123  block->next = first_block;
124  }
125  }
126  else
127  {
128  first_block = makeBlock(largest_block_size_);
129  if (first_block == nullptr)
130  {
131 #ifdef MOODYCAMEL_EXCEPTIONS_ENABLED
132  throw std::bad_alloc();
133 #else
134  abort();
135 #endif
136  }
137  first_block->next = first_block;
138  }
139  front_block_ = first_block;
140  tail_block_ = first_block;
141 
142  // Make sure the reader/writer threads will have the initialized memory setup above:
144  }
145 
146  // Note: The queue should not be accessed concurrently while it's
147  // being deleted. It's up to the user to synchronize this.
149  {
150  // Make sure we get the latest version of all variables from other CPUs:
152 
153  // Destroy any remaining objects in queue and free memory
154  Block* front_block = front_block_;
155  Block* block = front_block;
156  do
157  {
158  Block* next_block = block->next;
159  size_t block_front = block->front;
160  size_t block_tail = block->tail;
161 
162  for (size_t i = block_front; i != block_tail; i = (i + 1) & block->sizeMask)
163  {
164  auto element = reinterpret_cast<T*>(block->data + i * sizeof(T));
165  element->~T();
166  (void)element;
167  }
168 
169  auto raw_block = block->rawThis;
170  block->~Block();
171  std::free(raw_block);
172  block = next_block;
173  } while (block != front_block);
174  }
175 
176  // Enqueues a copy of element if there is room in the queue.
177  // Returns true if the element was enqueued, false otherwise.
178  // Does not allocate memory.
179  AE_FORCEINLINE bool tryEnqueue(T const& element)
180  {
181  return innerEnqueue<CannotAlloc>(element);
182  }
183 
184  // Enqueues a moved copy of element if there is room in the queue.
185  // Returns true if the element was enqueued, false otherwise.
186  // Does not allocate memory.
187  AE_FORCEINLINE bool tryEnqueue(T&& element)
188  {
189  return innerEnqueue<CannotAlloc>(std::forward<T>(element));
190  }
191 
192  // Enqueues a copy of element on the queue.
193  // Allocates an additional block of memory if needed.
194  // Only fails (returns false) if memory allocation fails.
195  AE_FORCEINLINE bool enqueue(T const& element)
196  {
197  return innerEnqueue<CanAlloc>(element);
198  }
199 
200  // Enqueues a moved copy of element on the queue.
201  // Allocates an additional block of memory if needed.
202  // Only fails (returns false) if memory allocation fails.
203  AE_FORCEINLINE bool enqueue(T&& element)
204  {
205  return innerEnqueue<CanAlloc>(std::forward<T>(element));
206  }
207 
208  // Attempts to dequeue an element; if the queue is empty,
209  // returns false instead. If the queue has at least one element,
210  // moves front to result using operator=, then returns true.
211  template <typename U>
212  bool tryDequeue(U& result)
213  {
214 #ifndef NDEBUG
215  ReentrantGuard guard(this->dequeuing_);
216 #endif
217 
218  // High-level pseudocode:
219  // Remember where the tail block is
220  // If the front block has an element in it, dequeue it
221  // Else
222  // If front block was the tail block when we entered the function, return false
223  // Else advance to next block and dequeue the item there
224 
225  // Note that we have to use the value of the tail block from before we check if the front
226  // block is full or not, in case the front block is empty and then, before we check if the
227  // tail block is at the front block or not, the producer fills up the front block *and
228  // moves on*, which would make us skip a filled block. Seems unlikely, but was consistently
229  // reproducible in practice.
230  // In order to avoid overhead in the common case, though, we do a double-checked pattern
231  // where we have the fast path if the front block is not empty, then read the tail block,
232  // then re-read the front block and check if it's not empty again, then check if the tail
233  // block has advanced.
234 
235  Block* front_block = front_block_.load();
236  size_t block_tail = front_block->localTail;
237  size_t block_front = front_block->front.load();
238 
239  if (block_front != block_tail || block_front != (front_block->localTail = front_block->tail.load()))
240  {
242 
243  non_empty_front_block:
244  // Front block not empty, dequeue from here
245  auto element = reinterpret_cast<T*>(front_block->data + block_front * sizeof(T));
246  result = std::move(*element);
247  element->~T();
248 
249  block_front = (block_front + 1) & front_block->sizeMask;
250 
252  front_block->front = block_front;
253  }
254  else if (front_block != tail_block_.load())
255  {
257 
258  front_block = front_block_.load();
259  block_tail = front_block->localTail = front_block->tail.load();
260  block_front = front_block->front.load();
262 
263  if (block_front != block_tail)
264  {
265  // Oh look, the front block isn't empty after all
266  goto non_empty_front_block;
267  }
268 
269  // Front block is empty but there's another block ahead, advance to it
270  Block* next_block = front_block->next;
271  // Don't need an acquire fence here since next can only ever be set on the tail_block,
272  // and we're not the tail_block, and we did an acquire earlier after reading tail_block which
273  // ensures next is up-to-date on this CPU in case we recently were at tail_block.
274 
275  size_t next_block_front = next_block->front.load();
276  size_t next_block_tail = next_block->localTail = next_block->tail.load();
278 
279  // Since the tail_block is only ever advanced after being written to,
280  // we know there's for sure an element to dequeue on it
281  assert(next_block_front != next_block_tail);
282  AE_UNUSED(next_block_tail);
283 
284  // We're done with this block, let the producer use it if it needs
285  fence(memory_order_release); // Expose possibly pending changes to front_block->front from last dequeue
286  front_block_ = front_block = next_block;
287 
288  compilerFence(memory_order_release); // Not strictly needed
289 
290  auto element = reinterpret_cast<T*>(front_block->data + next_block_front * sizeof(T));
291 
292  result = std::move(*element);
293  element->~T();
294 
295  next_block_front = (next_block_front + 1) & front_block->sizeMask;
296 
298  front_block->front = next_block_front;
299  }
300  else
301  {
302  // No elements in current block and no other block to advance to
303  return false;
304  }
305 
306  return true;
307  }
308 
309  // Returns a pointer to the front element in the queue (the one that
310  // would be removed next by a call to `tryDequeue` or `pop`). If the
311  // queue appears empty at the time the method is called, nullptr is
312  // returned instead.
313  // Must be called only from the consumer thread.
314  T* peek()
315  {
316 #ifndef NDEBUG
317  ReentrantGuard guard(this->dequeuing_);
318 #endif
319  // See tryDequeue() for reasoning
320 
321  Block* front_block = front_block_.load();
322  size_t block_tail = front_block->localTail;
323  size_t block_front = front_block->front.load();
324 
325  if (block_front != block_tail || block_front != (front_block->localTail = front_block->tail.load()))
326  {
328  non_empty_front_block:
329  return reinterpret_cast<T*>(front_block->data + block_front * sizeof(T));
330  }
331  else if (front_block != tail_block_.load())
332  {
334  front_block = front_block_.load();
335  block_tail = front_block->localTail = front_block->tail.load();
336  block_front = front_block->front.load();
338 
339  if (block_front != block_tail)
340  {
341  goto non_empty_front_block;
342  }
343 
344  Block* next_block = front_block->next;
345 
346  size_t next_block_front = next_block->front.load();
348 
349  assert(next_block_front != next_block->tail.load());
350  return reinterpret_cast<T*>(next_block->data + next_block_front * sizeof(T));
351  }
352 
353  return nullptr;
354  }
355 
356  // Removes the front element from the queue, if any, without returning it.
357  // Returns true on success, or false if the queue appeared empty at the time
358  // `pop` was called.
359  bool pop()
360  {
361 #ifndef NDEBUG
362  ReentrantGuard guard(this->dequeuing_);
363 #endif
364  // See tryDequeue() for reasoning
365 
366  Block* front_block = front_block_.load();
367  size_t block_tail = front_block->localTail;
368  size_t block_front = front_block->front.load();
369 
370  if (block_front != block_tail || block_front != (front_block->localTail = front_block->tail.load()))
371  {
373 
374  non_empty_front_block:
375  auto element = reinterpret_cast<T*>(front_block->data + block_front * sizeof(T));
376  element->~T();
377 
378  block_front = (block_front + 1) & front_block->sizeMask;
379 
381  front_block->front = block_front;
382  }
383  else if (front_block != tail_block_.load())
384  {
386  front_block = front_block_.load();
387  block_tail = front_block->localTail = front_block->tail.load();
388  block_front = front_block->front.load();
390 
391  if (block_front != block_tail)
392  {
393  goto non_empty_front_block;
394  }
395 
396  // Front block is empty but there's another block ahead, advance to it
397  Block* next_block = front_block->next;
398 
399  size_t next_block_front = next_block->front.load();
400  size_t next_block_tail = next_block->localTail = next_block->tail.load();
402 
403  assert(next_block_front != next_block_tail);
404  AE_UNUSED(next_block_tail);
405 
407  front_block_ = front_block = next_block;
408 
410 
411  auto element = reinterpret_cast<T*>(front_block->data + next_block_front * sizeof(T));
412  element->~T();
413 
414  next_block_front = (next_block_front + 1) & front_block->sizeMask;
415 
417  front_block->front = next_block_front;
418  }
419  else
420  {
421  // No elements in current block and no other block to advance to
422  return false;
423  }
424 
425  return true;
426  }
427 
428  // Returns the approximate number of items currently in the queue.
429  // Safe to call from both the producer and consumer threads.
430  inline size_t sizeApprox() const
431  {
432  size_t result = 0;
433  Block* front_block = front_block_.load();
434  Block* block = front_block;
435  do
436  {
438  size_t block_front = block->front.load();
439  size_t block_tail = block->tail.load();
440  result += (block_tail - block_front) & block->sizeMask;
441  block = block->next.load();
442  } while (block != front_block);
443  return result;
444  }
445 
446 private:
448  {
451  };
452 
453  template <AllocationMode canAlloc, typename U>
454  bool innerEnqueue(U&& element)
455  {
456 #ifndef NDEBUG
457  ReentrantGuard guard(this->enqueuing_);
458 #endif
459 
460  // High-level pseudocode (assuming we're allowed to alloc a new block):
461  // If room in tail block, add to tail
462  // Else check next block
463  // If next block is not the head block, enqueue on next block
464  // Else create a new block and enqueue there
465  // Advance tail to the block we just enqueued to
466 
467  Block* tail_block = tail_block_.load();
468  size_t block_front = tail_block->localFront;
469  size_t block_tail = tail_block->tail.load();
470 
471  size_t next_block_tail = (block_tail + 1) & tail_block->sizeMask;
472  if (next_block_tail != block_front || next_block_tail != (tail_block->localFront = tail_block->front.load()))
473  {
475  // This block has room for at least one more element
476  char* location = tail_block->data + block_tail * sizeof(T);
477  new (location) T(std::forward<U>(element));
478 
480  tail_block->tail = next_block_tail;
481  }
482  else
483  {
485  if (tail_block->next.load() != front_block_)
486  {
487  // Note that the reason we can't advance to the front_block and start adding new entries there
488  // is because if we did, then dequeue would stay in that block, eventually reading the new values,
489  // instead of advancing to the next full block (whose values were enqueued first and so should be
490  // consumed first).
491 
492  fence(memory_order_acquire); // Ensure we get latest writes if we got the latest front_block
493 
494  // tail_block is full, but there's a free block ahead, use it
495  Block* tail_block_next = tail_block->next.load();
496  size_t next_block_front = tail_block_next->localFront = tail_block_next->front.load();
497  next_block_tail = tail_block_next->tail.load();
499 
500  // This block must be empty since it's not the head block and we
501  // go through the blocks in a circle
502  assert(next_block_front == next_block_tail);
503  tail_block_next->localFront = next_block_front;
504 
505  char* location = tail_block_next->data + next_block_tail * sizeof(T);
506  new (location) T(std::forward<U>(element));
507 
508  tail_block_next->tail = (next_block_tail + 1) & tail_block_next->sizeMask;
509 
511  tail_block_ = tail_block_next;
512  }
513  else if (canAlloc == CanAlloc)
514  {
515  // tail_block is full and there's no free block ahead; create a new block
516  auto new_block_size = largest_block_size_ >= MAX_BLOCK_SIZE ? largest_block_size_ : largest_block_size_ * 2;
517  auto new_block = makeBlock(new_block_size);
518  if (new_block == nullptr)
519  {
520  // Could not allocate a block!
521  return false;
522  }
523  largest_block_size_ = new_block_size;
524 
525  new (new_block->data) T(std::forward<U>(element));
526 
527  assert(new_block->front == 0);
528  new_block->tail = new_block->localTail = 1;
529 
530  new_block->next = tail_block->next.load();
531  tail_block->next = new_block;
532 
533  // Might be possible for the dequeue thread to see the new tail_block->next
534  // *without* seeing the new tail_block value, but this is OK since it can't
535  // advance to the next block until tail_block is set anyway (because the only
536  // case where it could try to read the next is if it's already at the tail_block,
537  // and it won't advance past tail_block in any circumstance).
538 
540  tail_block_ = new_block;
541  }
542  else if (canAlloc == CannotAlloc)
543  {
544  // Would have had to allocate a new block to enqueue, but not allowed
545  return false;
546  }
547  else
548  {
549  assert(false && "Should be unreachable code");
550  return false;
551  }
552  }
553 
554  return true;
555  }
556 
557  // Disable copying
559  {
560  }
561 
562  // Disable assignment
564  {
565  }
566 
567  AE_FORCEINLINE static size_t ceilToPow2(size_t x)
568  {
569  // From http://graphics.stanford.edu/~seander/bithacks.html#RoundUpPowerOf2
570  --x;
571  x |= x >> 1;
572  x |= x >> 2;
573  x |= x >> 4;
574  for (size_t i = 1; i < sizeof(size_t); i <<= 1)
575  {
576  x |= x >> (i << 3);
577  }
578  ++x;
579  return x;
580  }
581 
582  template <typename U>
583  static AE_FORCEINLINE char* alignFor(char* ptr)
584  {
585  const std::size_t alignment = std::alignment_of<U>::value;
586  return ptr + (alignment - (reinterpret_cast<std::uintptr_t>(ptr) % alignment)) % alignment;
587  }
588 
589 private:
590 #ifndef NDEBUG
592  {
593  ReentrantGuard(bool& in_section) : in_section_(in_section)
594  {
595  assert(!in_section_ && "ReaderWriterQueue does not support enqueuing_ or dequeuing_ elements from other "
596  "elements' "
597  "ctors and dtors");
598  in_section_ = true;
599  }
600 
602  {
603  in_section_ = false;
604  }
605 
606  private:
608 
609  private:
610  bool& in_section_;
611  };
612 #endif
613 
614  struct Block
615  {
616  // Avoid false-sharing by putting highly contended variables on their own cache lines
617  WeakAtomic<size_t> front; // (Atomic) Elements are read from here
618  size_t localTail; // An uncontended shadow copy of tail, owned by the consumer
619 
620  char cachelineFiller0_[MOODYCAMEL_CACHE_LINE_SIZE - sizeof(WeakAtomic<size_t>) - sizeof(size_t)];
621  WeakAtomic<size_t> tail; // (Atomic) Elements are enqueued here
622  size_t localFront;
623 
624  char cachelineFiller1_[MOODYCAMEL_CACHE_LINE_SIZE - sizeof(WeakAtomic<size_t>) - sizeof(size_t)]; // next isn't
625  // very
626  // contended, but
627  // we don't want
628  // it on the same
629  // cache line as
630  // tail (which
631  // is)
633 
634  char* data; // Contents (on heap) are aligned to T's alignment
635 
636  const size_t sizeMask;
637 
638  // size must be a power of two (and greater than 0)
639  Block(size_t const& _size, char* _rawThis, char* _data)
640  : front(0)
641  , localTail(0)
642  , tail(0)
643  , localFront(0)
644  , next(nullptr)
645  , data(_data)
646  , sizeMask(_size - 1)
647  , rawThis(_rawThis)
648  {
649  }
650 
651  private:
652  // C4512 - Assignment operator could not be generated
653  Block& operator=(Block const&);
654 
655  public:
656  char* rawThis;
657  };
658 
659  static Block* makeBlock(size_t capacity)
660  {
661  // Allocate enough memory for the block itself, as well as all the elements it will contain
662  auto size = sizeof(Block) + std::alignment_of<Block>::value - 1;
663  size += sizeof(T) * capacity + std::alignment_of<T>::value - 1;
664  auto new_block_raw = static_cast<char*>(std::malloc(size));
665  if (new_block_raw == nullptr)
666  {
667  return nullptr;
668  }
669 
670  auto new_block_aligned = alignFor<Block>(new_block_raw);
671  auto new_block_data = alignFor<T>(new_block_aligned + sizeof(Block));
672  return new (new_block_aligned) Block(capacity, new_block_raw, new_block_data);
673  }
674 
675 private:
676  WeakAtomic<Block*> front_block_; // (Atomic) Elements are enqueued to this block
677 
679  WeakAtomic<Block*> tail_block_; // (Atomic) Elements are dequeued from this block
680 
682 
683 #ifndef NDEBUG
686 #endif
687 };
688 
689 // Like ReaderWriterQueue, but also providees blocking operations
690 template <typename T, size_t MAX_BLOCK_SIZE = 512>
692 {
693 private:
694  typedef ::moodycamel::ReaderWriterQueue<T, MAX_BLOCK_SIZE> ReaderWriterQueue;
695 
696 public:
697  explicit BlockingReaderWriterQueue(size_t maxSize = 15) : inner_(maxSize)
698  {
699  }
700 
701  // Enqueues a copy of element if there is room in the queue.
702  // Returns true if the element was enqueued, false otherwise.
703  // Does not allocate memory.
704  AE_FORCEINLINE bool tryEnqueue(T const& element)
705  {
706  if (inner_.tryEnqueue(element))
707  {
708  sema_.signal();
709  return true;
710  }
711  return false;
712  }
713 
714  // Enqueues a moved copy of element if there is room in the queue.
715  // Returns true if the element was enqueued, false otherwise.
716  // Does not allocate memory.
717  AE_FORCEINLINE bool tryEnqueue(T&& element)
718  {
719  if (inner_.tryEnqueue(std::forward<T>(element)))
720  {
721  sema_.signal();
722  return true;
723  }
724  return false;
725  }
726 
727  // Enqueues a copy of element on the queue.
728  // Allocates an additional block of memory if needed.
729  // Only fails (returns false) if memory allocation fails.
730  AE_FORCEINLINE bool enqueue(T const& element)
731  {
732  if (inner_.enqueue(element))
733  {
734  sema_.signal();
735  return true;
736  }
737  return false;
738  }
739 
740  // Enqueues a moved copy of element on the queue.
741  // Allocates an additional block of memory if needed.
742  // Only fails (returns false) if memory allocation fails.
743  AE_FORCEINLINE bool enqueue(T&& element)
744  {
745  if (inner_.enqueue(std::forward<T>(element)))
746  {
747  sema_.signal();
748  return true;
749  }
750  return false;
751  }
752 
753  // Attempts to dequeue an element; if the queue is empty,
754  // returns false instead. If the queue has at least one element,
755  // moves front to result using operator=, then returns true.
756  template <typename U>
757  bool tryDequeue(U& result)
758  {
759  if (sema_.tryWait())
760  {
761  bool success = inner_.tryDequeue(result);
762  assert(success);
763  AE_UNUSED(success);
764  return true;
765  }
766  return false;
767  }
768 
769  // Attempts to dequeue an element; if the queue is empty,
770  // waits until an element is available, then dequeues it.
771  template <typename U>
772  void waitDequeue(U& result)
773  {
774  sema_.wait();
775  bool success = inner_.tryDequeue(result);
776  AE_UNUSED(result);
777  assert(success);
778  AE_UNUSED(success);
779  }
780 
781  // Attempts to dequeue an element; if the queue is empty,
782  // waits until an element is available up to the specified timeout,
783  // then dequeues it and returns true, or returns false if the timeout
784  // expires before an element can be dequeued.
785  // Using a negative timeout indicates an indefinite timeout,
786  // and is thus functionally equivalent to calling waitDequeue.
787  template <typename U>
788  bool waitDequeTimed(U& result, std::int64_t timeout_usecs)
789  {
790  if (!sema_.wait(timeout_usecs))
791  {
792  return false;
793  }
794  bool success = inner_.tryDequeue(result);
795  AE_UNUSED(result);
796  assert(success);
797  AE_UNUSED(success);
798  return true;
799  }
800 
801 #if __cplusplus > 199711L || _MSC_VER >= 1700
802  // Attempts to dequeue an element; if the queue is empty,
803  // waits until an element is available up to the specified timeout,
804  // then dequeues it and returns true, or returns false if the timeout
805  // expires before an element can be dequeued.
806  // Using a negative timeout indicates an indefinite timeout,
807  // and is thus functionally equivalent to calling waitDequeue.
808  template <typename U, typename Rep, typename Period>
809  inline bool waitDequeTimed(U& result, std::chrono::duration<Rep, Period> const& timeout)
810  {
811  return waitDequeTimed(result, std::chrono::duration_cast<std::chrono::microseconds>(timeout).count());
812  }
813 #endif
814 
815  // Returns a pointer to the front element in the queue (the one that
816  // would be removed next by a call to `tryDequeue` or `pop`). If the
817  // queue appears empty at the time the method is called, nullptr is
818  // returned instead.
819  // Must be called only from the consumer thread.
821  {
822  return inner_.peek();
823  }
824 
825  // Removes the front element from the queue, if any, without returning it.
826  // Returns true on success, or false if the queue appeared empty at the time
827  // `pop` was called.
829  {
830  if (sema_.tryWait())
831  {
832  bool result = inner_.pop();
833  assert(result);
834  AE_UNUSED(result);
835  return true;
836  }
837  return false;
838  }
839 
840  // Returns the approximate number of items currently in the queue.
841  // Safe to call from both the producer and consumer threads.
842  AE_FORCEINLINE size_t sizeApprox() const
843  {
844  return sema_.availableApprox();
845  }
846 
847 private:
848  // Disable copying & assignment
849  BlockingReaderWriterQueue(ReaderWriterQueue const&)
850  {
851  }
852  BlockingReaderWriterQueue& operator=(ReaderWriterQueue const&)
853  {
854  }
855 
856 private:
857  ReaderWriterQueue inner_;
859 };
860 
861 } // end namespace moodycamel
862 
863 #ifdef AE_VCPP
864 #pragma warning(pop)
865 #endif
AE_FORCEINLINE bool tryEnqueue(T &&element)
AE_FORCEINLINE size_t sizeApprox() const
::moodycamel::ReaderWriterQueue< T, MAX_BLOCK_SIZE > ReaderWriterQueue
ReaderWriterQueue(size_t max_size=15)
AE_FORCEINLINE bool enqueue(T const &element)
Block(size_t const &_size, char *_rawThis, char *_data)
static Block * makeBlock(size_t capacity)
#define AE_UNUSED(x)
Definition: atomicops.h:42
#define MOODYCAMEL_CACHE_LINE_SIZE
BlockingReaderWriterQueue & operator=(ReaderWriterQueue const &)
static AE_FORCEINLINE size_t ceilToPow2(size_t x)
AE_FORCEINLINE bool tryEnqueue(T &&element)
ReaderWriterQueue(ReaderWriterQueue const &)
spsc_sema::LightweightSemaphore sema_
AE_FORCEINLINE bool tryEnqueue(T const &element)
AE_FORCEINLINE bool tryEnqueue(T const &element)
AE_FORCEINLINE void compilerFence(memory_order order)
Definition: atomicops.h:202
ReentrantGuard & operator=(ReentrantGuard const &)
WeakAtomic< Block * > tail_block_
static AE_FORCEINLINE char * alignFor(char *ptr)
BlockingReaderWriterQueue(ReaderWriterQueue const &)
WeakAtomic< Block * > front_block_
char cachelineFiller_[MOODYCAMEL_CACHE_LINE_SIZE-sizeof(WeakAtomic< Block * >)]
AE_FORCEINLINE bool enqueue(T &&element)
AE_FORCEINLINE void fence(memory_order order)
Definition: atomicops.h:225
ReaderWriterQueue & operator=(ReaderWriterQueue const &)
bool waitDequeTimed(U &result, std::int64_t timeout_usecs)
AE_FORCEINLINE bool enqueue(T const &element)
AE_FORCEINLINE bool enqueue(T &&element)
#define AE_FORCEINLINE
Definition: atomicops.h:51


ur_client_library
Author(s): Thomas Timm Andersen, Simon Rasmussen, Felix Exner, Lea Steffen, Tristan Schnell
autogenerated on Sun May 9 2021 02:16:26