Skip to content
Snippets Groups Projects
Commit abb426ae authored by Jason Short's avatar Jason Short
Browse files

When RTLing, force home as the final location for loiter.

parent 5b31f3ba
No related branches found
No related tags found
No related merge requests found
......@@ -1751,6 +1751,10 @@ static void update_navigation()
if((wp_distance <= g.waypoint_radius) || check_missed_wp()){
// if loiter_timer value > 0, we are set to trigger auto_land or approach after 20 seconds
set_mode(LOITER);
// force loitering above home
next_WP.lat = home.lat;
next_WP.lng = home.lng;
if(g.rtl_land_enabled || failsafe)
loiter_timer = millis();
else
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment