From c25478448b3c2f7b0cb9254477ab4073396d7bb1 Mon Sep 17 00:00:00 2001 From: Jason Short Date: Fri, 7 Oct 2011 11:06:31 -0700 Subject: [PATCH] Quick RTL Fix, logic was backward --- ArduCopter/ArduCopter.pde | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde index 2e549cd956..a25c472beb 100644 --- a/ArduCopter/ArduCopter.pde +++ b/ArduCopter/ArduCopter.pde @@ -1125,6 +1125,9 @@ static void update_navigation() case RTL: if((wp_distance <= g.waypoint_radius) || check_missed_wp()){ + // lets just jump to Loiter Mode after RTL + set_mode(LOITER); + }else{ // calculates desired Yaw // XXX this is an experiment #if FRAME_CONFIG == HELI_FRAME @@ -1132,9 +1135,6 @@ static void update_navigation() #endif wp_control = WP_MODE; - }else{ - // lets just jump to Loiter Mode after RTL - set_mode(LOITER); } // calculates the desired Roll and Pitch