Browse Source

Correct state machine processing for long failsafe event following short failsafe from lower modes

mission-4.1.18
Doug Weibel 14 years ago
parent
commit
8c9757a8d1
  1. 2
      ArduPlane/events.pde

2
ArduPlane/events.pde

@ -43,12 +43,12 @@ static void failsafe_long_on_event() @@ -43,12 +43,12 @@ static void failsafe_long_on_event()
case STABILIZE:
case FLY_BY_WIRE_A: // middle position
case FLY_BY_WIRE_B: // middle position
case CIRCLE:
set_mode(RTL);
break;
case AUTO:
case LOITER:
case CIRCLE:
if(g.long_fs_action == 1) {
set_mode(RTL);
}

Loading…
Cancel
Save