A Base filter class to provide a standard interface for all filters. More...
#include <filter_base.h>

Public Member Functions | |
| bool | configure (const std::string ¶m_name, ros::NodeHandle node_handle=ros::NodeHandle()) |
| Configure the filter from the parameter server. | |
| bool | configure (XmlRpc::XmlRpcValue &config) |
| The public method to configure a filter from XML. | |
| FilterBase () | |
| Default constructor used by Filter Factories. | |
| const std::string & | getName () |
| Get the name of the filter as a string. | |
| std::string | getType () |
| Get the type of the filter as a string. | |
| virtual bool | update (const T &data_in, T &data_out)=0 |
| Update the filter and return the data seperately This is an inefficient way to do this and can be overridden in the derived class. | |
| virtual | ~FilterBase () |
| Virtual Destructor. | |
Protected Member Functions | |
| virtual bool | configure ()=0 |
| Pure virtual function for the sub class to configure the filter This function must be implemented in the derived class. | |
| bool | getParam (const std::string &name, std::string &value) |
| Get a filter parameter as a string. | |
| bool | getParam (const std::string &name, double &value) |
| Get a filter parameter as a double. | |
| bool | getParam (const std::string &name, int &value) |
| Get a filter parameter as a int. | |
| bool | getParam (const std::string &name, unsigned int &value) |
| Get a filter parameter as an unsigned int. | |
| bool | getParam (const std::string &name, std::vector< double > &value) |
| Get a filter parameter as a std::vector<double> | |
| bool | getParam (const std::string &name, std::vector< std::string > &value) |
| Get a filter parameter as a std::vector<string> | |
| bool | getParam (const std::string &name, XmlRpc::XmlRpcValue &value) |
| Get a filter parameter as a XmlRpcValue. | |
| bool | loadConfiguration (XmlRpc::XmlRpcValue &config) |
Protected Attributes | |
| bool | configured_ |
| Whether the filter has been configured. | |
| std::string | filter_name_ |
| The name of the filter. | |
| std::string | filter_type_ |
| The type of the filter (Used by FilterChain for Factory construction) | |
| string_map_t | params_ |
| Storage of the parsed xml parameters. | |
Private Member Functions | |
| bool | setNameAndType (XmlRpc::XmlRpcValue &config) |
| Set the name and type of the filter from the parameter server. | |
A Base filter class to provide a standard interface for all filters.
Definition at line 50 of file filter_base.h.
| filters::FilterBase< T >::FilterBase | ( | ) | [inline] |
Default constructor used by Filter Factories.
Definition at line 55 of file filter_base.h.
| virtual filters::FilterBase< T >::~FilterBase | ( | ) | [inline, virtual] |
Virtual Destructor.
Definition at line 59 of file filter_base.h.
| bool filters::FilterBase< T >::configure | ( | const std::string & | param_name, |
| ros::NodeHandle | node_handle = ros::NodeHandle() |
||
| ) | [inline] |
Configure the filter from the parameter server.
| The | parameter from which to read the configuration |
| node_handle | The optional node handle, useful if operating in a different namespace. |
Definition at line 65 of file filter_base.h.
| bool filters::FilterBase< T >::configure | ( | XmlRpc::XmlRpcValue & | config | ) | [inline] |
The public method to configure a filter from XML.
| config | The XmlRpcValue from which the filter should be initialized |
Reimplemented in filters::MultiChannelFilterBase< T >.
Definition at line 80 of file filter_base.h.
| virtual bool filters::FilterBase< T >::configure | ( | ) | [protected, pure virtual] |
Pure virtual function for the sub class to configure the filter This function must be implemented in the derived class.
Implemented in filters::MultiChannelFilterBase< T >, filters::MultiChannelTransferFunctionFilter< T >, filters::MultiChannelMedianFilter< T >, filters::MultiChannelMeanFilter< T >, filters::MultiChannelIncrementFilter< T >, filters::MedianFilter< T >, filters::SingleChannelTransferFunctionFilter< T >, filters::MeanFilter< T >, filters::ParamTest< T >, and filters::IncrementFilter< T >.
| const std::string& filters::FilterBase< T >::getName | ( | ) | [inline] |
Get the name of the filter as a string.
Definition at line 106 of file filter_base.h.
| bool filters::FilterBase< T >::getParam | ( | const std::string & | name, |
| std::string & | value | ||
| ) | [inline, protected] |
Get a filter parameter as a string.
| name | The name of the parameter |
| value | The string to set with the value |
Definition at line 121 of file filter_base.h.
| bool filters::FilterBase< T >::getParam | ( | const std::string & | name, |
| double & | value | ||
| ) | [inline, protected] |
Get a filter parameter as a double.
| name | The name of the parameter |
| value | The double to set with the value |
Definition at line 142 of file filter_base.h.
| bool filters::FilterBase< T >::getParam | ( | const std::string & | name, |
| int & | value | ||
| ) | [inline, protected] |
Get a filter parameter as a int.
| name | The name of the parameter |
| value | The int to set with the value |
Definition at line 163 of file filter_base.h.
| bool filters::FilterBase< T >::getParam | ( | const std::string & | name, |
| unsigned int & | value | ||
| ) | [inline, protected] |
Get a filter parameter as an unsigned int.
| name | The name of the parameter |
| value | The int to set with the value |
Definition at line 184 of file filter_base.h.
| bool filters::FilterBase< T >::getParam | ( | const std::string & | name, |
| std::vector< double > & | value | ||
| ) | [inline, protected] |
Get a filter parameter as a std::vector<double>
| name | The name of the parameter |
| value | The std::vector<double> to set with the value |
Definition at line 199 of file filter_base.h.
| bool filters::FilterBase< T >::getParam | ( | const std::string & | name, |
| std::vector< std::string > & | value | ||
| ) | [inline, protected] |
Get a filter parameter as a std::vector<string>
| name | The name of the parameter |
| value | The std::vector<sgring> to set with the value |
Definition at line 233 of file filter_base.h.
| bool filters::FilterBase< T >::getParam | ( | const std::string & | name, |
| XmlRpc::XmlRpcValue & | value | ||
| ) | [inline, protected] |
Get a filter parameter as a XmlRpcValue.
| name | The name of the parameter |
| value | The XmlRpcValue to set with the value |
Definition at line 266 of file filter_base.h.
| std::string filters::FilterBase< T >::getType | ( | ) | [inline] |
Get the type of the filter as a string.
Definition at line 103 of file filter_base.h.
| bool filters::FilterBase< T >::loadConfiguration | ( | XmlRpc::XmlRpcValue & | config | ) | [inline, protected] |
Definition at line 317 of file filter_base.h.
| bool filters::FilterBase< T >::setNameAndType | ( | XmlRpc::XmlRpcValue & | config | ) | [inline, private] |
Set the name and type of the filter from the parameter server.
| param_name | The parameter from which to read |
Definition at line 292 of file filter_base.h.
| virtual bool filters::FilterBase< T >::update | ( | const T & | data_in, |
| T & | data_out | ||
| ) | [pure virtual] |
Update the filter and return the data seperately This is an inefficient way to do this and can be overridden in the derived class.
| data_in | A reference to the data to be input to the filter |
| data_out | A reference to the data output location |
Implemented in filters::MultiChannelFilterBase< T >, filters::MedianFilter< T >, filters::SingleChannelTransferFunctionFilter< T >, filters::MeanFilter< T >, filters::ParamTest< T >, and filters::IncrementFilter< T >.
bool filters::FilterBase< T >::configured_ [protected] |
Whether the filter has been configured.
Definition at line 283 of file filter_base.h.
std::string filters::FilterBase< T >::filter_name_ [protected] |
The name of the filter.
Definition at line 279 of file filter_base.h.
std::string filters::FilterBase< T >::filter_type_ [protected] |
The type of the filter (Used by FilterChain for Factory construction)
Definition at line 281 of file filter_base.h.
string_map_t filters::FilterBase< T >::params_ [protected] |
Storage of the parsed xml parameters.
Definition at line 286 of file filter_base.h.