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