From abb426aec3ccad504cdcb50127ac76c9426fdfe1 Mon Sep 17 00:00:00 2001 From: Jason Short Date: Wed, 30 May 2012 11:06:41 -0700 Subject: [PATCH] When RTLing, force home as the final location for loiter. --- ArduCopter/ArduCopter.pde | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde index 49fc75cf72..4196a25953 100644 --- a/ArduCopter/ArduCopter.pde +++ b/ArduCopter/ArduCopter.pde @@ -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