mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 08:38:36 -04:00
Copter: only allow auto_trim in STABILIZE
This commit is contained in:
parent
69da4e99f8
commit
fe56ac3839
@ -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;
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user