Filter: Increase gain modifier action

This commit is contained in:
Paul Riseborough 2021-04-11 08:19:24 +10:00 committed by Andrew Tridgell
parent 458c46353d
commit 6e6df3df58
2 changed files with 2 additions and 1 deletions

View File

@ -119,7 +119,7 @@ float SlewLimiter::modifier(float sample, float dt)
// Calculate the gain adjustment
float mod;
if (_oscillation_slew_rate > slew_rate_max) {
mod = slew_rate_max / _oscillation_slew_rate;
mod = slew_rate_max / (slew_rate_max + MODIFIER_GAIN * (_oscillation_slew_rate - slew_rate_max));
} else {
mod = 1.0f;
}

View File

@ -10,6 +10,7 @@
#define N_EVENTS 2 // number of positive and negative consecutive slew rate exceedance events recorded where a value of 2 corresponds to a complete cycle
#define WINDOW_MS 250 // time in msec required for a half cycle of the slowest oscillation frequency expected
#define MODIFIER_GAIN 1.5f // ratio of modifier reduction to slew rate exceedance ratio
class SlewLimiter {
public: