From bc578172a553eea81b324985dc0541419a1f4aca Mon Sep 17 00:00:00 2001 From: Jason Short Date: Wed, 30 May 2012 09:44:59 -0700 Subject: [PATCH] moved detector to run until the throttle is low, then stop running. --- ArduCopter/commands_logic.pde | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/ArduCopter/commands_logic.pde b/ArduCopter/commands_logic.pde index 0e2b3a35ea..e20172b154 100644 --- a/ArduCopter/commands_logic.pde +++ b/ArduCopter/commands_logic.pde @@ -424,9 +424,9 @@ static bool verify_land_sonar() if(ground_detector < 30) { ground_detector++; }else if (ground_detector == 30){ - ground_detector++; land_complete = true; if(g.rc_3.control_in == 0){ + ground_detector++; init_disarm_motors(); } return true; @@ -458,9 +458,9 @@ static bool verify_land_baro() if(ground_detector < 30) { ground_detector++; }else if (ground_detector == 30){ - ground_detector++; land_complete = true; if(g.rc_3.control_in == 0){ + ground_detector++; init_disarm_motors(); } return true;