12 #include <type_traits> 15 #if __cplusplus > 199711L || _MSC_VER >= 1700 // C++11 or VS2012 32 #ifndef MOODYCAMEL_CACHE_LINE_SIZE 33 #define MOODYCAMEL_CACHE_LINE_SIZE 64 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 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 52 template <
typename T,
size_t MAX_BLOCK_SIZE = 512>
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");
89 Block* firstBlock =
nullptr;
100 size_t initialBlockCount = (maxSize + MAX_BLOCK_SIZE * 2 - 3) / (MAX_BLOCK_SIZE - 1);
102 Block* lastBlock =
nullptr;
103 for (
size_t i = 0; i != initialBlockCount; ++i)
106 if (block ==
nullptr)
108 #ifdef MOODYCAMEL_EXCEPTIONS_ENABLED 109 throw std::bad_alloc();
114 if (firstBlock ==
nullptr)
120 lastBlock->next = block;
123 block->next = firstBlock;
129 if (firstBlock ==
nullptr)
131 #ifdef MOODYCAMEL_EXCEPTIONS_ENABLED 132 throw std::bad_alloc();
137 firstBlock->next = firstBlock;
155 Block* block = frontBlock_;
158 Block* nextBlock = block->next;
159 size_t blockFront = block->front;
160 size_t blockTail = block->tail;
162 for (
size_t i = blockFront; i != blockTail; i = (i + 1) & block->sizeMask)
164 auto element =
reinterpret_cast<T*
>(block->data + i *
sizeof(T));
169 auto rawBlock = block->rawThis;
173 }
while (block != frontBlock_);
181 return inner_enqueue<CannotAlloc>(element);
189 return inner_enqueue<CannotAlloc>(std::forward<T>(element));
197 return inner_enqueue<CanAlloc>(element);
205 return inner_enqueue<CanAlloc>(std::forward<T>(element));
211 template <
typename U>
236 size_t blockTail = frontBlock_->localTail;
237 size_t blockFront = frontBlock_->front.load();
239 if (blockFront != blockTail || blockFront != (frontBlock_->localTail = frontBlock_->tail.load()))
243 non_empty_front_block:
245 auto element =
reinterpret_cast<T*
>(frontBlock_->data + blockFront *
sizeof(T));
246 result = std::move(*element);
249 blockFront = (blockFront + 1) & frontBlock_->sizeMask;
252 frontBlock_->front = blockFront;
254 else if (frontBlock_ !=
tailBlock.load())
259 blockTail = frontBlock_->localTail = frontBlock_->tail.load();
260 blockFront = frontBlock_->front.load();
263 if (blockFront != blockTail)
266 goto non_empty_front_block;
270 Block* nextBlock = frontBlock_->next;
275 size_t nextBlockFront = nextBlock->front.load();
276 size_t nextBlockTail = nextBlock->localTail = nextBlock->tail.load();
281 assert(nextBlockFront != nextBlockTail);
290 auto element =
reinterpret_cast<T*
>(frontBlock_->data + nextBlockFront *
sizeof(T));
292 result = std::move(*element);
295 nextBlockFront = (nextBlockFront + 1) & frontBlock_->sizeMask;
298 frontBlock_->front = nextBlockFront;
322 size_t blockTail = frontBlock_->localTail;
323 size_t blockFront = frontBlock_->front.load();
325 if (blockFront != blockTail || blockFront != (frontBlock_->localTail = frontBlock_->tail.load()))
328 non_empty_front_block:
329 return reinterpret_cast<T*
>(frontBlock_->data + blockFront *
sizeof(T));
331 else if (frontBlock_ !=
tailBlock.load())
335 blockTail = frontBlock_->localTail = frontBlock_->tail.load();
336 blockFront = frontBlock_->front.load();
339 if (blockFront != blockTail)
341 goto non_empty_front_block;
344 Block* nextBlock = frontBlock_->next;
346 size_t nextBlockFront = nextBlock->front.load();
349 assert(nextBlockFront != nextBlock->tail.load());
350 return reinterpret_cast<T*
>(nextBlock->data + nextBlockFront *
sizeof(T));
367 size_t blockTail = frontBlock_->localTail;
368 size_t blockFront = frontBlock_->front.load();
370 if (blockFront != blockTail || blockFront != (frontBlock_->localTail = frontBlock_->tail.load()))
374 non_empty_front_block:
375 auto element =
reinterpret_cast<T*
>(frontBlock_->data + blockFront *
sizeof(T));
378 blockFront = (blockFront + 1) & frontBlock_->sizeMask;
381 frontBlock_->front = blockFront;
383 else if (frontBlock_ !=
tailBlock.load())
387 blockTail = frontBlock_->localTail = frontBlock_->tail.load();
388 blockFront = frontBlock_->front.load();
391 if (blockFront != blockTail)
393 goto non_empty_front_block;
397 Block* nextBlock = frontBlock_->next;
399 size_t nextBlockFront = nextBlock->front.load();
400 size_t nextBlockTail = nextBlock->localTail = nextBlock->tail.load();
403 assert(nextBlockFront != nextBlockTail);
411 auto element =
reinterpret_cast<T*
>(frontBlock_->data + nextBlockFront *
sizeof(T));
414 nextBlockFront = (nextBlockFront + 1) & frontBlock_->sizeMask;
417 frontBlock_->front = nextBlockFront;
434 Block* block = frontBlock_;
438 size_t blockFront = block->front.load();
439 size_t blockTail = block->tail.load();
440 result += (blockTail - blockFront) & block->sizeMask;
441 block = block->next.load();
442 }
while (block != frontBlock_);
453 template <AllocationMode canAlloc,
typename U>
468 size_t blockFront = tailBlock_->localFront;
469 size_t blockTail = tailBlock_->tail.load();
471 size_t nextBlockTail = (blockTail + 1) & tailBlock_->sizeMask;
472 if (nextBlockTail != blockFront || nextBlockTail != (tailBlock_->localFront = tailBlock_->front.load()))
476 char* location = tailBlock_->data + blockTail *
sizeof(T);
477 new (location) T(std::forward<U>(element));
480 tailBlock_->tail = nextBlockTail;
495 Block* tailBlockNext = tailBlock_->next.load();
496 size_t nextBlockFront = tailBlockNext->localFront = tailBlockNext->front.load();
497 nextBlockTail = tailBlockNext->tail.load();
502 assert(nextBlockFront == nextBlockTail);
503 tailBlockNext->localFront = nextBlockFront;
505 char* location = tailBlockNext->data + nextBlockTail *
sizeof(T);
506 new (location) T(std::forward<U>(element));
508 tailBlockNext->tail = (nextBlockTail + 1) & tailBlockNext->sizeMask;
518 if (newBlock ==
nullptr)
525 new (newBlock->data) T(std::forward<U>(element));
527 assert(newBlock->front == 0);
528 newBlock->tail = newBlock->localTail = 1;
530 newBlock->next = tailBlock_->next.load();
531 tailBlock_->next = newBlock;
549 assert(
false &&
"Should be unreachable code");
574 for (
size_t i = 1; i <
sizeof(size_t); i <<= 1)
582 template <
typename U>
585 const std::size_t alignment = std::alignment_of<U>::value;
586 return ptr + (alignment - (
reinterpret_cast<std::uintptr_t
>(ptr) % alignment)) % alignment;
595 assert(!
inSection &&
"ReaderWriterQueue does not support enqueuing or dequeuing elements from other elements' " 638 Block(
size_t const& _size,
char* _rawThis,
char* _data)
645 , sizeMask(_size - 1)
661 auto size =
sizeof(Block) + std::alignment_of<Block>::value - 1;
662 size +=
sizeof(T) * capacity + std::alignment_of<T>::value - 1;
663 auto newBlockRaw =
static_cast<char*
>(std::malloc(size));
664 if (newBlockRaw ==
nullptr)
669 auto newBlockAligned = align_for<Block>(newBlockRaw);
670 auto newBlockData = align_for<T>(newBlockAligned +
sizeof(Block));
671 return new (newBlockAligned) Block(capacity, newBlockRaw, newBlockData);
689 template <
typename T,
size_t MAX_BLOCK_SIZE = 512>
705 if (inner.try_enqueue(element))
718 if (inner.try_enqueue(std::forward<T>(element)))
731 if (inner.enqueue(element))
744 if (inner.enqueue(std::forward<T>(element)))
755 template <
typename U>
760 bool success = inner.try_dequeue(result);
770 template <
typename U>
774 bool success = inner.try_dequeue(result);
786 template <
typename U>
789 if (!sema.wait(timeout_usecs))
793 bool success = inner.try_dequeue(result);
800 #if __cplusplus > 199711L || _MSC_VER >= 1700 807 template <
typename U,
typename Rep,
typename Period>
808 inline bool wait_dequeue_timed(U& result, std::chrono::duration<Rep, Period>
const& timeout)
810 return wait_dequeue_timed(result, std::chrono::duration_cast<std::chrono::microseconds>(timeout).count());
831 bool result = inner.pop();
843 return sema.availableApprox();
weak_atomic< Block * > next
char cachelineFiller[MOODYCAMEL_CACHE_LINE_SIZE-sizeof(weak_atomic< Block * >)]
AE_FORCEINLINE T * peek()
::moodycamel::ReaderWriterQueue< T, MAX_BLOCK_SIZE > ReaderWriterQueue
weak_atomic< size_t > tail
weak_atomic< Block * > tailBlock
bool try_dequeue(U &result)
AE_FORCEINLINE bool pop()
AE_FORCEINLINE bool enqueue(T const &element)
Block(size_t const &_size, char *_rawThis, char *_data)
AE_FORCEINLINE bool try_enqueue(T &&element)
bool wait_dequeue_timed(U &result, std::int64_t timeout_usecs)
AE_FORCEINLINE bool try_enqueue(T const &element)
size_t size_approx() const
#define MOODYCAMEL_CACHE_LINE_SIZE
BlockingReaderWriterQueue & operator=(ReaderWriterQueue const &)
static AE_FORCEINLINE size_t ceilToPow2(size_t x)
weak_atomic< size_t > front
ReaderWriterQueue(ReaderWriterQueue const &)
BlockingReaderWriterQueue(size_t maxSize=15)
AE_FORCEINLINE bool try_enqueue(T const &element)
ReaderWriterQueue(size_t maxSize=15)
ReentrantGuard(bool &_inSection)
ReentrantGuard & operator=(ReentrantGuard const &)
BlockingReaderWriterQueue(ReaderWriterQueue const &)
bool inner_enqueue(U &&element)
bool try_dequeue(U &result)
AE_FORCEINLINE void compiler_fence(memory_order order)
AE_FORCEINLINE bool enqueue(T &&element)
static AE_FORCEINLINE char * align_for(char *ptr)
static Block * make_block(size_t capacity)
AE_FORCEINLINE bool try_enqueue(T &&element)
AE_FORCEINLINE void fence(memory_order order)
ReaderWriterQueue & operator=(ReaderWriterQueue const &)
AE_FORCEINLINE size_t size_approx() const
void wait_dequeue(U &result)
weak_atomic< Block * > frontBlock
spsc_sema::LightweightSemaphore sema
AE_FORCEINLINE bool enqueue(T const &element)
AE_FORCEINLINE bool enqueue(T &&element)