mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 08:13:56 -04:00
added safety checks for RTL
This commit is contained in:
parent
6e9d3f72ec
commit
b09ab99699
@ -16,7 +16,11 @@ static void failsafe_on_event()
|
|||||||
// 2 = Stay in AUTO and ignore failsafe
|
// 2 = Stay in AUTO and ignore failsafe
|
||||||
|
|
||||||
default:
|
default:
|
||||||
set_mode(RTL);
|
if(home_is_set == true){
|
||||||
|
if (get_distance(¤t_loc, &home) > 15){
|
||||||
|
set_mode(RTL);
|
||||||
|
}
|
||||||
|
}
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user