Browse Source

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

c415-sdk
Andy Piper 3 years ago committed by Randy Mackay
parent
commit
830130b8b6
  1. 1
      libraries/Filter/SlewLimiter.cpp

1
libraries/Filter/SlewLimiter.cpp

@ -41,6 +41,7 @@ SlewLimiter::SlewLimiter(const float &_slew_rate_max, const float &_slew_rate_ta @@ -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;
}

Loading…
Cancel
Save