mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 16:48:29 -04:00
ArduCopter: Loiter Timer should have been set when the approach altitude was set. Previously, land had to be enabled before auto approach would work.
This commit is contained in:
parent
37fc6c46b9
commit
dadc7d5a7d
@ -1824,7 +1824,8 @@ static void update_navigation()
|
||||
next_WP.lat = home.lat;
|
||||
next_WP.lng = home.lng;
|
||||
|
||||
if(g.rtl_land_enabled || failsafe)
|
||||
// If land is enabled OR failsafe OR auto approach altitude is set
|
||||
if(g.rtl_land_enabled || failsafe || g.rtl_approach_alt >= 1)
|
||||
loiter_timer = millis();
|
||||
else
|
||||
loiter_timer = 0;
|
||||
|
Loading…
Reference in New Issue
Block a user