ros2_control - humble
Loading...
Searching...
No Matches
lock_free_queue.hpp
1// Copyright 2025 PAL Robotics S.L.
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
16
17#ifndef REALTIME_TOOLS__LOCK_FREE_QUEUE_HPP_
18#define REALTIME_TOOLS__LOCK_FREE_QUEUE_HPP_
19
20#include <chrono>
21#include <mutex>
22#include <type_traits>
23#include <utility>
24
25#include <boost/lockfree/queue.hpp>
26#include <boost/lockfree/spsc_queue.hpp>
27#include <boost/lockfree/stack.hpp>
28
29namespace
30{
31// Trait to check if the capacity is set
32template <typename T>
33struct has_capacity : std::false_type
34{
35};
36
37template <typename T, std::size_t Capacity>
38struct has_capacity<boost::lockfree::spsc_queue<T, boost::lockfree::capacity<Capacity>>>
39: std::true_type
40{
41};
42
43template <typename T, std::size_t Capacity>
44struct has_capacity<boost::lockfree::queue<T, boost::lockfree::capacity<Capacity>>> : std::true_type
45{
46};
47
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
51{
52};
53
54// Traits to check if the queue is spsc_queue
55template <typename T>
56struct is_spsc_queue : std::false_type
57{
58};
59
60template <typename T>
61struct is_spsc_queue<boost::lockfree::spsc_queue<T>> : std::true_type
62{
63};
64
65template <typename T, std::size_t Capacity>
66struct is_spsc_queue<boost::lockfree::spsc_queue<T, boost::lockfree::capacity<Capacity>>>
67: std::true_type
68{
69};
70
71// Traits to get the capacity of the queue
72// Default case: no capacity
73template <typename T>
74struct get_boost_lockfree_queue_capacity
75{
76 static constexpr std::size_t value = 0; // Default to 0 if capacity is not defined
77};
78
79// Specialization for queues with capacity
80template <typename T, std::size_t Capacity>
81struct get_boost_lockfree_queue_capacity<
82 boost::lockfree::spsc_queue<T, boost::lockfree::capacity<Capacity>>>
83{
84 static constexpr std::size_t value = Capacity;
85};
86
87// Specialization for queues with capacity
88template <typename T, std::size_t Capacity>
89struct get_boost_lockfree_queue_capacity<
90 boost::lockfree::queue<T, boost::lockfree::capacity<Capacity>>>
91{
92 static constexpr std::size_t value = Capacity;
93};
94
95// Specialization for queues with 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>>>
99{
100 static constexpr std::size_t value = Capacity;
101};
102
103} // namespace
104
105namespace realtime_tools
106{
107template <typename DataType, typename LockFreeContainer>
119{
120public:
121 using T = DataType;
122
127 template <
128 bool HasCapacity = has_capacity<LockFreeContainer>::value,
129 typename std::enable_if_t<HasCapacity, int> = 0>
130 LockFreeQueueBase() : capacity_(get_boost_lockfree_queue_capacity<LockFreeContainer>::value)
131 {
132 }
133
139 template <
140 bool HasCapacity = has_capacity<LockFreeContainer>::value,
141 typename std::enable_if_t<!HasCapacity, int> = 1>
142 explicit LockFreeQueueBase(std::size_t capacity) : data_queue_(capacity), capacity_(capacity)
143 {
144 }
145
146 virtual ~LockFreeQueueBase() = default;
147
154 [[nodiscard]] bool pop(T & data) { return data_queue_.pop(data); }
155
163 template <typename U>
164 [[nodiscard]] std::enable_if_t<std::is_convertible_v<T, U>, bool> pop(U & data)
165 {
166 return data_queue_.pop(data);
167 }
168
176 [[nodiscard]] bool push(const T & data)
177 {
178 if constexpr (is_spsc_queue<LockFreeContainer>::value) {
179 return data_queue_.push(data);
180 } else {
181 return data_queue_.bounded_push(data);
182 }
183 }
184
192 template <typename U>
193 [[nodiscard]] std::enable_if_t<std::is_convertible_v<T, U>, bool> push(const U & data)
194 {
195 if constexpr (is_spsc_queue<LockFreeContainer>::value) {
196 return data_queue_.push(data);
197 } else {
198 return data_queue_.bounded_push(data);
199 }
200 }
201
214 template <typename U>
215 [[nodiscard]] std::enable_if_t<std::is_convertible_v<T, U>, bool> bounded_push(const U & data)
216 {
217 if (!push(data)) {
218 T dummy;
219 data_queue_.pop(dummy);
220 return push(data);
221 }
222 return true;
223 }
224
232 [[nodiscard]] bool get_latest(T & data)
233 {
234 return data_queue_.consume_all([&data](const T & d) { data = d; }) > 0;
235 }
236
244 bool empty() const
245 {
246 if constexpr (is_spsc_queue<LockFreeContainer>::value) {
247 return data_queue_.read_available() == 0;
248 } else {
249 return data_queue_.empty();
250 }
251 }
252
257 size_t capacity() const { return capacity_; }
258
264 template <
265 bool IsSPSCQueue = is_spsc_queue<LockFreeContainer>::value,
266 typename std::enable_if_t<IsSPSCQueue, int> = 0>
267 std::size_t size() const
268 {
269 return data_queue_.read_available();
270 }
271
283 bool is_lock_free() const
284 {
285 return (is_spsc_queue<LockFreeContainer>::value) || data_queue_.is_lock_free();
286 }
287
292 const LockFreeContainer & get_lockfree_container() const { return data_queue_; }
293
298 LockFreeContainer & get_lockfree_container() { return data_queue_; }
299
300private:
301 LockFreeContainer data_queue_;
302 std::size_t capacity_;
303}; // class
304
310template <class DataType, std::size_t Capacity = 0>
311using LockFreeSPSCQueue = std::conditional_t<
314 DataType, boost::lockfree::spsc_queue<DataType, boost::lockfree::capacity<Capacity>>>>;
315
322template <class DataType, std::size_t Capacity = 0, bool FixedSize = true>
323using LockFreeMPMCQueue = std::conditional_t<
324 Capacity == 0,
326 DataType, boost::lockfree::queue<DataType, boost::lockfree::fixed_sized<FixedSize>>>,
328 DataType,
329 boost::lockfree::queue<
330 DataType, boost::lockfree::capacity<Capacity>, boost::lockfree::fixed_sized<FixedSize>>>>;
331
332} // namespace realtime_tools
333#endif // REALTIME_TOOLS__LOCK_FREE_QUEUE_HPP_
A base class for lock-free queues.
Definition lock_free_queue.hpp:119
LockFreeContainer & get_lockfree_container()
Get the lockfree container.
Definition lock_free_queue.hpp:298
bool get_latest(T &data)
Get the latest data from the queue.
Definition lock_free_queue.hpp:232
std::enable_if_t< std::is_convertible_v< T, U >, bool > pop(U &data)
Pop the data from the queue.
Definition lock_free_queue.hpp:164
LockFreeQueueBase()
Construct a new LockFreeQueueBase object.
Definition lock_free_queue.hpp:130
bool is_lock_free() const
The method to check if the queue is lock free.
Definition lock_free_queue.hpp:283
std::enable_if_t< std::is_convertible_v< T, U >, bool > bounded_push(const U &data)
The bounded_push function pushes the data into the queue and pops the oldest data if the queue is ful...
Definition lock_free_queue.hpp:215
bool empty() const
Check if the queue is empty.
Definition lock_free_queue.hpp:244
size_t capacity() const
Get the capacity of the queue.
Definition lock_free_queue.hpp:257
bool push(const T &data)
Push the data into the queue.
Definition lock_free_queue.hpp:176
std::size_t size() const
Get the size of the queue.
Definition lock_free_queue.hpp:267
std::enable_if_t< std::is_convertible_v< T, U >, bool > push(const U &data)
Push the data into the queue.
Definition lock_free_queue.hpp:193
bool pop(T &data)
Pop the data from the queue.
Definition lock_free_queue.hpp:154
LockFreeQueueBase(std::size_t capacity)
Construct a new LockFreeQueueBase object.
Definition lock_free_queue.hpp:142
const LockFreeContainer & get_lockfree_container() const
Get the lockfree container.
Definition lock_free_queue.hpp:292
A pthread mutex wrapper that provides a mutex with the priority inheritance protocol and a priority c...
Definition async_function_handler.hpp:38
std::conditional_t< Capacity==0, LockFreeQueueBase< DataType, boost::lockfree::spsc_queue< DataType > >, LockFreeQueueBase< DataType, boost::lockfree::spsc_queue< DataType, boost::lockfree::capacity< Capacity > > > > LockFreeSPSCQueue
Lock-free Single Producer Single Consumer Queue.
Definition lock_free_queue.hpp:314
std::conditional_t< Capacity==0, LockFreeQueueBase< DataType, boost::lockfree::queue< DataType, boost::lockfree::fixed_sized< FixedSize > > >, LockFreeQueueBase< DataType, boost::lockfree::queue< DataType, boost::lockfree::capacity< Capacity >, boost::lockfree::fixed_sized< FixedSize > > > > LockFreeMPMCQueue
Lock-free Multiple Producer Multiple Consumer Queue.
Definition lock_free_queue.hpp:330