|  | 
|  | 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 | + | 
|  | 15 | +/// \author Sai Kishor Kothakota | 
|  | 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 | + | 
|  | 29 | +namespace | 
|  | 30 | +{ | 
|  | 31 | +// Trait to check if the capacity is set | 
|  | 32 | +template <typename T> | 
|  | 33 | +struct has_capacity : std::false_type | 
|  | 34 | +{ | 
|  | 35 | +}; | 
|  | 36 | + | 
|  | 37 | +template <typename T, std::size_t Capacity> | 
|  | 38 | +struct has_capacity<boost::lockfree::spsc_queue<T, boost::lockfree::capacity<Capacity>>> | 
|  | 39 | +: std::true_type | 
|  | 40 | +{ | 
|  | 41 | +}; | 
|  | 42 | + | 
|  | 43 | +template <typename T, std::size_t Capacity> | 
|  | 44 | +struct has_capacity<boost::lockfree::queue<T, boost::lockfree::capacity<Capacity>>> : std::true_type | 
|  | 45 | +{ | 
|  | 46 | +}; | 
|  | 47 | + | 
|  | 48 | +template <typename T, std::size_t Capacity, bool FixedSize> | 
|  | 49 | +struct 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 | 
|  | 55 | +template <typename T> | 
|  | 56 | +struct is_spsc_queue : std::false_type | 
|  | 57 | +{ | 
|  | 58 | +}; | 
|  | 59 | + | 
|  | 60 | +template <typename T> | 
|  | 61 | +struct is_spsc_queue<boost::lockfree::spsc_queue<T>> : std::true_type | 
|  | 62 | +{ | 
|  | 63 | +}; | 
|  | 64 | + | 
|  | 65 | +template <typename T, std::size_t Capacity> | 
|  | 66 | +struct 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 | 
|  | 73 | +template <typename T> | 
|  | 74 | +struct 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 | 
|  | 80 | +template <typename T, std::size_t Capacity> | 
|  | 81 | +struct 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 | 
|  | 88 | +template <typename T, std::size_t Capacity> | 
|  | 89 | +struct 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 | 
|  | 96 | +template <typename T, std::size_t Capacity, bool FixedSize> | 
|  | 97 | +struct 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 | + | 
|  | 105 | +namespace realtime_tools | 
|  | 106 | +{ | 
|  | 107 | +template <typename DataType, typename LockFreeContainer> | 
|  | 108 | +class LockFreeQueueBase | 
|  | 109 | +/** | 
|  | 110 | + * @brief A base class for lock-free queues. | 
|  | 111 | + * | 
|  | 112 | + * This class provides a base implementation for lock-free queues with various functionalities | 
|  | 113 | + * such as pushing, popping, and checking the state of the queue. It supports both single-producer | 
|  | 114 | + * single-consumer (SPSC) and multiple-producer multiple-consumer (MPMC) queues. | 
|  | 115 | + * | 
|  | 116 | + * @tparam DataType The type of data to be stored in the queue. | 
|  | 117 | + * @tparam LockFreeContainer The underlying lock-free container type - Typically boost::lockfree::spsc_queue or boost::lockfree::queue with their own template parameters | 
|  | 118 | + */ | 
|  | 119 | +{ | 
|  | 120 | +public: | 
|  | 121 | +  using T = DataType; | 
|  | 122 | + | 
|  | 123 | +  /** | 
|  | 124 | +   * @brief Construct a new LockFreeQueueBase object | 
|  | 125 | +   * @note This constructor is enabled only if the LockFreeContainer has a capacity set | 
|  | 126 | +   */ | 
|  | 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 | + | 
|  | 134 | +  /** | 
|  | 135 | +   * @brief Construct a new LockFreeQueueBase object | 
|  | 136 | +   * @param capacity Capacity of the queue | 
|  | 137 | +   * @note This constructor is enabled only if the LockFreeContainer has no capacity set | 
|  | 138 | +   */ | 
|  | 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 | + | 
|  | 148 | +  /** | 
|  | 149 | +   * @brief Pop the data from the queue | 
|  | 150 | +   * @param data Data to be popped | 
|  | 151 | +   * @return true If the data is popped successfully | 
|  | 152 | +   * @return false If the queue is empty or the data could not be popped | 
|  | 153 | +   */ | 
|  | 154 | +  [[nodiscard]] bool pop(T & data) { return data_queue_.pop(data); } | 
|  | 155 | + | 
|  | 156 | +  /** | 
|  | 157 | +   * @brief Pop the data from the queue | 
|  | 158 | +   * @param data Data to be popped | 
|  | 159 | +   * @return true If the data is popped successfully | 
|  | 160 | +   * @return false If the queue is empty or the data could not be popped | 
|  | 161 | +   * @note This function is enabled only if the data type is convertible to the template type of the queue | 
|  | 162 | +   */ | 
|  | 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 | + | 
|  | 169 | +  /** | 
|  | 170 | +   * @brief Push the data into the queue | 
|  | 171 | +   * @param data Data to be pushed | 
|  | 172 | +   * @return true If the data is pushed successfully | 
|  | 173 | +   * @return false If the queue is full or the data could not be pushed | 
|  | 174 | +   */ | 
|  | 175 | + | 
|  | 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 | + | 
|  | 185 | +  /** | 
|  | 186 | +   * @brief Push the data into the queue | 
|  | 187 | +   * @param data Data to be pushed | 
|  | 188 | +   * @return true If the data is pushed successfully | 
|  | 189 | +   * @return false If the queue is full or the data could not be pushed | 
|  | 190 | +   * @note This function is enabled only if the data type is convertible to the template type of the queue | 
|  | 191 | +   */ | 
|  | 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 | + | 
|  | 202 | +  /** | 
|  | 203 | +   * @brief The bounded_push function pushes the data into the queue and pops the oldest data if the queue is full | 
|  | 204 | +   * @param data Data to be pushed | 
|  | 205 | +   * @return true If the data is pushed successfully | 
|  | 206 | +   * @return false If the data could not be pushed | 
|  | 207 | +   * @note This function is enabled only if the queue is a spsc_queue and only if the data type | 
|  | 208 | +   * is convertible to the template type of the queue | 
|  | 209 | +   * @note For a SPSC Queue, to be used in single-threaded applications | 
|  | 210 | +   * @warning For a SPSC Queue, this method might not work as expected when used in multi-threaded applications | 
|  | 211 | +   * if it is used with two different threads, one doing bounded_push and the other doing pop. In this case, the | 
|  | 212 | +   * queue is no longer a single producer single consumer queue. So, the behavior might not be as expected. | 
|  | 213 | +   */ | 
|  | 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 | + | 
|  | 225 | +  /** | 
|  | 226 | +   * @brief Get the latest data from the queue | 
|  | 227 | +   * @param data Data to be filled with the latest data | 
|  | 228 | +   * @return true If the data is filled with the latest data, false otherwise | 
|  | 229 | +   * @return false If the queue is empty | 
|  | 230 | +   * @note This function consumes all the data in the queue until the last data and returns the last element of the queue | 
|  | 231 | +   */ | 
|  | 232 | +  [[nodiscard]] bool get_latest(T & data) | 
|  | 233 | +  { | 
|  | 234 | +    return data_queue_.consume_all([&data](const T & d) { data = d; }) > 0; | 
|  | 235 | +  } | 
|  | 236 | + | 
|  | 237 | +  /** | 
|  | 238 | +   * @brief Check if the queue is empty | 
|  | 239 | +   * @return true If the queue is empty | 
|  | 240 | +   * @return false If the queue is not empty | 
|  | 241 | +   * @note The result is only accurate, if no other thread modifies the queue. Therefore, it is rarely practical to use this value in program logic. | 
|  | 242 | +   * @note For a SPSC Queue, it should only be called from the consumer thread where pop is called. If need to be called from producer thread, use write_available() instead. | 
|  | 243 | +   */ | 
|  | 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 | + | 
|  | 253 | +  /** | 
|  | 254 | +   * @brief Get the capacity of the queue | 
|  | 255 | +   * @return std::size_t Capacity of the queue | 
|  | 256 | +   */ | 
|  | 257 | +  size_t capacity() const { return capacity_; } | 
|  | 258 | + | 
|  | 259 | +  /** | 
|  | 260 | +   * @brief Get the size of the queue | 
|  | 261 | +   * @return std::size_t Size of the queue | 
|  | 262 | +   * @note This function is enabled only if the queue is a spsc_queue | 
|  | 263 | +   */ | 
|  | 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 | + | 
|  | 272 | +  /** | 
|  | 273 | +   * @brief The method to check if the queue is lock free | 
|  | 274 | +   * @return true If the queue is lock free, false otherwise | 
|  | 275 | +   * @warning It only checks, if the queue head and tail nodes and the freelist can | 
|  | 276 | +   * be modified in a lock-free manner. On most platforms, the whole implementation | 
|  | 277 | +   * is lock-free, if this is true. Using c++0x-style atomics, there is no possibility | 
|  | 278 | +   * to provide a completely accurate implementation, because one would need to test | 
|  | 279 | +   * every internal node, which is impossible if further nodes will be allocated from | 
|  | 280 | +   * the operating system. | 
|  | 281 | +   * @link https://www.boost.org/doc/libs/1_74_0/doc/html/boost/lockfree/queue.html | 
|  | 282 | +   */ | 
|  | 283 | +  bool is_lock_free() const | 
|  | 284 | +  { | 
|  | 285 | +    return (is_spsc_queue<LockFreeContainer>::value) || data_queue_.is_lock_free(); | 
|  | 286 | +  } | 
|  | 287 | + | 
|  | 288 | +  /** | 
|  | 289 | +   * @brief Get the lockfree container | 
|  | 290 | +   * @return const LockFreeContainer& Reference to the lockfree container | 
|  | 291 | +   */ | 
|  | 292 | +  const LockFreeContainer & get_lockfree_container() const { return data_queue_; } | 
|  | 293 | + | 
|  | 294 | +  /** | 
|  | 295 | +   * @brief Get the lockfree container | 
|  | 296 | +   * @return LockFreeContainer& Reference to the lockfree container | 
|  | 297 | +   */ | 
|  | 298 | +  LockFreeContainer & get_lockfree_container() { return data_queue_; } | 
|  | 299 | + | 
|  | 300 | +private: | 
|  | 301 | +  LockFreeContainer data_queue_; | 
|  | 302 | +  std::size_t capacity_; | 
|  | 303 | +};  // class | 
|  | 304 | + | 
|  | 305 | +/** | 
|  | 306 | + * @brief Lock-free Single Producer Single Consumer Queue | 
|  | 307 | + * @tparam DataType Type of the data to be stored in the queue | 
|  | 308 | + * @tparam Capacity Capacity of the queue | 
|  | 309 | + */ | 
|  | 310 | +template <class DataType, std::size_t Capacity = 0> | 
|  | 311 | +using LockFreeSPSCQueue = std::conditional_t< | 
|  | 312 | +  Capacity == 0, LockFreeQueueBase<DataType, boost::lockfree::spsc_queue<DataType>>, | 
|  | 313 | +  LockFreeQueueBase< | 
|  | 314 | +    DataType, boost::lockfree::spsc_queue<DataType, boost::lockfree::capacity<Capacity>>>>; | 
|  | 315 | + | 
|  | 316 | +/** | 
|  | 317 | + * @brief Lock-free Multiple Producer Multiple Consumer Queue | 
|  | 318 | + * @tparam DataType Type of the data to be stored in the queue | 
|  | 319 | + * @tparam Capacity Capacity of the queue | 
|  | 320 | + * @tparam FixedSize Fixed size of the queue | 
|  | 321 | + */ | 
|  | 322 | +template <class DataType, std::size_t Capacity = 0, bool FixedSize = true> | 
|  | 323 | +using LockFreeMPMCQueue = std::conditional_t< | 
|  | 324 | +  Capacity == 0, | 
|  | 325 | +  LockFreeQueueBase< | 
|  | 326 | +    DataType, boost::lockfree::queue<DataType, boost::lockfree::fixed_sized<FixedSize>>>, | 
|  | 327 | +  LockFreeQueueBase< | 
|  | 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_ | 
0 commit comments