mirror of https://github.com/ArduPilot/ardupilot
Add Guided mode to failsafe handling
This commit is contained in:
parent
e965d95ba8
commit
ca5560ef1c
|
@ -17,6 +17,7 @@ static void failsafe_short_on_event()
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case AUTO:
|
case AUTO:
|
||||||
|
case GUIDED:
|
||||||
case LOITER:
|
case LOITER:
|
||||||
if(g.short_fs_action == 1) {
|
if(g.short_fs_action == 1) {
|
||||||
set_mode(RTL);
|
set_mode(RTL);
|
||||||
|
@ -47,6 +48,7 @@ static void failsafe_long_on_event()
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case AUTO:
|
case AUTO:
|
||||||
|
case GUIDED:
|
||||||
case LOITER:
|
case LOITER:
|
||||||
if(g.long_fs_action == 1) {
|
if(g.long_fs_action == 1) {
|
||||||
set_mode(RTL);
|
set_mode(RTL);
|
||||||
|
|
Loading…
Reference in New Issue