Copter: Disarm: move autotune disarm call after setting soft arm false

This commit is contained in:
Iampete1 2024-08-13 01:29:00 +01:00 committed by Andrew Tridgell
parent bdea9be7fb
commit ba976a2b78

View File

@ -808,11 +808,6 @@ bool AP_Arming_Copter::disarm(const AP_Arming::Method method, bool do_disarm_che
}
}
#if AUTOTUNE_ENABLED == ENABLED
// Possibly save auto tuned parameters
copter.mode_autotune.autotune.disarmed(copter.flightmode == &copter.mode_autotune);
#endif
// we are not in the air
copter.set_land_complete(true);
copter.set_land_complete_maybe(true);
@ -833,6 +828,11 @@ bool AP_Arming_Copter::disarm(const AP_Arming::Method method, bool do_disarm_che
copter.ap.in_arming_delay = false;
#if AUTOTUNE_ENABLED == ENABLED
// Possibly save auto tuned parameters
copter.mode_autotune.autotune.disarmed(copter.flightmode == &copter.mode_autotune);
#endif
return true;
}