Skip to content

Commit

Permalink
Copter: Disarm: move autotune disarm call after setting soft arm false
Browse files Browse the repository at this point in the history
  • Loading branch information
IamPete1 authored and tridge committed Aug 19, 2024
1 parent bdea9be commit ba976a2
Showing 1 changed file with 5 additions and 5 deletions.
10 changes: 5 additions & 5 deletions ArduCopter/AP_Arming.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);
Expand All @@ -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;
}

Expand Down

0 comments on commit ba976a2

Please sign in to comment.