1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-23 00:05:33 +03:00

Add ITerm anti-windup based on motor output saturation

Added noise threshold for PID ITerm accumulation

Removed ITerm setpoint scaler. Added CLI and MSP settings

Made default ITerm noise threshold zero. Added CLI setting.

Removed itermWindupPointPercent from MSP
This commit is contained in:
Martin Budden 2017-01-26 18:15:29 +00:00 committed by borisbstyle
parent 990c13b7ea
commit 9dfb3e45ee
8 changed files with 39 additions and 22 deletions

View file

@ -169,8 +169,8 @@ static void resetPidProfile(pidProfile_t *pidProfile)
pidProfile->yaw_p_limit = YAW_P_LIMIT_MAX;
pidProfile->pidSumLimit = PIDSUM_LIMIT;
pidProfile->yaw_lpf_hz = 0;
pidProfile->rollPitchItermIgnoreRate = 200;
pidProfile->yawItermIgnoreRate = 55;
pidProfile->itermWindupPointPercent = 75;
pidProfile->itermNoiseThreshold = 0;
pidProfile->dterm_filter_type = FILTER_BIQUAD;
pidProfile->dterm_lpf_hz = 100; // filtering ON by default
pidProfile->dterm_notch_hz = 260;