mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-14 20:10:18 +03:00
set default iterm_windup to 85 for yaw
This commit is contained in:
parent
40610c8e48
commit
898fe30924
1 changed files with 1 additions and 1 deletions
|
@ -138,7 +138,7 @@ void resetPidProfile(pidProfile_t *pidProfile)
|
|||
.yaw_lowpass_hz = 100,
|
||||
.dterm_notch_hz = 0,
|
||||
.dterm_notch_cutoff = 0,
|
||||
.itermWindupPointPercent = 100,
|
||||
.itermWindupPointPercent = 85,
|
||||
.pidAtMinThrottle = PID_STABILISATION_ON,
|
||||
.levelAngleLimit = 55,
|
||||
.feedforward_transition = 0,
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue