mirror of https://github.com/ArduPilot/ardupilot
Correct state machine processing for long failsafe event following short failsafe from lower modes
This commit is contained in:
parent
251c5875fb
commit
8c9757a8d1
|
@ -43,12 +43,12 @@ static void failsafe_long_on_event()
|
||||||
case STABILIZE:
|
case STABILIZE:
|
||||||
case FLY_BY_WIRE_A: // middle position
|
case FLY_BY_WIRE_A: // middle position
|
||||||
case FLY_BY_WIRE_B: // middle position
|
case FLY_BY_WIRE_B: // middle position
|
||||||
|
case CIRCLE:
|
||||||
set_mode(RTL);
|
set_mode(RTL);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case AUTO:
|
case AUTO:
|
||||||
case LOITER:
|
case LOITER:
|
||||||
case CIRCLE:
|
|
||||||
if(g.long_fs_action == 1) {
|
if(g.long_fs_action == 1) {
|
||||||
set_mode(RTL);
|
set_mode(RTL);
|
||||||
}
|
}
|
||||||
|
|
Loading…
Reference in New Issue