From 77d6f22864f3e4e08e565ca89bf2f862affa2133 Mon Sep 17 00:00:00 2001 From: Adam M Rivera Date: Sun, 15 Apr 2012 19:50:05 -0500 Subject: [PATCH] ArduCopter, commands_logic: Updated logic to allow as low as 5m. --- ArduCopter/ArduCopter.pde | 2 +- ArduCopter/commands_logic.pde | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde index fc03173eaa..64699c9b1b 100644 --- a/ArduCopter/ArduCopter.pde +++ b/ArduCopter/ArduCopter.pde @@ -1814,7 +1814,7 @@ static void update_navigation() wp_control = LOITER_MODE; } - if(g.rtl_approach_alt > 5){ + if(g.rtl_approach_alt >= 5){ set_mode(APPROACH); } // Kick us out of loiter and begin landing if the auto_land_timer is set diff --git a/ArduCopter/commands_logic.pde b/ArduCopter/commands_logic.pde index 14dcd9605f..327686cfb6 100644 --- a/ArduCopter/commands_logic.pde +++ b/ArduCopter/commands_logic.pde @@ -295,7 +295,7 @@ static void do_land() static void do_approach() { // Make sure we are not using this to land - if(g.rtl_approach_alt > 5){ + if(g.rtl_approach_alt >= 5){ wp_control = LOITER_MODE; // just to make sure