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 (std::string param_name, ros::NodeHandle node=ros::NodeHandle()) | 
| Configure the filter chain from a configuration stored on the parameter server.  More... | |
| bool | configure (XmlRpc::XmlRpcValue &config, const std::string &filter_ns) | 
| Configure the filter chain This will call configure on all filters which have been added.  More... | |
| FilterChain (std::string data_type) | |
| Create the filter chain object.  More... | |
| bool | update (const T &data_in, T &data_out) | 
| process data through each of the filters added sequentially  More... | |
| ~FilterChain () | |
| Private Attributes | |
| T | buffer0_ | 
| ! A temporary intermediate buffer  More... | |
| T | buffer1_ | 
| ! A temporary intermediate buffer  More... | |
| bool | configured_ | 
| ! whether the system is configured  More... | |
| pluginlib::ClassLoader< filters::FilterBase< T > > | loader_ | 
| std::vector< boost::shared_ptr< filters::FilterBase< T > > > | reference_pointers_ | 
| ! A vector of pointers to currently constructed filters  More... | |
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 47 of file filter_chain.h.
| 
 | inline | 
Create the filter chain object.
Definition at line 53 of file filter_chain.h.
| 
 | inline | 
Definition at line 64 of file filter_chain.h.
| 
 | inline | 
Clear all filters from this chain.
Definition at line 130 of file filter_chain.h.
| 
 | inline | 
Configure the filter chain from a configuration stored on the parameter server.
| 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 74 of file filter_chain.h.
| 
 | inline | 
Configure the filter chain This will call configure on all filters which have been added.
Definition at line 142 of file filter_chain.h.
| 
 | inline | 
process data through each of the filters added sequentially
Definition at line 92 of file filter_chain.h.
| 
 | private | 
! A temporary intermediate buffer
Definition at line 264 of file filter_chain.h.
| 
 | private | 
! A temporary intermediate buffer
Definition at line 265 of file filter_chain.h.
| 
 | private | 
! whether the system is configured
Definition at line 266 of file filter_chain.h.
| 
 | private | 
Definition at line 50 of file filter_chain.h.
| 
 | private | 
! A vector of pointers to currently constructed filters
Definition at line 258 of file filter_chain.h.