mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
Copter: crash check works with flip flight mode
This commit is contained in:
parent
22280e1c57
commit
fe26af86de
@ -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;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user