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. 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 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. More... | |
virtual | ~FilterBase () |
Virtual Destructor. More... | |
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. More... | |
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) |
Protected Attributes | |
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... | |
Private Member Functions | |
bool | setNameAndType (XmlRpc::XmlRpcValue &config) |
Set the name and type of the filter from the parameter server. More... | |
A Base filter class to provide a standard interface for all filters.
Definition at line 50 of file filter_base.h.
|
inline |
Default constructor used by Filter Factories.
Definition at line 55 of file filter_base.h.
|
inlinevirtual |
Virtual Destructor.
Definition at line 59 of file filter_base.h.
|
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.
|
inline |
The public method to configure a filter from XML.
config | The XmlRpcValue from which the filter should be initialized |
Definition at line 80 of file filter_base.h.
|
protectedpure 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 >.
|
inline |
Get the name of the filter as a string.
Definition at line 106 of file filter_base.h.
|
inlineprotected |
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.
|
inlineprotected |
Get a filter parameter as a boolean.
name | The name of the parameter |
value | The boolean to set with the value |
Definition at line 142 of file filter_base.h.
|
inlineprotected |
Get a filter parameter as a double.
name | The name of the parameter |
value | The double to set with the value |
Definition at line 163 of file filter_base.h.
|
inlineprotected |
Get a filter parameter as a int.
name | The name of the parameter |
value | The int to set with the value |
Definition at line 184 of file filter_base.h.
|
inlineprotected |
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 205 of file filter_base.h.
|
inlineprotected |
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 220 of file filter_base.h.
|
inlineprotected |
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 254 of file filter_base.h.
|
inlineprotected |
Get a filter parameter as a XmlRpcValue.
name | The name of the parameter |
value | The XmlRpcValue to set with the value |
Definition at line 287 of file filter_base.h.
|
inline |
Get the type of the filter as a string.
Definition at line 103 of file filter_base.h.
|
inlineprotected |
Definition at line 338 of file filter_base.h.
|
inlineprivate |
Set the name and type of the filter from the parameter server.
param_name | The parameter from which to read |
Definition at line 313 of file filter_base.h.
|
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 >.
|
protected |
Whether the filter has been configured.
Definition at line 304 of file filter_base.h.
|
protected |
The name of the filter.
Definition at line 300 of file filter_base.h.
|
protected |
The type of the filter (Used by FilterChain for Factory construction)
Definition at line 302 of file filter_base.h.
|
protected |
Storage of the parsed xml parameters.
Definition at line 307 of file filter_base.h.