ros2_control - humble
Loading...
Searching...
No Matches
Public Types | Public Member Functions | List of all members
realtime_tools::LockFreeQueueBase< DataType, LockFreeContainer > Class Template Reference

A base class for lock-free queues. More...

#include <lock_free_queue.hpp>

Public Types

using T = DataType
 

Public Member Functions

template<bool HasCapacity = has_capacity<LockFreeContainer>::value, typename std::enable_if_t< HasCapacity, int > = 0>
 LockFreeQueueBase ()
 Construct a new LockFreeQueueBase object.
 
template<bool HasCapacity = has_capacity<LockFreeContainer>::value, typename std::enable_if_t<!HasCapacity, int > = 1>
 LockFreeQueueBase (std::size_t capacity)
 Construct a new LockFreeQueueBase object.
 
bool pop (T &data)
 Pop the data from the queue.
 
template<typename U >
std::enable_if_t< std::is_convertible_v< T, U >, boolpop (U &data)
 Pop the data from the queue.
 
bool push (const T &data)
 Push the data into the queue.
 
template<typename U >
std::enable_if_t< std::is_convertible_v< T, U >, boolpush (const U &data)
 Push the data into the queue.
 
template<typename U >
std::enable_if_t< std::is_convertible_v< T, U >, boolbounded_push (const U &data)
 The bounded_push function pushes the data into the queue and pops the oldest data if the queue is full.
 
bool get_latest (T &data)
 Get the latest data from the queue.
 
bool empty () const
 Check if the queue is empty.
 
size_t capacity () const
 Get the capacity of the queue.
 
template<bool IsSPSCQueue = is_spsc_queue<LockFreeContainer>::value, typename std::enable_if_t< IsSPSCQueue, int > = 0>
std::size_t size () const
 Get the size of the queue.
 
bool is_lock_free () const
 The method to check if the queue is lock free.
 
const LockFreeContainerget_lockfree_container () const
 Get the lockfree container.
 
LockFreeContainerget_lockfree_container ()
 Get the lockfree container.
 

Detailed Description

template<typename DataType, typename LockFreeContainer>
class realtime_tools::LockFreeQueueBase< DataType, LockFreeContainer >

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.

Template Parameters
DataTypeThe type of data to be stored in the queue.
LockFreeContainerThe underlying lock-free container type - Typically boost::lockfree::spsc_queue or boost::lockfree::queue with their own template parameters

Constructor & Destructor Documentation

◆ LockFreeQueueBase() [1/2]

template<typename DataType , typename LockFreeContainer >
template<bool HasCapacity = has_capacity<LockFreeContainer>::value, typename std::enable_if_t< HasCapacity, int > = 0>
realtime_tools::LockFreeQueueBase< DataType, LockFreeContainer >::LockFreeQueueBase ( )
inline

Construct a new LockFreeQueueBase object.

Note
This constructor is enabled only if the LockFreeContainer has a capacity set

◆ LockFreeQueueBase() [2/2]

template<typename DataType , typename LockFreeContainer >
template<bool HasCapacity = has_capacity<LockFreeContainer>::value, typename std::enable_if_t<!HasCapacity, int > = 1>
realtime_tools::LockFreeQueueBase< DataType, LockFreeContainer >::LockFreeQueueBase ( std::size_t  capacity)
inlineexplicit

Construct a new LockFreeQueueBase object.

Parameters
capacityCapacity of the queue
Note
This constructor is enabled only if the LockFreeContainer has no capacity set

Member Function Documentation

◆ bounded_push()

template<typename DataType , typename LockFreeContainer >
template<typename U >
std::enable_if_t< std::is_convertible_v< T, U >, bool > realtime_tools::LockFreeQueueBase< DataType, LockFreeContainer >::bounded_push ( const U data)
inline

The bounded_push function pushes the data into the queue and pops the oldest data if the queue is full.

Parameters
dataData to be pushed
Returns
true If the data is pushed successfully
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
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.

◆ capacity()

template<typename DataType , typename LockFreeContainer >
size_t realtime_tools::LockFreeQueueBase< DataType, LockFreeContainer >::capacity ( ) const
inline

Get the capacity of the queue.

Returns
std::size_t Capacity of the queue

◆ empty()

template<typename DataType , typename LockFreeContainer >
bool realtime_tools::LockFreeQueueBase< DataType, LockFreeContainer >::empty ( ) const
inline

Check if the queue is empty.

Returns
true If the queue is empty
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.
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.

◆ get_latest()

template<typename DataType , typename LockFreeContainer >
bool realtime_tools::LockFreeQueueBase< DataType, LockFreeContainer >::get_latest ( T &  data)
inline

Get the latest data from the queue.

Parameters
dataData to be filled with the latest data
Returns
true If the data is filled with the latest data, false otherwise
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

◆ get_lockfree_container() [1/2]

template<typename DataType , typename LockFreeContainer >
LockFreeContainer & realtime_tools::LockFreeQueueBase< DataType, LockFreeContainer >::get_lockfree_container ( )
inline

Get the lockfree container.

Returns
LockFreeContainer& Reference to the lockfree container

◆ get_lockfree_container() [2/2]

template<typename DataType , typename LockFreeContainer >
const LockFreeContainer & realtime_tools::LockFreeQueueBase< DataType, LockFreeContainer >::get_lockfree_container ( ) const
inline

Get the lockfree container.

Returns
const LockFreeContainer& Reference to the lockfree container

◆ is_lock_free()

template<typename DataType , typename LockFreeContainer >
bool realtime_tools::LockFreeQueueBase< DataType, LockFreeContainer >::is_lock_free ( ) const
inline

The method to check if the queue is lock free.

Returns
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. https://www.boost.org/doc/libs/1_74_0/doc/html/boost/lockfree/queue.html

◆ pop() [1/2]

template<typename DataType , typename LockFreeContainer >
bool realtime_tools::LockFreeQueueBase< DataType, LockFreeContainer >::pop ( T &  data)
inline

Pop the data from the queue.

Parameters
dataData to be popped
Returns
true If the data is popped successfully
false If the queue is empty or the data could not be popped

◆ pop() [2/2]

template<typename DataType , typename LockFreeContainer >
template<typename U >
std::enable_if_t< std::is_convertible_v< T, U >, bool > realtime_tools::LockFreeQueueBase< DataType, LockFreeContainer >::pop ( U data)
inline

Pop the data from the queue.

Parameters
dataData to be popped
Returns
true If the data is popped successfully
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

◆ push() [1/2]

template<typename DataType , typename LockFreeContainer >
bool realtime_tools::LockFreeQueueBase< DataType, LockFreeContainer >::push ( const T &  data)
inline

Push the data into the queue.

Parameters
dataData to be pushed
Returns
true If the data is pushed successfully
false If the queue is full or the data could not be pushed

◆ push() [2/2]

template<typename DataType , typename LockFreeContainer >
template<typename U >
std::enable_if_t< std::is_convertible_v< T, U >, bool > realtime_tools::LockFreeQueueBase< DataType, LockFreeContainer >::push ( const U data)
inline

Push the data into the queue.

Parameters
dataData to be pushed
Returns
true If the data is pushed successfully
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

◆ size()

template<typename DataType , typename LockFreeContainer >
template<bool IsSPSCQueue = is_spsc_queue<LockFreeContainer>::value, typename std::enable_if_t< IsSPSCQueue, int > = 0>
std::size_t realtime_tools::LockFreeQueueBase< DataType, LockFreeContainer >::size ( ) const
inline

Get the size of the queue.

Returns
std::size_t Size of the queue
Note
This function is enabled only if the queue is a spsc_queue

The documentation for this class was generated from the following file: