Copter: auto-disarm in Drift, Sport, OF_Loiter

This commit is contained in:
Randy Mackay 2014-07-31 22:58:02 +09:00
parent b52f8351e8
commit 2c0699c9ed

View File

@ -103,7 +103,9 @@ 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 == LOITER || control_mode == ALT_HOLD || control_mode == POSHOLD || control_mode == AUTOTUNE))) {
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))) {
auto_disarming_counter++;
if(auto_disarming_counter >= AUTO_DISARMING_DELAY) {