#include <filter_base.h>
Public Member Functions | |
bool | configure (unsigned int number_of_channels, const std::string ¶m_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... | |
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... | |
MultiChannelFilterBase () | |
virtual bool | update (const std::vector< T > &data_in, std::vector< T > &data_out)=0 |
Update the filter and return the data seperately. More... | |
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 ¶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 | ~FilterBase () |
Virtual Destructor. More... | |
Protected Attributes | |
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) |
Definition at line 378 of file filter_base.h.
|
inline |
Definition at line 381 of file filter_base.h.
|
inline |
Configure the filter from the parameter server.
number_of_channels | How many parallel channels the filter will process |
The | parameter from which to read the configuration |
node_handle | The optional node handle, useful if operating in a different namespace. |
Definition at line 388 of file filter_base.h.
|
inline |
The public method to configure a filter from XML.
number_of_channels | How many parallel channels the filter will process |
config | The XmlRpcValue to load the configuration from |
Definition at line 405 of file filter_base.h.
|
inline |
A method to hide the base class method and warn if improperly called.
Definition at line 425 of file filter_base.h.
|
pure virtual |
Pure virtual function for the sub class to configure the filter This function must be implemented in the derived class.
Implements filters::FilterBase< T >.
Implemented in filters::MultiChannelTransferFunctionFilter< T >, filters::MultiChannelMedianFilter< T >, filters::MultiChannelMeanFilter< T >, and filters::MultiChannelIncrementFilter< T >.
|
pure virtual |
Update the filter and return the data seperately.
data_in | A reference to the data to be input to the filter |
data_out | A reference to the data output location This funciton must be implemented in the derived class. |
Implemented in filters::MultiChannelTransferFunctionFilter< T >, filters::MultiChannelMedianFilter< T >, filters::MultiChannelMeanFilter< T >, and filters::MultiChannelIncrementFilter< T >.
|
inlinevirtual |
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 |
Implements filters::FilterBase< T >.
Definition at line 441 of file filter_base.h.
|
protected |
How many parallel inputs for which the filter is to be configured.
Definition at line 454 of file filter_base.h.