1
0
Fork 0
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:
borisbstyle 2015-11-13 14:59:43 +01:00
parent d7ecb4cc39
commit 59e66cfd54

View file

@ -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();
}