Store and forward data. More...
#include <buffer.h>
Classes | |
struct | Impl |
class | RosCB |
Public Member Functions | |
Buffer (const ros::NodeHandle &nh, std::size_t max_queue_size) noexcept | |
Constructor. More... | |
Buffer (BufferPolicy policy=BufferPolicy::Discard, std::size_t max_queue_size=1, ros::CallbackQueueInterface *cbq=nullptr) noexcept | |
Constructor. More... | |
bool | has_some () const noexcept |
Check if the buffer has pending data. More... | |
bool | process_one () |
Wait for and process one data item. More... | |
template<class Rep , class Period > | |
bool | process_one (const std::chrono::duration< Rep, Period > &timeout) |
Wait for and process one data item. More... | |
void | reset () noexcept override |
Reset filter. More... | |
void | set_callback_queue (ros::CallbackQueueInterface *cbq) noexcept |
Process data with a ROS callback queue. More... | |
void | set_policy (BufferPolicy policy, std::size_t max_queue_size=0) |
Modify the buffer policy. More... | |
void | spin () |
Process all data indefinitely. More... | |
void | spin_once () |
Process pending data. More... | |
bool | wait () noexcept |
Wait for pending data. More... | |
template<class Rep , class Period > | |
bool | wait_for (const std::chrono::duration< Rep, Period > &timeout) noexcept |
Wait for pending data until timeout expires. More... | |
virtual | ~Buffer () |
Protected Member Functions | |
virtual void | receive (const Inputs &... in) override |
Process incoming data. More... | |
Private Types | |
using | QueueElement = std::tuple< Inputs... > |
Private Member Functions | |
void | process_some (std::unique_lock< std::mutex > &) |
void | send_queue_element (const QueueElement &e) |
Private Attributes | |
ros::CallbackQueueInterface * | cbq_ |
std::shared_ptr< Impl > | impl_ |
Additional Inherited Members |
Store and forward data.
The buffer acts as a decoupler in the filter pipeline. Data can be stored and processed at a later time. The pipeline is effectively split into independent upstream and downstream parts, and it becomes possible to run the downstream data processing asynchronously. For instance, you can run computationally expensive algorithms on ROS messages in a different thread without blocking the ROS subscriber callback queue.
The buffer can be used for at least three different use cases:
|
private |
|
noexcept |
Constructor.
Constructs a buffer with BufferPolicy::Queue policy and data processing via ROS callbacks.
nh
ROS node handle whose callback queue is used for data processing max_queue_size
the maximum number of queued data itemsDefinition at line 113 of file buffer_impl.h.
|
noexcept |
Constructor.
policy
the buffer policy max_queue_size
for the BufferPolicy::Queue policy, the maximum number of queued data items. cbq
ROS callback queue that is used to process queued dataDefinition at line 106 of file buffer_impl.h.
|
virtual |
Definition at line 120 of file buffer_impl.h.
|
noexcept |
Check if the buffer has pending data.
true | if the current policy is BufferPolicy::Queue and a subsequent call to process_one() or spin_once() will process data. |
false | otherwise |
Definition at line 191 of file buffer_impl.h.
bool fkie_message_filters::Buffer< Inputs >::process_one | ( | ) |
Wait for and process one data item.
true | data has been processed successfully |
false | either the current buffer policy is not BufferPolicy::Queue, or the policy has been changed to something other than BufferPolicy::Queue while the function was waiting, or the ROS node has been shut down. |
Definition at line 213 of file buffer_impl.h.
bool fkie_message_filters::Buffer< Inputs >::process_one | ( | const std::chrono::duration< Rep, Period > & | timeout | ) |
Wait for and process one data item.
timeout
maximum duration to wait for new data if none is availabletrue | data has been processed successfully |
false | either the current buffer policy is not BufferPolicy::Queue, or the policy has been changed to something other than BufferPolicy::Queue while the function was waiting, or time timeout expired, or the ROS node has been shut down. |
Definition at line 229 of file buffer_impl.h.
|
private |
Definition at line 176 of file buffer_impl.h.
|
overrideprotectedvirtual |
Process incoming data.
Derived classes need to override this method to handle all data that is to be consumed by the sink.
Implements fkie_message_filters::Sink< Inputs... >.
Definition at line 244 of file buffer_impl.h.
|
overridevirtualnoexcept |
Reset filter.
If the buffer policy is BufferPolicy::Queue, this will clear the internal queue and discard all pending data. Otherwise, this function has no effect.
Reimplemented from fkie_message_filters::FilterBase.
Definition at line 167 of file buffer_impl.h.
|
private |
Definition at line 279 of file buffer_impl.h.
|
noexcept |
Process data with a ROS callback queue.
Instead of running your own processing threads, you can use the ROS callback system to schedule data processing whenever new data arrives.
cbq
the ROS callback queue or nullptr
to disable ROS callbacks.Definition at line 153 of file buffer_impl.h.
void fkie_message_filters::Buffer< Inputs >::set_policy | ( | BufferPolicy | policy, |
std::size_t | max_queue_size = 0 |
||
) |
Modify the buffer policy.
If the new buffer policy is not BufferPolicy::Queue, any pending call to wait(), process_one(), or spin() will return. If the buffer policy is changed to BufferPolicy::Passthru, all pending data is processed immediately before the function returns. If the buffer policy is changed to BufferPolicy::Discard, all pending data is discarded immediately.
policy
the buffer policy max_queue_size
for the BufferPolicy::Queue policy, the maximum number of queued data items. If zero, the previously set queue size remains unchanged.Definition at line 126 of file buffer_impl.h.
void fkie_message_filters::Buffer< Inputs >::spin | ( | ) |
Process all data indefinitely.
Blocks and processes all incoming data until the buffer policy is changed to something other than BufferPolicy::Queue or the ROS node is shut down.
You can call the function from multiple threads at once, and the workload will be shared among all participating threads.
Definition at line 265 of file buffer_impl.h.
void fkie_message_filters::Buffer< Inputs >::spin_once | ( | ) |
Process pending data.
Does nothing if the buffer policy is not BufferPolicy::Queue. The method is guaranteed to return as it will only process data which is pending at invocation time. This also means that there may be new data pending already when this method returns.
Definition at line 160 of file buffer_impl.h.
|
noexcept |
Wait for pending data.
true | there is data available for consumption by spin_once() |
false | either the current buffer policy is not BufferPolicy::Queue, or the policy has been changed to something other than BufferPolicy::Queue while the function was waiting, or the ROS node has been shut down. |
Definition at line 198 of file buffer_impl.h.
|
noexcept |
Wait for pending data until timeout expires.
timeout
maximum duration to wait for new data if none is availabletrue | there is data available for consumption by spin_once() |
false | either the current buffer policy is not BufferPolicy::Queue, or the policy has been changed to something other than BufferPolicy::Queue while the function was waiting, or the timeout expired, or the ROS node has been shut down. |
Definition at line 206 of file buffer_impl.h.
|
private |
|
private |