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

One-dimensional digital filter class. More...

#include <transfer_function.h>

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

Public Member Functions

virtual bool configure ()
 Configure the filter with the correct number of channels and params. More...
 
 SingleChannelTransferFunctionFilter ()
 Construct the filter. More...
 
virtual bool update (const T &data_in, T &data_out)
 Update the filter and return the data seperately. More...
 
 ~SingleChannelTransferFunctionFilter ()
 Destructor to clean up. 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

std::vector< double > a_
 
std::vector< double > b_
 
boost::scoped_ptr< RealtimeCircularBuffer< T > > input_buffer_
 
boost::scoped_ptr< RealtimeCircularBuffer< T > > output_buffer_
 
temp_
 
- 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::SingleChannelTransferFunctionFilter< T >

One-dimensional digital filter class.

This class calculates the output for $N$ one-dimensional digital filters. The filter is described by vectors $a$ and $b$ and implemented using the standard difference equation:

\begin{eqnarray*} a[0]*y[n] = b[0]*x[n] &+& b[1]*x[n-1]+ ... + b[n_b]*x[n-n_b]\\ &-& a[1]*y[n-1]- ... - a[n_a]*y[n-n_a] \end{eqnarray*}


If $a[0]$ is not equal to 1, the coefficients are normalized by $a[0]$.

Example xml config:

<filter type="TransferFunctionFilter" name="filter_name">
<params a="1.0 0.5" b="0.2 0.2">
</filter>

Definition at line 74 of file transfer_function.h.

Constructor & Destructor Documentation

Construct the filter.

Definition at line 113 of file transfer_function.h.

Destructor to clean up.

Definition at line 118 of file transfer_function.h.

Member Function Documentation

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

Configure the filter with the correct number of channels and params.

Parameters
number_of_channelsThe number of inputs filtered.
configThe xml that is parsed to configure the filter.
Todo:
check length
Todo:
check length

Implements filters::FilterBase< T >.

Definition at line 123 of file transfer_function.h.

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

Update the filter and return the data seperately.

Parameters
data_invector<T> with number_of_channels elements
data_outvector<T> with number_of_channels elements

Implements filters::FilterBase< T >.

Definition at line 170 of file transfer_function.h.

Member Data Documentation

template<typename T>
std::vector<double> filters::SingleChannelTransferFunctionFilter< T >::a_
protected

Definition at line 107 of file transfer_function.h.

template<typename T>
std::vector<double> filters::SingleChannelTransferFunctionFilter< T >::b_
protected

Definition at line 108 of file transfer_function.h.

template<typename T>
boost::scoped_ptr<RealtimeCircularBuffer<T > > filters::SingleChannelTransferFunctionFilter< T >::input_buffer_
protected

Definition at line 102 of file transfer_function.h.

template<typename T>
boost::scoped_ptr<RealtimeCircularBuffer<T > > filters::SingleChannelTransferFunctionFilter< T >::output_buffer_
protected

Definition at line 103 of file transfer_function.h.

template<typename T>
T filters::SingleChannelTransferFunctionFilter< T >::temp_
protected

Definition at line 105 of file transfer_function.h.


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


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