Browse Source

Plane: set mode CIRCLE on short failsafe in AUTO

this makes the code match the docs
master
Andrew Tridgell 12 years ago
parent
commit
2d5deddd30
  1. 2
      ArduPlane/events.pde

2
ArduPlane/events.pde

@ -23,7 +23,7 @@ static void failsafe_short_on_event(enum failsafe_state fstype) @@ -23,7 +23,7 @@ static void failsafe_short_on_event(enum failsafe_state fstype)
case GUIDED:
case LOITER:
if(g.short_fs_action == 1) {
set_mode(RTL);
set_mode(CIRCLE);
}
break;

Loading…
Cancel
Save