Browse Source

Filter: add dt<0 check to LPF

master
Jonathan Challinger 10 years ago committed by Randy Mackay
parent
commit
f20a91ec95
  1. 2
      libraries/Filter/LowPassFilter.h

2
libraries/Filter/LowPassFilter.h

@ -42,7 +42,7 @@ public:
// add a new raw value to the filter, retrieve the filtered result // add a new raw value to the filter, retrieve the filtered result
float apply(float sample, float cutoff_freq, float dt) { float apply(float sample, float cutoff_freq, float dt) {
if (cutoff_freq <= 0.0f) { if (cutoff_freq <= 0.0f || dt < 0.0f) {
_output = sample; _output = sample;
return _output; return _output;
} }

Loading…
Cancel
Save