Copter: auto-disarm if land complete regardless of mode
This commit is contained in:
parent
d0d26b6878
commit
3e1bffe9ab
@ -105,9 +105,7 @@ static void auto_disarm_check()
|
||||
}
|
||||
|
||||
// allow auto disarm in manual flight modes or Loiter/AltHold if we're landed
|
||||
if (manual_flight_mode(control_mode) || (ap.land_complete && (control_mode == ALT_HOLD || control_mode == LOITER || control_mode == OF_LOITER ||
|
||||
control_mode == DRIFT || control_mode == SPORT || control_mode == AUTOTUNE ||
|
||||
control_mode == POSHOLD))) {
|
||||
if (manual_flight_mode(control_mode) || ap.land_complete) {
|
||||
auto_disarming_counter++;
|
||||
|
||||
if(auto_disarming_counter >= AUTO_DISARMING_DELAY) {
|
||||
|
Loading…
Reference in New Issue
Block a user