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::Selector< Inputs, Is > Class Template Reference

Reorder or reduce an N-ary filter. More...

#include <fkie_message_filters/selector.h>

Inheritance diagram for fkie_message_filters::Selector< Inputs, Is >:
Inheritance graph
[legend]
Collaboration diagram for fkie_message_filters::Selector< Inputs, Is >:
Collaboration graph
[legend]

Public Types

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

Public Member Functions

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...
 
virtual void reset () noexcept
 Reset filter state. 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

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, std::size_t... Is>
class fkie_message_filters::Selector< Inputs, Is >

Reorder or reduce an N-ary filter.

This filter reorders the arguments of an N-ary filter and/or chooses an arbitrary subset of the input arguments. The output arguments are selected from the input by index. The following example reduces a ternary filter to a binary filter of the first two arguments, in swapped order:

namespace mf = fkie_message_filters;
using BufferIn = mf::Buffer<T0, T1, T2>;
using Select = mf::Selector<BufferIn::Output, 1, 0>;
using BufferOut = mf::Buffer<T1, T0>;
BufferIn buf_in;
Select select;
BufferOut buf_out;
mf::chain(buf_in, select, buf_out);
See also
Divider, Combiner

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.

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.

◆ receive()

template<class... Inputs, std::size_t... Is>
void fkie_message_filters::Selector< Inputs, Is >::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()

virtual void fkie_message_filters::FilterBase::reset ( )
inlinevirtualnoexceptinherited

Reset filter state.

For stateful filters, this method resets the internal state as if the filter had just been created. Existing connections to sources and sinks are unaffected.

The default implementation does nothing.

Exceptions
Does not throw any exceptions.

Reimplemented in fkie_message_filters::Buffer< Inputs >, fkie_message_filters::Buffer< Inputs... >, fkie_message_filters::TfFilter< Inputs >, fkie_message_filters::TfFilter< Inputs... >, fkie_message_filters::Combiner< PolicyTmpl, IOs >, fkie_message_filters::Sequencer< Inputs >, and fkie_message_filters::Sequencer< Inputs... >.

◆ 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.

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