Filter: Adjust SlewLimiter tuning

This commit is contained in:
Paul Riseborough 2021-04-11 08:21:53 +10:00 committed by Andrew Tridgell
parent 6e6df3df58
commit dd446433f7

View File

@ -9,7 +9,7 @@
#include "LowPassFilter.h"
#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 WINDOW_MS 300 // 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 {