Copter: crash check works with flip flight mode

This commit is contained in:
Randy Mackay 2014-02-03 16:25:11 +09:00 committed by Andrew Tridgell
parent 22280e1c57
commit fe26af86de

View File

@ -26,7 +26,7 @@ void crash_check()
}
// return immediately if we are not in an angle stabilize flight mode or we are flipping
if (control_mode == ACRO || ap.do_flip) {
if (control_mode == ACRO || control_mode == FLIP) {
inverted_count = 0;
return;
}