added in RTL failsafe option for AUTO mode.
git-svn-id: https://arducopter.googlecode.com/svn/trunk@2372 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
26655d47ad
commit
b8d3b12b35
@ -9,13 +9,21 @@ void failsafe_on_event()
|
||||
// This is how to handle a failsafe.
|
||||
switch(control_mode)
|
||||
{
|
||||
case AUTO:
|
||||
if (g.throttle_fs_action == 1) {
|
||||
set_mode(RTL);
|
||||
}
|
||||
// 2 = Stay in AUTO and ignore failsafe
|
||||
|
||||
default:
|
||||
// not ready to enable yet w/o more testing
|
||||
//set_mode(RTL);
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
void failsafe_off_event()
|
||||
{
|
||||
/*
|
||||
if (g.throttle_fs_action == 2){
|
||||
// We're back in radio contact
|
||||
// return to AP
|
||||
@ -36,7 +44,6 @@ void failsafe_off_event()
|
||||
// ------------------------------------------------------
|
||||
set_mode(RTL);
|
||||
}
|
||||
*/
|
||||
}
|
||||
|
||||
void low_battery_event(void)
|
||||
|
Loading…
Reference in New Issue
Block a user