mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-20 23:05:19 +03:00
Prevent winding up of Iterm when disarmed
This commit is contained in:
parent
d7ecb4cc39
commit
59e66cfd54
1 changed files with 1 additions and 1 deletions
|
@ -568,7 +568,7 @@ void processRx(void)
|
|||
* Additional code to prevent Iterm reset below min_check. pid_at_min_throttle higher than 1 will
|
||||
* activate the feature. Experimental yet. Minimum configuration is 2 sec and maxx is 5seconds.
|
||||
*/
|
||||
if (masterConfig.mixerConfig.pid_at_min_throttle > 1) {
|
||||
if (masterConfig.mixerConfig.pid_at_min_throttle > 1 && ARMING_FLAG(ARMED)) {
|
||||
if (pidResetErrorGyroTimeout < millis()) {
|
||||
pidResetErrorGyro();
|
||||
}
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue