From 476713f9e39e4b7111a13258c554d7e31da33e33 Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Wed, 10 Nov 2021 10:10:36 +0000 Subject: [PATCH] Filter: set output slew rate to zero when max is zero. --- libraries/Filter/SlewLimiter.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/libraries/Filter/SlewLimiter.cpp b/libraries/Filter/SlewLimiter.cpp index fde35dad3c..d2e0677597 100644 --- a/libraries/Filter/SlewLimiter.cpp +++ b/libraries/Filter/SlewLimiter.cpp @@ -41,6 +41,7 @@ SlewLimiter::SlewLimiter(const float &_slew_rate_max, const float &_slew_rate_ta float SlewLimiter::modifier(float sample, float dt) { if (slew_rate_max <= 0) { + _output_slew_rate = 0.0; return 1.0; }