FKIE Message Filters
Improved filters for processing ROS messages
Public Types | Public Member Functions | Static Public Attributes | Protected Member Functions | List of all members
fkie_message_filters::Buffer< Inputs > Class Template Reference

Store and forward data. More...

#include <fkie_message_filters/buffer.h>

Inheritance diagram for fkie_message_filters::Buffer< Inputs >:
Inheritance graph
[legend]
Collaboration diagram for fkie_message_filters::Buffer< Inputs >:
Collaboration graph
[legend]

Public Types

using Input = IO< Inputs... >
 Grouped input types. More...
 
using Output = IO< Outputs... >
 Grouped output types. More...
 

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...
 
Connection connect_to_sink (Sink< Outputs... > &dst) noexcept
 Connect this source to a sink. More...
 
Connection connect_to_source (Source< Inputs... > &src) noexcept
 Connect this sink to a source. More...
 
void disconnect_from_all_sinks () noexcept
 Disconnect from all connected sinks. More...
 
void disconnect_from_all_sources () noexcept
 Disconnect from all connected sources. 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...
 

Static Public Attributes

static constexpr std::size_t NUM_INPUTS = sizeof...(Inputs)
 Number of input arguments.
 
static constexpr std::size_t NUM_OUTPUTS
 Number of output arguments.
 

Protected Member Functions

virtual void receive (const Inputs &... in) override
 Process incoming data. More...
 
void send (const Outputs &... out)
 Pass data to all connected sinks. More...
 

Detailed Description

template<class... Inputs>
class fkie_message_filters::Buffer< Inputs >

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:

  1. Use the buffer as a valve
    You can toggle between the BufferPolicy::Discard and BufferPolicy::Passthru modes to selectively disable or enable data processing at specific times. This is the simplest use case without any asynchronous processing.
  2. Run multiple ROS callback queues
    If your ROS node runs multiple callback queues, you can use the buffer to bind processing to a particular queue:
    namespace mf = fkie_message_filters;
    ros::NodeHandle nh;
    nh.setCallbackQueue(...);
    // Version 1
    mf::Buffer<M> buf1(nh, 10); // will use the callback queue of nh
    // Version 2
    mf::Buffer<M> buf2(mf::BufferPolicy::Queue, 10);
    buf2.set_callback_queue(...); // will explicitly set the ROS callback queue
  3. Run your own thread(s) for data processing
    This is the most versatile option for advanced users. You can set up your worker threads as you desire and then call spin(), spin_once() or process_one() as you see fit.
    namespace mf = fkie_message_filters;
    mf::Subscriber<M> sub;
    mf::Buffer<mf::Subscriber<M>::Output> buffer(mf::BufferPolicy::Queue, 10);
    mf::SimpleUserFilter<mf::Subscriber<M>::Output> flt;
    std::thread t([&buffer]{ buffer.spin(); });
    flt.set_processing_function(...);
    mf::chain(sub, buffer, flt);
    ros::spin();

Member Typedef Documentation

◆ Input

template<typename... Inputs>
using fkie_message_filters::Sink< Inputs >::Input = IO<Inputs...>
inherited

Grouped input types.

This type can be used to define sources with matching types.

◆ Output

using fkie_message_filters::Source< Outputs >::Output = IO<Outputs...>
inherited

Grouped output types.

This type can be used to define sinks with matching types.

Constructor & Destructor Documentation

◆ Buffer() [1/2]

template<class... Inputs>
fkie_message_filters::Buffer< Inputs >::Buffer ( const ros::NodeHandle &  nh,
std::size_t  max_queue_size 
)
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 items
Exceptions
Does not throw any exceptions.

◆ Buffer() [2/2]

template<class... Inputs>
fkie_message_filters::Buffer< Inputs >::Buffer ( BufferPolicy  policy = BufferPolicy::Discard,
std::size_t  max_queue_size = 1,
ros::CallbackQueueInterface *  cbq = nullptr 
)
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 data
Exceptions
Does not throw any exceptions.
See also
set_policy(), set_callback_queue()

Member Function Documentation

◆ connect_to_sink()

Connection fkie_message_filters::Source< Outputs >::connect_to_sink ( Sink< Outputs... > &  dst)
noexceptinherited

Connect this source to a sink.

Can be called multiple times to connect multiple sinks; in that case, the sinks receive data in the same order as they have been connected. This function does basically the same thing as Sink::connect_to_source(), only from the opposite point of view.

  • dst the sink that is to be connected
Returns
a connection object that can be used to monitor or sever the created connection
Exceptions
Does not throw any exceptions.

◆ connect_to_source()

template<typename... Inputs>
Connection fkie_message_filters::Sink< Inputs >::connect_to_source ( Source< Inputs... > &  src)
noexceptinherited

Connect this sink to a source.

Can be called multiple times to connect multiple sources; in that case, the sink receives data from all connected sources. This function does basically the same thing as Source::connect_to_sink(), only from the opposite point of view.

  • src the source that is to be connected
Returns
a connection object that can be used to monitor or sever the created connection
Exceptions
Does not throw any exceptions.

◆ disconnect_from_all_sinks()

void fkie_message_filters::Source< Outputs >::disconnect_from_all_sinks ( )
noexceptinherited

Disconnect from all connected sinks.

Severs the connection to all sinks, turning the send() method into a no-op.

Exceptions
Does not throw any exceptions.

◆ disconnect_from_all_sources()

template<typename... Inputs>
void fkie_message_filters::Sink< Inputs >::disconnect_from_all_sources ( )
noexceptinherited

Disconnect from all connected sources.

Severs the connection to all sources. The receive() method will not be called any more.

Exceptions
Does not throw any exceptions.

◆ has_some()

template<class... Inputs>
bool fkie_message_filters::Buffer< Inputs >::has_some ( ) const
noexcept

Check if the buffer has pending data.

Return values
trueif the current policy is BufferPolicy::Queue and a subsequent call to process_one() or spin_once() will process data.
falseotherwise
Exceptions
Does not throw any exceptions.

◆ process_one() [1/2]

template<class... Inputs>
bool fkie_message_filters::Buffer< Inputs >::process_one ( )

Wait for and process one data item.

Return values
truedata has been processed successfully
falseeither 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.
Exceptions
Does not throw any exceptions, but will propagate uncaught exceptions from filter callbacks.

◆ process_one() [2/2]

template<class... Inputs>
template<class Rep , class Period >
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 available
Return values
truedata has been processed successfully
falseeither 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.
Exceptions
Does not throw any exceptions, but will propagate uncaught exceptions from filter callbacks.

◆ receive()

template<class... Inputs>
virtual void fkie_message_filters::Buffer< Inputs >::receive ( const Inputs &...  in)
overrideprotectedvirtual

Process incoming data.

Derived classes need to override this method to handle all data that is to be consumed by the sink.

Exceptions
Depends on the implementation.

Implements fkie_message_filters::Sink< Inputs >.

◆ reset()

template<class... Inputs>
void fkie_message_filters::Buffer< Inputs >::reset ( )
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.

Exceptions
Does not throw any exceptions.

Reimplemented from fkie_message_filters::FilterBase.

◆ send()

void fkie_message_filters::Source< Outputs >::send ( const Outputs &...  out)
protectedinherited

Pass data to all connected sinks.

  • out data
Exceptions
Does not throw any exceptions, but will propagate uncaught exceptions from filter callbacks.

◆ set_callback_queue()

template<class... Inputs>
void fkie_message_filters::Buffer< Inputs >::set_callback_queue ( ros::CallbackQueueInterface *  cbq)
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.
Exceptions
Does not throw any exceptions.
namespace mf = fkie_message_filters;
mf::Buffer<...> buf;
buf.set_callback_queue(ros::getGlobalCallbackQueue());
ros::spin();

◆ set_policy()

template<class... Inputs>
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.
Warning
If you change the policy from BufferPolicy::Queue to BufferPolicy::Passthru and there is still a pending call to process_one(), spin_once(), or spin() in a different thread, some data might be processed in parallel or out of order when the queue is flushed.
Exceptions
Does not throw any exceptions, but will propagate uncaught exceptions from filter callbacks.

◆ spin()

template<class... Inputs>
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.

Exceptions
Does not throw any exceptions, but will propagate uncaught exceptions from filter callbacks.
See also
set_policy()

◆ spin_once()

template<class... Inputs>
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.

Exceptions
Does not throw any exceptions, but will propagate uncaught exceptions from filter callbacks.

◆ wait()

template<class... Inputs>
bool fkie_message_filters::Buffer< Inputs >::wait ( )
noexcept

Wait for pending data.

Return values
truethere is data available for consumption by spin_once()
falseeither 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.
Exceptions
Does not throw any exceptions.

◆ wait_for()

template<class... Inputs>
template<class Rep , class Period >
bool fkie_message_filters::Buffer< Inputs >::wait_for ( const std::chrono::duration< Rep, Period > &  timeout)
noexcept

Wait for pending data until timeout expires.

  • timeout maximum duration to wait for new data if none is available
Return values
truethere is data available for consumption by spin_once()
falseeither 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.
Exceptions
Does not throw any exceptions.

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