From fd97eb5a8ddc7597f0fda9f13a7f8bdd4350716b Mon Sep 17 00:00:00 2001 From: Jason Short Date: Tue, 3 Jul 2012 17:38:50 -0700 Subject: [PATCH] commands fixed logic bug to make a copter loiter after the mission is ended. --- ArduCopter/commands_process.pde | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/ArduCopter/commands_process.pde b/ArduCopter/commands_process.pde index 56583022d5..7038e46649 100644 --- a/ArduCopter/commands_process.pde +++ b/ArduCopter/commands_process.pde @@ -65,11 +65,11 @@ static void update_commands() // we will disarm the motors after landing. } else { // If the approach altitude is valid (above 1m), do approach, else land - if(g.rtl_approach_alt >= 1){ + if(g.rtl_approach_alt == 0){ + set_mode(LAND); + }else{ set_mode(LOITER); set_new_altitude(g.rtl_approach_alt); - }else{ - set_mode(LAND); } } }