LocalGuidance
A library that generates velocity references to follow a path.
robot_utils::FilterButter Class Reference

FilterButter. More...

#include <FilterButter.hpp>

Public Member Functions

 FilterButter (int dim, int order)
 
virtual ~FilterButter ()
 Destructor. More...
 
bool initLowpass (double fs, double fc)
 
bool deactivate ()
 
Eigen::Matrix< double, Eigen::Dynamic, 1 > filterData (const Eigen::Matrix< double, Eigen::Dynamic, 1 > &actValues)
 

Public Attributes

 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
 

Private Attributes

int dim_
 
int order_
 
bool isInit_
 
bool firstCall_
 
Eigen::Matrix< double, 1, Eigen::Dynamic > aCoeff_
 
Eigen::Matrix< double, 1, Eigen::Dynamic > bCoeff_
 
Eigen::Matrix< double, Eigen::Dynamic, Eigen::Dynamic > InputValues_
 
Eigen::Matrix< double, Eigen::Dynamic, Eigen::Dynamic > OutputValues_
 

Detailed Description

FilterButter.

Approximate time delays for various low-pass Butterworth digital filters Order Delay Order Delay Order Delay 2 0.225/fc 7 0.715/fc 12 1.219/fc 3 0.318/fc 8 0.816/fc 14 1.421/fc 4 0.416/fc 9 0.917/fc 16 1.624/fc 5 0.515/fc 10 1.017/fc 18 1.826/fc 6 0.615/fc 11 1.118/fc 20 2.029/fc Note that cut-off frequency, fc, should be entered as Hertz. The measurement unit for the time delay is seconds. For example, a low-pass, forward-filtered signal with fc=4Hz and order N=4 will introduce a time delay of 0.416/(4 Hz)=0.104 s.

Reference: {Manal2007678, title = "A general solution for the time delay introduced by a low-pass Butterworth digital filter: An application to musculoskeletal modeling", journal = "Journal of Biomechanics", volume = "40", number = "3", pages = "678 - 681", year = "2007", note = "", issn = "0021-9290", doi = "10.1016/j.jbiomech.2006.02.001", url = "http://www.sciencedirect.com/science/article/pii/S0021929006000480", author = "Kurt Manal and William Rose", keywords = "Signal", keywords = "Processing", keywords = "Smoothing", keywords = "Electromechanical delay", keywords = "Group delay" }

Constructor & Destructor Documentation

robot_utils::FilterButter::FilterButter ( int  dim,
int  order 
)

Constructor

Parameters
dimVector dimension
orderLength of the filter
virtual robot_utils::FilterButter::~FilterButter ( )
virtual

Destructor.

Member Function Documentation

bool robot_utils::FilterButter::deactivate ( )

Deactivate the filter,

Returns
Eigen::Matrix<double,Eigen::Dynamic,1> robot_utils::FilterButter::filterData ( const Eigen::Matrix< double, Eigen::Dynamic, 1 > &  actValues)

adds the new value as measured point and return the next filter value

Parameters
actValuesactual measurement
Returns
filtered value
bool robot_utils::FilterButter::initLowpass ( double  fs,
double  fc 
)

Initialize the lowpass filter

Parameters
fsSampling frequency [rad/s] or [Hz]
fccut-off frequency [rad/s] or [Hz]
Returns
true if successful

Member Data Documentation

Eigen::Matrix<double,1,Eigen::Dynamic> robot_utils::FilterButter::aCoeff_
private
Eigen::Matrix<double,1,Eigen::Dynamic> robot_utils::FilterButter::bCoeff_
private
int robot_utils::FilterButter::dim_
private
robot_utils::FilterButter::EIGEN_MAKE_ALIGNED_OPERATOR_NEW
bool robot_utils::FilterButter::firstCall_
private
Eigen::Matrix<double,Eigen::Dynamic,Eigen::Dynamic> robot_utils::FilterButter::InputValues_
private
bool robot_utils::FilterButter::isInit_
private
int robot_utils::FilterButter::order_
private
Eigen::Matrix<double,Eigen::Dynamic,Eigen::Dynamic> robot_utils::FilterButter::OutputValues_
private

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