17#ifndef REALTIME_TOOLS__LOCK_FREE_QUEUE_HPP_
18#define REALTIME_TOOLS__LOCK_FREE_QUEUE_HPP_
25#include <boost/lockfree/queue.hpp>
26#include <boost/lockfree/spsc_queue.hpp>
27#include <boost/lockfree/stack.hpp>
33struct has_capacity : std::false_type
37template <
typename T, std::
size_t Capacity>
38struct has_capacity<boost::lockfree::spsc_queue<T, boost::lockfree::capacity<Capacity>>>
43template <
typename T, std::
size_t Capacity>
44struct has_capacity<boost::lockfree::queue<T, boost::lockfree::capacity<Capacity>>> : std::true_type
48template <
typename T, std::
size_t Capacity,
bool FixedSize>
49struct has_capacity<boost::lockfree::queue<
50 T, boost::lockfree::capacity<Capacity>, boost::lockfree::fixed_sized<FixedSize>>> : std::true_type
56struct is_spsc_queue : std::false_type
61struct is_spsc_queue<boost::lockfree::spsc_queue<T>> : std::true_type
65template <
typename T, std::
size_t Capacity>
66struct is_spsc_queue<boost::lockfree::spsc_queue<T, boost::lockfree::capacity<Capacity>>>
74struct get_boost_lockfree_queue_capacity
76 static constexpr std::size_t value = 0;
80template <
typename T, std::
size_t Capacity>
81struct get_boost_lockfree_queue_capacity<
82 boost::lockfree::spsc_queue<T, boost::lockfree::capacity<Capacity>>>
84 static constexpr std::size_t value = Capacity;
88template <
typename T, std::
size_t Capacity>
89struct get_boost_lockfree_queue_capacity<
90 boost::lockfree::queue<T, boost::lockfree::capacity<Capacity>>>
92 static constexpr std::size_t value = Capacity;
96template <
typename T, std::
size_t Capacity,
bool FixedSize>
97struct get_boost_lockfree_queue_capacity<boost::lockfree::queue<
98 T, boost::lockfree::capacity<Capacity>, boost::lockfree::fixed_sized<FixedSize>>>
100 static constexpr std::size_t value = Capacity;
107template <
typename DataType,
typename LockFreeContainer>
128 bool HasCapacity = has_capacity<LockFreeContainer>::value,
129 typename std::enable_if_t<HasCapacity, int> = 0>
140 bool HasCapacity = has_capacity<LockFreeContainer>::value,
141 typename std::enable_if_t<!HasCapacity, int> = 1>
154 [[nodiscard]]
bool pop(T & data) {
return data_queue_.pop(data); }
163 template <
typename U>
164 [[nodiscard]] std::enable_if_t<std::is_convertible_v<T, U>,
bool>
pop(U & data)
166 return data_queue_.pop(data);
176 [[nodiscard]]
bool push(
const T & data)
178 if constexpr (is_spsc_queue<LockFreeContainer>::value) {
179 return data_queue_.push(data);
181 return data_queue_.bounded_push(data);
192 template <
typename U>
193 [[nodiscard]] std::enable_if_t<std::is_convertible_v<T, U>,
bool>
push(
const U & data)
195 if constexpr (is_spsc_queue<LockFreeContainer>::value) {
196 return data_queue_.push(data);
198 return data_queue_.bounded_push(data);
214 template <
typename U>
215 [[nodiscard]] std::enable_if_t<std::is_convertible_v<T, U>,
bool>
bounded_push(
const U & data)
219 data_queue_.pop(dummy);
234 return data_queue_.consume_all([&data](
const T & d) { data = d; }) > 0;
246 if constexpr (is_spsc_queue<LockFreeContainer>::value) {
247 return data_queue_.read_available() == 0;
249 return data_queue_.empty();
265 bool IsSPSCQueue = is_spsc_queue<LockFreeContainer>::value,
266 typename std::enable_if_t<IsSPSCQueue, int> = 0>
269 return data_queue_.read_available();
285 return (is_spsc_queue<LockFreeContainer>::value) || data_queue_.is_lock_free();
301 LockFreeContainer data_queue_;
302 std::size_t capacity_;
310template <
class DataType, std::
size_t Capacity = 0>
314 DataType, boost::lockfree::spsc_queue<DataType, boost::lockfree::capacity<Capacity>>>>;
322template <
class DataType, std::
size_t Capacity = 0,
bool FixedSize = true>
326 DataType, boost::lockfree::queue<DataType, boost::lockfree::fixed_sized<FixedSize>>>,
329 boost::lockfree::queue<
330 DataType, boost::lockfree::capacity<Capacity>, boost::lockfree::fixed_sized<FixedSize>>>>;