Copter: only allow auto_trim in STABILIZE

This commit is contained in:
Randy Mackay 2013-08-15 21:11:23 +09:00
parent 69da4e99f8
commit fe56ac3839

View File

@ -68,7 +68,7 @@ static void arm_motors_check()
}
// arm the motors and configure for flight
if (arming_counter == AUTO_TRIM_DELAY && motors.armed()) {
if (arming_counter == AUTO_TRIM_DELAY && motors.armed() && control_mode == STABILIZE) {
auto_trim_counter = 250;
}