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

A median filter which works on arrays. More...

#include <median.h>

Inheritance diagram for filters::MultiChannelMedianFilter< T >:
Inheritance graph
[legend]

Public Member Functions

virtual bool configure ()
 Pure virtual function for the sub class to configure the filter This function must be implemented in the derived class. More...
 
 MultiChannelMedianFilter ()
 Construct the filter with the expected width and height. More...
 
virtual bool update (const std::vector< T > &data_in, std::vector< T > &data_out)
 Update the filter and return the data seperately. More...
 
 ~MultiChannelMedianFilter ()
 Destructor to clean up. More...
 
- Public Member Functions inherited from filters::MultiChannelFilterBase< T >
bool configure (unsigned int number_of_channels, const std::string &param_name, ros::NodeHandle node_handle=ros::NodeHandle())
 Configure the filter from the parameter server. More...
 
bool configure (unsigned int number_of_channels, XmlRpc::XmlRpcValue &config)
 The public method to configure a filter from XML. More...
 
bool configure (XmlRpc::XmlRpcValue &config)
 A method to hide the base class method and warn if improperly called. More...
 
 MultiChannelFilterBase ()
 
virtual bool update (const T &data_in, T &data_out)
 Update the filter and return the data seperately This is an inefficient way to do this and can be overridden in the derived class. More...
 
- Public Member Functions inherited from filters::FilterBase< T >
bool configure (const std::string &param_name, ros::NodeHandle node_handle=ros::NodeHandle())
 Configure the filter from the parameter server. More...
 
bool configure (XmlRpc::XmlRpcValue &config)
 The public method to configure a filter from XML. More...
 
 FilterBase ()
 Default constructor used by Filter Factories. More...
 
const std::string & getName ()
 Get the name of the filter as a string. More...
 
std::string getType ()
 Get the type of the filter as a string. More...
 
virtual ~FilterBase ()
 Virtual Destructor. More...
 

Protected Attributes

boost::scoped_ptr< RealtimeCircularBuffer< std::vector< T > > > data_storage_
 Storage for data between updates. More...
 
uint32_t number_of_observations_
 Number of observations over which to filter. More...
 
std::vector< T > temp
 
std::vector< T > temp_storage_
 Preallocated storage for the list to sort. More...
 
- Protected Attributes inherited from filters::MultiChannelFilterBase< T >
unsigned int number_of_channels_
 How many parallel inputs for which the filter is to be configured. More...
 
- Protected Attributes inherited from filters::FilterBase< T >
bool configured_
 Whether the filter has been configured. More...
 
std::string filter_name_
 The name of the filter. More...
 
std::string filter_type_
 The type of the filter (Used by FilterChain for Factory construction) More...
 
string_map_t params_
 Storage of the parsed xml parameters. More...
 

Additional Inherited Members

- Protected Member Functions inherited from filters::FilterBase< T >
bool getParam (const std::string &name, std::string &value)
 Get a filter parameter as a string. More...
 
bool getParam (const std::string &name, bool &value)
 Get a filter parameter as a boolean. More...
 
bool getParam (const std::string &name, double &value)
 Get a filter parameter as a double. More...
 
bool getParam (const std::string &name, int &value)
 Get a filter parameter as a int. More...
 
bool getParam (const std::string &name, unsigned int &value)
 Get a filter parameter as an unsigned int. More...
 
bool getParam (const std::string &name, std::vector< double > &value)
 Get a filter parameter as a std::vector<double> More...
 
bool getParam (const std::string &name, std::vector< std::string > &value)
 Get a filter parameter as a std::vector<string> More...
 
bool getParam (const std::string &name, XmlRpc::XmlRpcValue &value)
 Get a filter parameter as a XmlRpcValue. More...
 
bool loadConfiguration (XmlRpc::XmlRpcValue &config)
 

Detailed Description

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

A median filter which works on arrays.

Definition at line 181 of file median.h.

Constructor & Destructor Documentation

Construct the filter with the expected width and height.

Definition at line 211 of file median.h.

Destructor to clean up.

Definition at line 218 of file median.h.

Member Function Documentation

template<typename T >
bool filters::MultiChannelMedianFilter< T >::configure ( )
virtual

Pure virtual function for the sub class to configure the filter This function must be implemented in the derived class.

Implements filters::MultiChannelFilterBase< T >.

Definition at line 224 of file median.h.

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

Update the filter and return the data seperately.

Parameters
data_indouble array with length width
data_outdouble array with length width

Implements filters::MultiChannelFilterBase< T >.

Definition at line 242 of file median.h.

Member Data Documentation

template<typename T>
boost::scoped_ptr<RealtimeCircularBuffer<std::vector<T> > > filters::MultiChannelMedianFilter< T >::data_storage_
protected

Storage for data between updates.

Definition at line 201 of file median.h.

template<typename T>
uint32_t filters::MultiChannelMedianFilter< T >::number_of_observations_
protected

Number of observations over which to filter.

Definition at line 206 of file median.h.

template<typename T>
std::vector<T> filters::MultiChannelMedianFilter< T >::temp
protected

Definition at line 203 of file median.h.

template<typename T>
std::vector<T> filters::MultiChannelMedianFilter< T >::temp_storage_
protected

Preallocated storage for the list to sort.

Definition at line 200 of file median.h.


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


filters
Author(s):
autogenerated on Mon Jun 10 2019 13:15:08