Browse Source

Add Guided mode to failsafe handling

master
Doug Weibel 13 years ago
parent
commit
7960e7963c
  1. 2
      ArduPlane/events.pde

2
ArduPlane/events.pde

@ -17,6 +17,7 @@ static void failsafe_short_on_event() @@ -17,6 +17,7 @@ static void failsafe_short_on_event()
break;
case AUTO:
case GUIDED:
case LOITER:
if(g.short_fs_action == 1) {
set_mode(RTL);
@ -47,6 +48,7 @@ static void failsafe_long_on_event() @@ -47,6 +48,7 @@ static void failsafe_long_on_event()
break;
case AUTO:
case GUIDED:
case LOITER:
if(g.long_fs_action == 1) {
set_mode(RTL);

Loading…
Cancel
Save