diff --git a/libraries/Filter/LowPassFilter.cpp b/libraries/Filter/LowPassFilter.cpp index e4f741b93431d..eba8e0d38bf06 100644 --- a/libraries/Filter/LowPassFilter.cpp +++ b/libraries/Filter/LowPassFilter.cpp @@ -1,8 +1,6 @@ // /// @file LowPassFilter.cpp -/// @brief A class to implement a low pass filter without losing precision even for int types -/// the downside being that it's a little slower as it internally uses a float -/// and it consumes an extra 4 bytes of memory to hold the constant gain +/// @brief A class to implement a low pass filter #ifndef HAL_DEBUG_BUILD #define AP_INLINE_VECTOR_OPS @@ -12,134 +10,134 @@ #include //////////////////////////////////////////////////////////////////////////////////////////// -// DigitalLPF +// DigitalLPF, base class //////////////////////////////////////////////////////////////////////////////////////////// template DigitalLPF::DigitalLPF() { // built in initialization - _output = T(); + output = T(); } // add a new raw value to the filter, retrieve the filtered result template -T DigitalLPF::apply(const T &sample, float cutoff_freq, float dt) { - if (is_negative(cutoff_freq) || is_negative(dt)) { - INTERNAL_ERROR(AP_InternalError::error_t::invalid_arg_or_result); - _output = sample; - return _output; - } - if (is_zero(cutoff_freq)) { - _output = sample; - return _output; - } - if (is_zero(dt)) { - return _output; - } - float rc = 1.0f/(M_2PI*cutoff_freq); - alpha = constrain_float(dt/(dt+rc), 0.0f, 1.0f); - _output += (sample - _output) * alpha; - if (!initialised) { - initialised = true; - _output = sample; - } - return _output; -} - -template -T DigitalLPF::apply(const T &sample) { - _output += (sample - _output) * alpha; +T DigitalLPF::_apply(const T &sample, const float &alpha) { + output += (sample - output) * alpha; if (!initialised) { initialised = true; - _output = sample; - } - return _output; -} - -template -void DigitalLPF::compute_alpha(float sample_freq, float cutoff_freq) { - if (sample_freq <= 0) { - alpha = 1; - } else { - alpha = calc_lowpass_alpha_dt(1.0/sample_freq, cutoff_freq); + output = sample; } + return output; } // get latest filtered value from filter (equal to the value returned by latest call to apply method) template const T &DigitalLPF::get() const { - return _output; + return output; } +// Reset filter to given value template -void DigitalLPF::reset(T value) { - _output = value; +void DigitalLPF::reset(const T &value) { + output = value; initialised = true; } - -//////////////////////////////////////////////////////////////////////////////////////////// -// LowPassFilter -//////////////////////////////////////////////////////////////////////////////////////////// -// constructors +// Set reset flag such that the filter will be reset to the next value applied template -LowPassFilter::LowPassFilter() : - _cutoff_freq(0.0f) {} +void DigitalLPF::reset() { + initialised = false; +} -template -LowPassFilter::LowPassFilter(float cutoff_freq) : - _cutoff_freq(cutoff_freq) {} +template class DigitalLPF; +template class DigitalLPF; +template class DigitalLPF; + +//////////////////////////////////////////////////////////////////////////////////////////// +// Low pass filter with constant time step +//////////////////////////////////////////////////////////////////////////////////////////// +// constructor template -LowPassFilter::LowPassFilter(float sample_freq, float cutoff_freq) +LowPassFilterConstDt::LowPassFilterConstDt(const float &sample_freq, const float &new_cutoff_freq) { - set_cutoff_frequency(sample_freq, cutoff_freq); + set_cutoff_frequency(sample_freq, new_cutoff_freq); } // change parameters template -void LowPassFilter::set_cutoff_frequency(float cutoff_freq) { - _cutoff_freq = cutoff_freq; +void LowPassFilterConstDt::set_cutoff_frequency(const float &sample_freq, const float &new_cutoff_freq) { + cutoff_freq = new_cutoff_freq; + + if (sample_freq <= 0) { + alpha = 1; + } else { + alpha = calc_lowpass_alpha_dt(1.0/sample_freq, cutoff_freq); + } } +// return the cutoff frequency template -void LowPassFilter::set_cutoff_frequency(float sample_freq, float cutoff_freq) { - _cutoff_freq = cutoff_freq; - _filter.compute_alpha(sample_freq, cutoff_freq); +float LowPassFilterConstDt::get_cutoff_freq(void) const { + return cutoff_freq; } -// return the cutoff frequency +// add a new raw value to the filter, retrieve the filtered result template -float LowPassFilter::get_cutoff_freq(void) const { - return _cutoff_freq; +T LowPassFilterConstDt::apply(const T &sample) { + return this->_apply(sample, alpha); } +template class LowPassFilterConstDt; +template class LowPassFilterConstDt; +template class LowPassFilterConstDt; + +//////////////////////////////////////////////////////////////////////////////////////////// +// Low pass filter with variable time step +//////////////////////////////////////////////////////////////////////////////////////////// + template -T LowPassFilter::apply(T sample, float dt) { - return _filter.apply(sample, _cutoff_freq, dt); +LowPassFilter::LowPassFilter(const float &new_cutoff_freq) +{ + set_cutoff_frequency(new_cutoff_freq); } +// change parameters template -T LowPassFilter::apply(T sample) { - return _filter.apply(sample); +void LowPassFilter::set_cutoff_frequency(const float &new_cutoff_freq) { + cutoff_freq = new_cutoff_freq; } +// return the cutoff frequency template -const T &LowPassFilter::get() const { - return _filter.get(); +float LowPassFilter::get_cutoff_freq() const { + return cutoff_freq; } +// add a new raw value to the filter, retrieve the filtered result template -void LowPassFilter::reset(T value) { - _filter.reset(value); +T LowPassFilter::apply(const T &sample, const float &dt) { + if (is_negative(cutoff_freq) || is_negative(dt)) { + INTERNAL_ERROR(AP_InternalError::error_t::invalid_arg_or_result); + this->reset(sample); + return this->get(); + } + if (is_zero(cutoff_freq)) { + this->reset(sample); + return this->get(); + } + if (is_zero(dt)) { + return this->get(); + } + const float rc = 1.0f/(M_2PI*cutoff_freq); + const float alpha = constrain_float(dt/(dt+rc), 0.0f, 1.0f); + return this->_apply(sample, alpha); } /* * Make an instances * Otherwise we have to move the constructor implementations to the header file :P */ -template class LowPassFilter; -template class LowPassFilter; template class LowPassFilter; template class LowPassFilter; template class LowPassFilter; diff --git a/libraries/Filter/LowPassFilter.h b/libraries/Filter/LowPassFilter.h index 497d0ddf976e7..3106bc14aeabf 100644 --- a/libraries/Filter/LowPassFilter.h +++ b/libraries/Filter/LowPassFilter.h @@ -15,14 +15,12 @@ // /// @file LowPassFilter.h -/// @brief A class to implement a low pass filter without losing precision even for int types -/// the downside being that it's a little slower as it internally uses a float -/// and it consumes an extra 4 bytes of memory to hold the constant gain +/// @brief A class to implement a low pass filter. /* - Note that this filter can be used in 2 ways: + Two classes are provided: - 1) providing dt on every sample, and calling apply like this: + LowPassFilter: providing dt on every sample, and calling apply like this: // call once filter.set_cutoff_frequency(frequency_hz); @@ -30,7 +28,7 @@ // then on each sample output = filter.apply(sample, dt); - 2) providing a sample freq and cutoff_freq once at start + LowPassFilterConstDt: providing a sample freq and cutoff_freq once at start // call once filter.set_cutoff_frequency(sample_freq, frequency_hz); @@ -45,79 +43,89 @@ #pragma once #include -#include "FilterClass.h" // DigitalLPF implements the filter math template class DigitalLPF { public: + + // constructor DigitalLPF(); - // add a new raw value to the filter, retrieve the filtered result - T apply(const T &sample, float cutoff_freq, float dt); - T apply(const T &sample); CLASS_NO_COPY(DigitalLPF); - void compute_alpha(float sample_freq, float cutoff_freq); - // get latest filtered value from filter (equal to the value returned by latest call to apply method) const T &get() const; - void reset(T value); - void reset() { - initialised = false; - } + + // Reset filter to given value + void reset(const T &value); + + // Set reset flag such that the filter will be reset to the next value applied + void reset(); + +protected: + // add a new raw value to the filter, retrieve the filtered result + T _apply(const T &sample, const float &alpha); private: - T _output; - float alpha = 1.0f; + T output; bool initialised; }; -// LPF base class +// Low pass filter with constant time step template -class LowPassFilter { +class LowPassFilterConstDt : public DigitalLPF { public: - LowPassFilter(); - LowPassFilter(float cutoff_freq); - LowPassFilter(float sample_freq, float cutoff_freq); - CLASS_NO_COPY(LowPassFilter); + // constructors + LowPassFilterConstDt() {}; + LowPassFilterConstDt(const float &sample_freq, const float &cutoff_freq); + + CLASS_NO_COPY(LowPassFilterConstDt); // change parameters - void set_cutoff_frequency(float cutoff_freq); - void set_cutoff_frequency(float sample_freq, float cutoff_freq); + void set_cutoff_frequency(const float &sample_freq, const float &cutoff_freq); // return the cutoff frequency - float get_cutoff_freq(void) const; - T apply(T sample, float dt); - T apply(T sample); - const T &get() const; - void reset(T value); - void reset(void) { _filter.reset(); } + float get_cutoff_freq() const; -protected: - float _cutoff_freq; + // add a new raw value to the filter, retrieve the filtered result + T apply(const T &sample); private: - DigitalLPF _filter; + float cutoff_freq; + float alpha; }; -// Uncomment this, if you decide to remove the instantiations in the implementation file -/* -template -LowPassFilter::LowPassFilter() : _cutoff_freq(0.0f) { - -} -// constructor +typedef LowPassFilterConstDt LowPassFilterConstDtFloat; +typedef LowPassFilterConstDt LowPassFilterConstDtVector2f; +typedef LowPassFilterConstDt LowPassFilterConstDtVector3f; + +// Low pass filter with variable time step template -LowPassFilter::LowPassFilter(float cutoff_freq) : _cutoff_freq(cutoff_freq) { - -} -*/ +class LowPassFilter : public DigitalLPF { +public: + + // constructors + LowPassFilter() {}; + LowPassFilter(const float &cutoff_freq); + + CLASS_NO_COPY(LowPassFilter); + + // change parameters + void set_cutoff_frequency(const float &cutoff_freq); + + // return the cutoff frequency + float get_cutoff_freq() const; + + // add a new raw value to the filter, retrieve the filtered result + T apply(const T &sample, const float &dt); + +private: + float cutoff_freq; +}; // typedefs for compatibility -typedef LowPassFilter LowPassFilterInt; -typedef LowPassFilter LowPassFilterLong; typedef LowPassFilter LowPassFilterFloat; typedef LowPassFilter LowPassFilterVector2f; typedef LowPassFilter LowPassFilterVector3f;