Filter: dt check fix for LPF

This commit is contained in:
Randy Mackay 2015-04-17 10:59:03 +09:00
parent f20a91ec95
commit 99a9a88529

View File

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