Public Member Functions | Private Attributes | List of all members
filters::MultiChannelFilterChain< T > Class Template Reference

A class which will construct and sequentially call Filters according to xml This is the primary way in which users are expected to interact with Filters. More...

#include <filter_chain.h>

Public Member Functions

bool clear ()
 Clear all filters from this chain. More...
 
bool configure (unsigned int size, std::string param_name, ros::NodeHandle node=ros::NodeHandle())
 Configure the filter chain from a configuration stored on the parameter server. More...
 
bool configure (unsigned int size, XmlRpc::XmlRpcValue &config)
 Configure the filter chain This will call configure on all filters which have been added as well as allocate the buffers. More...
 
std::vector< std::shared_ptr< filters::MultiChannelFilterBase< T > > > getFilters () const
 Return a copy of the vector of loaded filters (the pointers point to the actual filters used by the chain). More...
 
 MultiChannelFilterChain (std::string data_type)
 Create the filter chain object. More...
 
bool update (const std::vector< T > &data_in, std::vector< T > &data_out)
 process data through each of the filters added sequentially More...
 
 ~MultiChannelFilterChain ()
 

Private Attributes

std::vector< T > buffer0_
 ! A temporary intermediate buffer More...
 
std::vector< T > buffer1_
 ! A temporary intermediate buffer More...
 
bool configured_
 ! whether the system is configured More...
 
pluginlib::ClassLoader< filters::MultiChannelFilterBase< T > > loader_
 
std::vector< std::shared_ptr< filters::MultiChannelFilterBase< T > > > reference_pointers_
 ! A vector of pointers to currently constructed filters More...
 

Detailed Description

template<typename T>
class filters::MultiChannelFilterChain< T >

A class which will construct and sequentially call Filters according to xml This is the primary way in which users are expected to interact with Filters.

Definition at line 275 of file filter_chain.h.

Constructor & Destructor Documentation

◆ MultiChannelFilterChain()

template<typename T>
filters::MultiChannelFilterChain< T >::MultiChannelFilterChain ( std::string  data_type)
inline

Create the filter chain object.

Definition at line 281 of file filter_chain.h.

◆ ~MultiChannelFilterChain()

template<typename T>
filters::MultiChannelFilterChain< T >::~MultiChannelFilterChain ( )
inline

Definition at line 356 of file filter_chain.h.

Member Function Documentation

◆ clear()

template<typename T>
bool filters::MultiChannelFilterChain< T >::clear ( )
inline

Clear all filters from this chain.

Definition at line 363 of file filter_chain.h.

◆ configure() [1/2]

template<typename T>
bool filters::MultiChannelFilterChain< T >::configure ( unsigned int  size,
std::string  param_name,
ros::NodeHandle  node = ros::NodeHandle() 
)
inline

Configure the filter chain from a configuration stored on the parameter server.

Parameters
param_nameThe name of the filter chain to load
nodeThe node handle to use if a different namespace is required

Definition at line 296 of file filter_chain.h.

◆ configure() [2/2]

template<typename T>
bool filters::MultiChannelFilterChain< T >::configure ( unsigned int  size,
XmlRpc::XmlRpcValue config 
)
inline

Configure the filter chain This will call configure on all filters which have been added as well as allocate the buffers.

Definition at line 377 of file filter_chain.h.

◆ getFilters()

template<typename T>
std::vector<std::shared_ptr<filters::MultiChannelFilterBase<T> > > filters::MultiChannelFilterChain< T >::getFilters ( ) const
inline

Return a copy of the vector of loaded filters (the pointers point to the actual filters used by the chain).

Definition at line 504 of file filter_chain.h.

◆ update()

template<typename T>
bool filters::MultiChannelFilterChain< T >::update ( const std::vector< T > &  data_in,
std::vector< T > &  data_out 
)
inline

process data through each of the filters added sequentially

Definition at line 317 of file filter_chain.h.

Member Data Documentation

◆ buffer0_

template<typename T>
std::vector<T> filters::MultiChannelFilterChain< T >::buffer0_
private

! A temporary intermediate buffer

Definition at line 513 of file filter_chain.h.

◆ buffer1_

template<typename T>
std::vector<T> filters::MultiChannelFilterChain< T >::buffer1_
private

! A temporary intermediate buffer

Definition at line 514 of file filter_chain.h.

◆ configured_

template<typename T>
bool filters::MultiChannelFilterChain< T >::configured_
private

! whether the system is configured

Definition at line 515 of file filter_chain.h.

◆ loader_

Definition at line 278 of file filter_chain.h.

◆ reference_pointers_

template<typename T>
std::vector<std::shared_ptr<filters::MultiChannelFilterBase<T> > > filters::MultiChannelFilterChain< T >::reference_pointers_
private

! A vector of pointers to currently constructed filters

Definition at line 511 of file filter_chain.h.


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


filters
Author(s):
autogenerated on Wed May 11 2022 02:40:46