mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 10:28:29 -04:00
allow auto-land if failsafe is triggered
This commit is contained in:
parent
fabeccad4a
commit
e8b6f5ecee
@ -1684,7 +1684,7 @@ static void update_navigation()
|
||||
if((wp_distance <= g.waypoint_radius) || check_missed_wp()){
|
||||
// if auto_land_timer value > 0, we are set to trigger auto_land after 20 seconds
|
||||
set_mode(LOITER);
|
||||
if(g.rtl_land_enabled)
|
||||
if(g.rtl_land_enabled || failsafe)
|
||||
auto_land_timer = millis();
|
||||
else
|
||||
auto_land_timer = 0;
|
||||
|
Loading…
Reference in New Issue
Block a user