Filter: set output slew rate to zero when max is zero.

This commit is contained in:
Andy Piper 2021-11-10 10:10:36 +00:00 committed by Randy Mackay
parent ae1f274919
commit 830130b8b6

View File

@ -41,6 +41,7 @@ SlewLimiter::SlewLimiter(const float &_slew_rate_max, const float &_slew_rate_ta
float SlewLimiter::modifier(float sample, float dt) float SlewLimiter::modifier(float sample, float dt)
{ {
if (slew_rate_max <= 0) { if (slew_rate_max <= 0) {
_output_slew_rate = 0.0;
return 1.0; return 1.0;
} }