-
Notifications
You must be signed in to change notification settings - Fork 77
New issue
Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.
By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.
Already on GitHub? Sign in to your account
Add Lock-free Queue #253
Open
saikishor
wants to merge
35
commits into
ros-controls:master
Choose a base branch
from
pal-robotics-forks:boost/lockfree/realtime/buffer
base: master
Could not load branches
Branch not found: {{ refName }}
Loading
Could not load tags
Nothing to show
Loading
Are you sure you want to change the base?
Some commits from the old base branch may be removed from the timeline,
and old review comments may become outdated.
+805
−0
Open
Add Lock-free Queue #253
Changes from all commits
Commits
Show all changes
35 commits
Select commit
Hold shift + click to select a range
561d370
add libboost-dev dependency
saikishor 2455b16
Add LockFreeBuffer class
saikishor 02db30d
Add LockFreeSPSCQueueBase class
saikishor 1468fe8
Add more functionality and tests
saikishor 2ef8020
Add tests to CMakeLists
saikishor 268138b
Draft: functional lockfree queue (not spsc_queue)
saikishor 5e94cc9
Add more template enabled methods
saikishor 34d03b5
update tests
saikishor 6b629b1
Update the LockFreeQueue to completely support SPSC and MPMC queues +…
saikishor 9a9951d
cleanup and change license
saikishor 8c2c974
Update the documentation and add some minor tests
saikishor c991609
Merge branch 'ros-controls:master' into boost/lockfree/realtime/buffer
saikishor 860029e
Add is_lock_free method
saikishor fe75f45
Update documentation
saikishor 52f53b1
Add get_latest method to the LockFreeQueue
saikishor 356d87e
update CMakeLists.txt
saikishor ac7ae53
Apply suggestions from code review
saikishor 66dcdfd
Change template arg LockFreeSPSCContainer to LockFreeContainer
saikishor 5d990c0
Install boost
christophfroehlich 71321b3
cleanup the commented tests
saikishor 4f61624
Update include/realtime_tools/lock_free_queue.hpp
saikishor 9a8acdf
Update tests
saikishor ddb5ca9
Update condition for bounded push and update documentation
saikishor 494b47d
Install boost in Windows CI
christophfroehlich 8d1bae4
Unify empty method with internal conditioning of SPSC queue or MPMC q…
saikishor f90d22b
Try to set CMP0167 for boost on windows
christophfroehlich 081d2f6
Remove quiet and add Boost::boost
christophfroehlich 2f8d285
Remove atomic link libraries
christophfroehlich fff6ee3
Try to fix msvc atomic
christophfroehlich 2bb6519
Try to fix atomic.lib on msvc
christophfroehlich 551a9fb
Don't link atomic on windows
christophfroehlich 689f63c
Use master branch of CI repo
christophfroehlich b8becad
Simplify push method and also add fixed_size arg to the MPMC queue
saikishor bd74a53
reuse tests to test all constructable types of LockFreeQueues
saikishor 0d3fc7e
Merge branch 'master' into boost/lockfree/realtime/buffer
saikishor File filter
Filter by extension
Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
|
@@ -32,3 +32,4 @@ jobs: | |
ros_distro: jazzy | ||
ref_for_scheduled_build: master | ||
os_name: windows-2019 | ||
install_boost: true |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,333 @@ | ||
// Copyright 2025 PAL Robotics S.L. | ||
// | ||
// Licensed under the Apache License, Version 2.0 (the "License"); | ||
// you may not use this file except in compliance with the License. | ||
// You may obtain a copy of the License at | ||
// | ||
// http://www.apache.org/licenses/LICENSE-2.0 | ||
// | ||
// Unless required by applicable law or agreed to in writing, software | ||
// distributed under the License is distributed on an "AS IS" BASIS, | ||
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. | ||
// See the License for the specific language governing permissions and | ||
// limitations under the License. | ||
|
||
/// \author Sai Kishor Kothakota | ||
|
||
#ifndef REALTIME_TOOLS__LOCK_FREE_QUEUE_HPP_ | ||
#define REALTIME_TOOLS__LOCK_FREE_QUEUE_HPP_ | ||
|
||
#include <chrono> | ||
#include <mutex> | ||
#include <type_traits> | ||
#include <utility> | ||
|
||
#include <boost/lockfree/queue.hpp> | ||
#include <boost/lockfree/spsc_queue.hpp> | ||
#include <boost/lockfree/stack.hpp> | ||
|
||
namespace | ||
{ | ||
// Trait to check if the capacity is set | ||
template <typename T> | ||
struct has_capacity : std::false_type | ||
{ | ||
}; | ||
|
||
template <typename T, std::size_t Capacity> | ||
struct has_capacity<boost::lockfree::spsc_queue<T, boost::lockfree::capacity<Capacity>>> | ||
: std::true_type | ||
{ | ||
}; | ||
|
||
template <typename T, std::size_t Capacity> | ||
struct has_capacity<boost::lockfree::queue<T, boost::lockfree::capacity<Capacity>>> : std::true_type | ||
{ | ||
}; | ||
|
||
template <typename T, std::size_t Capacity, bool FixedSize> | ||
struct has_capacity<boost::lockfree::queue< | ||
T, boost::lockfree::capacity<Capacity>, boost::lockfree::fixed_sized<FixedSize>>> : std::true_type | ||
{ | ||
}; | ||
|
||
// Traits to check if the queue is spsc_queue | ||
template <typename T> | ||
struct is_spsc_queue : std::false_type | ||
{ | ||
}; | ||
|
||
template <typename T> | ||
struct is_spsc_queue<boost::lockfree::spsc_queue<T>> : std::true_type | ||
{ | ||
}; | ||
|
||
template <typename T, std::size_t Capacity> | ||
struct is_spsc_queue<boost::lockfree::spsc_queue<T, boost::lockfree::capacity<Capacity>>> | ||
: std::true_type | ||
{ | ||
}; | ||
|
||
// Traits to get the capacity of the queue | ||
// Default case: no capacity | ||
template <typename T> | ||
struct get_boost_lockfree_queue_capacity | ||
{ | ||
static constexpr std::size_t value = 0; // Default to 0 if capacity is not defined | ||
}; | ||
|
||
// Specialization for queues with capacity | ||
template <typename T, std::size_t Capacity> | ||
struct get_boost_lockfree_queue_capacity< | ||
boost::lockfree::spsc_queue<T, boost::lockfree::capacity<Capacity>>> | ||
{ | ||
static constexpr std::size_t value = Capacity; | ||
}; | ||
|
||
// Specialization for queues with capacity | ||
template <typename T, std::size_t Capacity> | ||
struct get_boost_lockfree_queue_capacity< | ||
boost::lockfree::queue<T, boost::lockfree::capacity<Capacity>>> | ||
{ | ||
static constexpr std::size_t value = Capacity; | ||
}; | ||
|
||
// Specialization for queues with capacity | ||
template <typename T, std::size_t Capacity, bool FixedSize> | ||
struct get_boost_lockfree_queue_capacity<boost::lockfree::queue< | ||
T, boost::lockfree::capacity<Capacity>, boost::lockfree::fixed_sized<FixedSize>>> | ||
{ | ||
static constexpr std::size_t value = Capacity; | ||
}; | ||
|
||
} // namespace | ||
|
||
namespace realtime_tools | ||
{ | ||
template <typename DataType, typename LockFreeContainer> | ||
class LockFreeQueueBase | ||
/** | ||
* @brief A base class for lock-free queues. | ||
* | ||
* This class provides a base implementation for lock-free queues with various functionalities | ||
* such as pushing, popping, and checking the state of the queue. It supports both single-producer | ||
* single-consumer (SPSC) and multiple-producer multiple-consumer (MPMC) queues. | ||
* | ||
* @tparam DataType The type of data to be stored in the queue. | ||
* @tparam LockFreeContainer The underlying lock-free container type - Typically boost::lockfree::spsc_queue or boost::lockfree::queue with their own template parameters | ||
*/ | ||
{ | ||
public: | ||
using T = DataType; | ||
|
||
/** | ||
* @brief Construct a new LockFreeQueueBase object | ||
* @note This constructor is enabled only if the LockFreeContainer has a capacity set | ||
*/ | ||
template < | ||
bool HasCapacity = has_capacity<LockFreeContainer>::value, | ||
typename std::enable_if_t<HasCapacity, int> = 0> | ||
LockFreeQueueBase() : capacity_(get_boost_lockfree_queue_capacity<LockFreeContainer>::value) | ||
{ | ||
} | ||
|
||
/** | ||
* @brief Construct a new LockFreeQueueBase object | ||
* @param capacity Capacity of the queue | ||
* @note This constructor is enabled only if the LockFreeContainer has no capacity set | ||
*/ | ||
template < | ||
bool HasCapacity = has_capacity<LockFreeContainer>::value, | ||
typename std::enable_if_t<!HasCapacity, int> = 1> | ||
explicit LockFreeQueueBase(std::size_t capacity) : data_queue_(capacity), capacity_(capacity) | ||
{ | ||
} | ||
|
||
virtual ~LockFreeQueueBase() = default; | ||
|
||
/** | ||
* @brief Pop the data from the queue | ||
* @param data Data to be popped | ||
* @return true If the data is popped successfully | ||
* @return false If the queue is empty or the data could not be popped | ||
*/ | ||
[[nodiscard]] bool pop(T & data) { return data_queue_.pop(data); } | ||
|
||
/** | ||
* @brief Pop the data from the queue | ||
* @param data Data to be popped | ||
* @return true If the data is popped successfully | ||
* @return false If the queue is empty or the data could not be popped | ||
* @note This function is enabled only if the data type is convertible to the template type of the queue | ||
*/ | ||
template <typename U> | ||
[[nodiscard]] std::enable_if_t<std::is_convertible_v<T, U>, bool> pop(U & data) | ||
{ | ||
return data_queue_.pop(data); | ||
} | ||
|
||
/** | ||
* @brief Push the data into the queue | ||
* @param data Data to be pushed | ||
* @return true If the data is pushed successfully | ||
* @return false If the queue is full or the data could not be pushed | ||
*/ | ||
|
||
[[nodiscard]] bool push(const T & data) | ||
{ | ||
if constexpr (is_spsc_queue<LockFreeContainer>::value) { | ||
return data_queue_.push(data); | ||
} else { | ||
return data_queue_.bounded_push(data); | ||
} | ||
} | ||
|
||
/** | ||
* @brief Push the data into the queue | ||
* @param data Data to be pushed | ||
* @return true If the data is pushed successfully | ||
* @return false If the queue is full or the data could not be pushed | ||
* @note This function is enabled only if the data type is convertible to the template type of the queue | ||
*/ | ||
template <typename U> | ||
[[nodiscard]] std::enable_if_t<std::is_convertible_v<T, U>, bool> push(const U & data) | ||
{ | ||
if constexpr (is_spsc_queue<LockFreeContainer>::value) { | ||
return data_queue_.push(data); | ||
} else { | ||
return data_queue_.bounded_push(data); | ||
} | ||
} | ||
|
||
/** | ||
* @brief The bounded_push function pushes the data into the queue and pops the oldest data if the queue is full | ||
* @param data Data to be pushed | ||
* @return true If the data is pushed successfully | ||
* @return false If the data could not be pushed | ||
* @note This function is enabled only if the queue is a spsc_queue and only if the data type | ||
* is convertible to the template type of the queue | ||
* @note For a SPSC Queue, to be used in single-threaded applications | ||
* @warning For a SPSC Queue, this method might not work as expected when used in multi-threaded applications | ||
* if it is used with two different threads, one doing bounded_push and the other doing pop. In this case, the | ||
* queue is no longer a single producer single consumer queue. So, the behavior might not be as expected. | ||
*/ | ||
template <typename U> | ||
[[nodiscard]] std::enable_if_t<std::is_convertible_v<T, U>, bool> bounded_push(const U & data) | ||
{ | ||
if (!push(data)) { | ||
T dummy; | ||
data_queue_.pop(dummy); | ||
return push(data); | ||
} | ||
return true; | ||
} | ||
|
||
/** | ||
* @brief Get the latest data from the queue | ||
* @param data Data to be filled with the latest data | ||
* @return true If the data is filled with the latest data, false otherwise | ||
* @return false If the queue is empty | ||
* @note This function consumes all the data in the queue until the last data and returns the last element of the queue | ||
*/ | ||
[[nodiscard]] bool get_latest(T & data) | ||
{ | ||
return data_queue_.consume_all([&data](const T & d) { data = d; }) > 0; | ||
} | ||
|
||
/** | ||
* @brief Check if the queue is empty | ||
* @return true If the queue is empty | ||
* @return false If the queue is not empty | ||
* @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. | ||
* @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. | ||
*/ | ||
bool empty() const | ||
{ | ||
if constexpr (is_spsc_queue<LockFreeContainer>::value) { | ||
return data_queue_.read_available() == 0; | ||
} else { | ||
return data_queue_.empty(); | ||
} | ||
} | ||
|
||
/** | ||
* @brief Get the capacity of the queue | ||
* @return std::size_t Capacity of the queue | ||
*/ | ||
size_t capacity() const { return capacity_; } | ||
|
||
/** | ||
* @brief Get the size of the queue | ||
* @return std::size_t Size of the queue | ||
* @note This function is enabled only if the queue is a spsc_queue | ||
*/ | ||
template < | ||
bool IsSPSCQueue = is_spsc_queue<LockFreeContainer>::value, | ||
typename std::enable_if_t<IsSPSCQueue, int> = 0> | ||
std::size_t size() const | ||
{ | ||
return data_queue_.read_available(); | ||
} | ||
|
||
/** | ||
* @brief The method to check if the queue is lock free | ||
* @return true If the queue is lock free, false otherwise | ||
* @warning It only checks, if the queue head and tail nodes and the freelist can | ||
* be modified in a lock-free manner. On most platforms, the whole implementation | ||
* is lock-free, if this is true. Using c++0x-style atomics, there is no possibility | ||
* to provide a completely accurate implementation, because one would need to test | ||
* every internal node, which is impossible if further nodes will be allocated from | ||
* the operating system. | ||
* @link https://www.boost.org/doc/libs/1_74_0/doc/html/boost/lockfree/queue.html | ||
*/ | ||
bool is_lock_free() const | ||
{ | ||
return (is_spsc_queue<LockFreeContainer>::value) || data_queue_.is_lock_free(); | ||
} | ||
|
||
/** | ||
* @brief Get the lockfree container | ||
* @return const LockFreeContainer& Reference to the lockfree container | ||
*/ | ||
const LockFreeContainer & get_lockfree_container() const { return data_queue_; } | ||
|
||
/** | ||
* @brief Get the lockfree container | ||
* @return LockFreeContainer& Reference to the lockfree container | ||
*/ | ||
LockFreeContainer & get_lockfree_container() { return data_queue_; } | ||
|
||
private: | ||
LockFreeContainer data_queue_; | ||
std::size_t capacity_; | ||
}; // class | ||
|
||
/** | ||
* @brief Lock-free Single Producer Single Consumer Queue | ||
* @tparam DataType Type of the data to be stored in the queue | ||
* @tparam Capacity Capacity of the queue | ||
*/ | ||
template <class DataType, std::size_t Capacity = 0> | ||
using LockFreeSPSCQueue = std::conditional_t< | ||
Capacity == 0, LockFreeQueueBase<DataType, boost::lockfree::spsc_queue<DataType>>, | ||
LockFreeQueueBase< | ||
DataType, boost::lockfree::spsc_queue<DataType, boost::lockfree::capacity<Capacity>>>>; | ||
|
||
/** | ||
* @brief Lock-free Multiple Producer Multiple Consumer Queue | ||
* @tparam DataType Type of the data to be stored in the queue | ||
* @tparam Capacity Capacity of the queue | ||
* @tparam FixedSize Fixed size of the queue | ||
*/ | ||
template <class DataType, std::size_t Capacity = 0, bool FixedSize = true> | ||
using LockFreeMPMCQueue = 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>>>>; | ||
|
||
} // namespace realtime_tools | ||
#endif // REALTIME_TOOLS__LOCK_FREE_QUEUE_HPP_ |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Oops, something went wrong.
Oops, something went wrong.
Add this suggestion to a batch that can be applied as a single commit.
This suggestion is invalid because no changes were made to the code.
Suggestions cannot be applied while the pull request is closed.
Suggestions cannot be applied while viewing a subset of changes.
Only one suggestion per line can be applied in a batch.
Add this suggestion to a batch that can be applied as a single commit.
Applying suggestions on deleted lines is not supported.
You must change the existing code in this line in order to create a valid suggestion.
Outdated suggestions cannot be applied.
This suggestion has been applied or marked resolved.
Suggestions cannot be applied from pending reviews.
Suggestions cannot be applied on multi-line comments.
Suggestions cannot be applied while the pull request is queued to merge.
Suggestion cannot be applied right now. Please check back later.
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
is there a smaller dependency by any chance?
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
https://github.com/ros/rosdistro/blob/master/rosdep/base.yaml#L2833-L2842
It is basic core one
If boost is included, then it pulls in everything