mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 10:28:29 -04:00
Added comments
moved out failsafe check. otherwise the reporting was erroneous.
This commit is contained in:
parent
92f7b22722
commit
5f55780b5e
@ -11,21 +11,20 @@ static void failsafe_on_event()
|
||||
{
|
||||
case AUTO:
|
||||
if (g.throttle_fs_action == 1) {
|
||||
// do_rtl sets the altitude to the current altitude by default
|
||||
set_mode(RTL);
|
||||
// send up up 10m
|
||||
// We add an additional 10m to the current altitude
|
||||
next_WP.alt += 1000;
|
||||
}
|
||||
// 2 = Stay in AUTO and ignore failsafe
|
||||
|
||||
default:
|
||||
if(home_is_set == true){
|
||||
// home distance is in meters
|
||||
// This is to prevent accidental RTL
|
||||
if ((home_distance > 15) && (current_loc.alt > 400)){
|
||||
set_mode(RTL);
|
||||
// send up up 10m
|
||||
next_WP.alt += 1000;
|
||||
}
|
||||
// same as above ^
|
||||
// do_rtl sets the altitude to the current altitude by default
|
||||
set_mode(RTL);
|
||||
// We add an additional 10m to the current altitude
|
||||
next_WP.alt += 1000;
|
||||
}else{
|
||||
// We have no GPS so we must land
|
||||
set_mode(LAND);
|
||||
|
Loading…
Reference in New Issue
Block a user