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>

List of all members.

Public Member Functions

bool clear ()
 Clear all filters from this chain.
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.
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.
 MultiChannelFilterChain (std::string data_type)
 Create the filter chain object.
bool update (const std::vector< T > &data_in, std::vector< T > &data_out)
 process data through each of the filters added sequentially
 ~MultiChannelFilterChain ()

Private Attributes

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

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 269 of file filter_chain.h.


Constructor & Destructor Documentation

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

Create the filter chain object.

Definition at line 275 of file filter_chain.h.

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

Definition at line 350 of file filter_chain.h.


Member Function Documentation

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

Clear all filters from this chain.

Definition at line 357 of file filter_chain.h.

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 371 of file filter_chain.h.

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_name The name of the filter chain to load
node The node handle to use if a different namespace is required

Definition at line 290 of file filter_chain.h.

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 311 of file filter_chain.h.


Member Data Documentation

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

! A temporary intermediate buffer

Definition at line 496 of file filter_chain.h.

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

! A temporary intermediate buffer

Definition at line 497 of file filter_chain.h.

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

! whether the system is configured

Definition at line 498 of file filter_chain.h.

template<typename T>
pluginlib::ClassLoader<filters::MultiChannelFilterBase<T> > filters::MultiChannelFilterChain< T >::loader_ [private]

Definition at line 272 of file filter_chain.h.

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

! A vector of pointers to currently constructed filters

Definition at line 490 of file filter_chain.h.


The documentation for this class was generated from the following file:
 All Classes Namespaces Files Functions Variables Typedefs Defines


filters
Author(s): Tully Foote/tfoote@willowgarage.com
autogenerated on Fri Jan 11 09:33:18 2013