mirror of https://github.com/ArduPilot/ardupilot
Filter: added new constructor for 1p filter
allow both sample rate and cutoff to be specified in constructor
This commit is contained in:
parent
7220dc15f9
commit
b165e025d9
|
@ -61,14 +61,20 @@ void DigitalLPF<T>::reset(T value) {
|
|||
////////////////////////////////////////////////////////////////////////////////////////////
|
||||
// LowPassFilter
|
||||
////////////////////////////////////////////////////////////////////////////////////////////
|
||||
|
||||
// constructors
|
||||
template <class T>
|
||||
LowPassFilter<T>::LowPassFilter() : _cutoff_freq(0.0f) {
|
||||
|
||||
}
|
||||
// constructor
|
||||
LowPassFilter<T>::LowPassFilter() :
|
||||
_cutoff_freq(0.0f) {}
|
||||
|
||||
template <class T>
|
||||
LowPassFilter<T>::LowPassFilter(float cutoff_freq) : _cutoff_freq(cutoff_freq) {
|
||||
|
||||
LowPassFilter<T>::LowPassFilter(float cutoff_freq) :
|
||||
_cutoff_freq(cutoff_freq) {}
|
||||
|
||||
template <class T>
|
||||
LowPassFilter<T>::LowPassFilter(float sample_freq, float cutoff_freq)
|
||||
{
|
||||
set_cutoff_frequency(sample_freq, cutoff_freq);
|
||||
}
|
||||
|
||||
// change parameters
|
||||
|
|
|
@ -73,6 +73,7 @@ class LowPassFilter {
|
|||
public:
|
||||
LowPassFilter();
|
||||
LowPassFilter(float cutoff_freq);
|
||||
LowPassFilter(float sample_freq, float cutoff_freq);
|
||||
|
||||
// change parameters
|
||||
void set_cutoff_frequency(float cutoff_freq);
|
||||
|
|
Loading…
Reference in New Issue