Public Types | Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
cras::FilterChain< F > Class Template Reference

#include <filter_chain.hpp>

Inheritance diagram for cras::FilterChain< F >:
Inheritance graph
[legend]

Public Types

typedef ::std::function< void(const F &data, const size_t filterNum, const ::std::string &name, const ::std::string &type, bool success)> FilterFinishedCallback
 Callback to be called after each filter processes the data. More...
 
typedef ::std::function< void(const F &data, const size_t filterNum, const ::std::string &name, const ::std::string &type)> FilterStartCallback
 Callback to be called before each filter processes the data. More...
 

Public Member Functions

bool clear ()
 Clear all filters from this chain. This function intentionally shadows filters::FilterChain::clear() which is non-virtual. More...
 
void disableFilter (const ::std::string &name)
 Temporarily disable the filter with the given name. More...
 
void enableFilter (const ::std::string &name)
 Enable the temporarily disabled filter with the given name. More...
 
 FilterChain (const ::std::string &dataType, const FilterFinishedCallback &filterFinishedCallback={}, const FilterStartCallback &filterStartCallback={}, const ::cras::LogHelperPtr &logHelper=::std::make_shared<::cras::NodeLogHelper >())
 Construct a filter chain. More...
 
::std::vector<::std::shared_ptr<::filters::FilterBase< F > > > getActiveFilters () const
 Get a copy of the list of active filters. More...
 
::std::unordered_set<::std::string > getDisabledFilters () const
 Get which filters are temporarily disabled. More...
 
void setDisabledFilters (::std::unordered_set<::std::string > filters)
 Set which filters are temporarily disabled. This overrides any previous calls to disableFilter() and enableFilter(). More...
 
void setFilterFinishedCallback (const FilterFinishedCallback &callback)
 Set the filter finished callback. More...
 
void setFilterStartCallback (const FilterStartCallback &callback)
 Set the filter start callback. More...
 
void setNodelet (const ::nodelet::Nodelet *nodelet)
 Inform this chain that it is running in the given nodelet, so that it can do appropriate optimizations. This should be done after the filters are configured. More...
 
bool update (const F &data_in, F &data_out)
 Do the filtering. This function intentionally shadows filters::FilterChain::update() which is non-virtual. More...
 
- Public Member Functions inherited from filters::FilterChain< F >
bool clear ()
 
bool configure (std::string param_name, ros::NodeHandle node=ros::NodeHandle())
 
bool configure (XmlRpc::XmlRpcValue &config, const std::string &filter_ns)
 
 FilterChain (std::string data_type)
 
std::vector< std::shared_ptr< filters::FilterBase< T > > > getFilters () const
 
bool update (const T &data_in, T &data_out)
 
 ~FilterChain ()
 

Protected Member Functions

void callFinishedCallback (const F &data, size_t filterNum, bool succeeded)
 If filterFinishedCallback is set, call it. More...
 
void callStartCallback (const F &data, size_t filterNum)
 If filterStartCallback is set, call it. More...
 
void updateActiveFilters ()
 Update the contents of activeFilters with just the filters that have not been disabled. More...
 

Protected Attributes

::std::vector<::std::shared_ptr<::filters::FilterBase< F > > > activeFilters
 A list of filters that should be treated as active and should act on the input data. More...
 
mutable ::std::mutex activeFiltersMutex
 Mutex protecting activeFilters access. More...
 
buffer0
 A temporary intermediate buffer. More...
 
buffer1
 A temporary intermediate buffer. More...
 
::std::unordered_set<::std::string > disabledFilters
 A set of filters that have been temporarily disabled. More...
 
FilterFinishedCallback filterFinishedCallback
 The optional callback to call when a filter finishes its work. More...
 
FilterStartCallback filterStartCallback
 The optional callback to call when a filter starts its work. More...
 
bool initialized {false}
 Whether this filter chain has been initialized (gets set by first update() and cleared by clear()). More...
 

Additional Inherited Members

- Private Member Functions inherited from cras::HasLogger
::cras::LogHelperConstPtr getCrasLogger () const
 This is the function picked up by CRAS_* logging macros. More...
 
 HasLogger (const ::cras::LogHelperPtr &log)
 Associate the logger with this interface. More...
 
void setCrasLogger (const ::cras::LogHelperPtr &log)
 Set the logger to be used for logging. More...
 
- Private Attributes inherited from cras::HasLogger
::cras::LogHelperPtr log
 Log helper. More...
 

Detailed Description

template<typename F>
class cras::FilterChain< F >

This filter chain implementation allows for selectively disabling/enabling filters during run time. It also adds a callback with the input and result of each filter run, so that you can e.g. publish the output of each filter.

Template Parameters
FType of the filtered data.

Definition at line 42 of file filter_chain.hpp.

Member Typedef Documentation

◆ FilterFinishedCallback

template<typename F >
typedef ::std::function< void(const F& data, const size_t filterNum, const ::std::string& name, const ::std::string& type, bool success)> cras::FilterChain< F >::FilterFinishedCallback

Callback to be called after each filter processes the data.

Parameters
[in]dataThe data after application of the filter.
[in]filterNumThe number of the filter in the filtering chain.
[in]nameName of the filter that processed the data.
[in]typeType of the filter that processed the data.
[in]successWhether the filter succeeded (its update() function returned true).

Definition at line 68 of file filter_chain.hpp.

◆ FilterStartCallback

template<typename F >
typedef ::std::function< void(const F& data, const size_t filterNum, const ::std::string& name, const ::std::string& type)> cras::FilterChain< F >::FilterStartCallback

Callback to be called before each filter processes the data.

Parameters
[in]dataThe data before application of the filter.
[in]filterNumThe number of the filter in the filtering chain.
[in]nameName of the filter that processed the data.
[in]typeType of the filter that processed the data.

Definition at line 55 of file filter_chain.hpp.

Constructor & Destructor Documentation

◆ FilterChain()

template<typename F >
cras::FilterChain< F >::FilterChain ( const ::std::string &  dataType,
const FilterFinishedCallback filterFinishedCallback = {},
const FilterStartCallback filterStartCallback = {},
const ::cras::LogHelperPtr logHelper = ::std::make_shared<::cras::NodeLogHelper >() 
)
explicit

Construct a filter chain.

Parameters
[in]dataTypeTextual representation of the data type.
[in]filterFinishedCallbackOptional callback to be called after each filter finishes its work.
[in]filterStartCallbackOptional callback to be called before each filter starts its work.
[in]logHelperThe log helper used for printing console messages.

Member Function Documentation

◆ callFinishedCallback()

template<typename F >
void cras::FilterChain< F >::callFinishedCallback ( const F &  data,
size_t  filterNum,
bool  succeeded 
)
protected

If filterFinishedCallback is set, call it.

Parameters
[in]dataThe filtered data to pass to the callback.
[in]filterNumNumber of the filter to pass to the callback.
[in]succeededWhether the filter succeeded (its update() function returned true).

◆ callStartCallback()

template<typename F >
void cras::FilterChain< F >::callStartCallback ( const F &  data,
size_t  filterNum 
)
protected

If filterStartCallback is set, call it.

Parameters
[in]dataThe filtered data to pass to the callback.
[in]filterNumNumber of the filter to pass to the callback.

◆ clear()

template<typename F >
bool cras::FilterChain< F >::clear ( )

Clear all filters from this chain. This function intentionally shadows filters::FilterChain::clear() which is non-virtual.

Returns
Always true.

◆ disableFilter()

template<typename F >
void cras::FilterChain< F >::disableFilter ( const ::std::string &  name)

Temporarily disable the filter with the given name.

Parameters
[in]nameName of the filter to disable. If the filter is not found, nothing happens.

◆ enableFilter()

template<typename F >
void cras::FilterChain< F >::enableFilter ( const ::std::string &  name)

Enable the temporarily disabled filter with the given name.

Parameters
[in]nameName of the filter to enable. If the filter is not found, nothing happens.

◆ getActiveFilters()

template<typename F >
::std::vector<::std::shared_ptr<::filters::FilterBase<F> > > cras::FilterChain< F >::getActiveFilters ( ) const

Get a copy of the list of active filters.

Returns
The active filters.

◆ getDisabledFilters()

template<typename F >
::std::unordered_set<::std::string> cras::FilterChain< F >::getDisabledFilters ( ) const

Get which filters are temporarily disabled.

Returns
The disabled filters.

◆ setDisabledFilters()

template<typename F >
void cras::FilterChain< F >::setDisabledFilters ( ::std::unordered_set<::std::string >  filters)

Set which filters are temporarily disabled. This overrides any previous calls to disableFilter() and enableFilter().

Parameters
[in]filtersThe filters to disable.

◆ setFilterFinishedCallback()

template<typename F >
void cras::FilterChain< F >::setFilterFinishedCallback ( const FilterFinishedCallback callback)

Set the filter finished callback.

Parameters
[in]callbackThe callback to set.

◆ setFilterStartCallback()

template<typename F >
void cras::FilterChain< F >::setFilterStartCallback ( const FilterStartCallback callback)

Set the filter start callback.

Parameters
[in]callbackThe callback to set.

◆ setNodelet()

template<typename F >
void cras::FilterChain< F >::setNodelet ( const ::nodelet::Nodelet nodelet)

Inform this chain that it is running in the given nodelet, so that it can do appropriate optimizations. This should be done after the filters are configured.

Parameters
[in]nodeletThe nodelet this chain is running in. Setting to nullptr will inform the chain it is not running inside a nodelet.

◆ update()

template<typename F >
bool cras::FilterChain< F >::update ( const F &  data_in,
F &  data_out 
)

Do the filtering. This function intentionally shadows filters::FilterChain::update() which is non-virtual.

Parameters
[in]data_inInput data.
[out]data_outThe filtered data.
Returns
Whether the filtering succeeded. If false, data_out should not be considered valid.

◆ updateActiveFilters()

template<typename F >
void cras::FilterChain< F >::updateActiveFilters ( )
protected

Update the contents of activeFilters with just the filters that have not been disabled.

Member Data Documentation

◆ activeFilters

template<typename F >
::std::vector<::std::shared_ptr<::filters::FilterBase<F> > > cras::FilterChain< F >::activeFilters
protected

A list of filters that should be treated as active and should act on the input data.

Definition at line 179 of file filter_chain.hpp.

◆ activeFiltersMutex

template<typename F >
mutable ::std::mutex cras::FilterChain< F >::activeFiltersMutex
protected

Mutex protecting activeFilters access.

Definition at line 182 of file filter_chain.hpp.

◆ buffer0

template<typename F >
F cras::FilterChain< F >::buffer0
protected

A temporary intermediate buffer.

Definition at line 190 of file filter_chain.hpp.

◆ buffer1

template<typename F >
F cras::FilterChain< F >::buffer1
protected

A temporary intermediate buffer.

Definition at line 193 of file filter_chain.hpp.

◆ disabledFilters

template<typename F >
::std::unordered_set<::std::string> cras::FilterChain< F >::disabledFilters
protected

A set of filters that have been temporarily disabled.

Definition at line 176 of file filter_chain.hpp.

◆ filterFinishedCallback

template<typename F >
FilterFinishedCallback cras::FilterChain< F >::filterFinishedCallback
protected

The optional callback to call when a filter finishes its work.

Definition at line 173 of file filter_chain.hpp.

◆ filterStartCallback

template<typename F >
FilterStartCallback cras::FilterChain< F >::filterStartCallback
protected

The optional callback to call when a filter starts its work.

Definition at line 170 of file filter_chain.hpp.

◆ initialized

template<typename F >
bool cras::FilterChain< F >::initialized {false}
protected

Whether this filter chain has been initialized (gets set by first update() and cleared by clear()).

Definition at line 185 of file filter_chain.hpp.


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


cras_cpp_common
Author(s): Martin Pecka
autogenerated on Sun Jan 14 2024 03:48:14