From 09f4a16bfb700788c5c18776a86fc7b6673836e0 Mon Sep 17 00:00:00 2001 From: Jason Short Date: Tue, 29 May 2012 11:19:28 -0700 Subject: [PATCH] changed the way takeoff complete is figured. Looking for high throttle. --- ArduCopter/ArduCopter.pde | 10 ++++++---- 1 file changed, 6 insertions(+), 4 deletions(-) diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde index fa8c716427..72c689344e 100644 --- a/ArduCopter/ArduCopter.pde +++ b/ArduCopter/ArduCopter.pde @@ -1624,11 +1624,13 @@ void update_throttle_mode(void) } #endif - // Code to manage the Copter state - if ((millis() - takeoff_timer) > 5000){ - // we must be in the air by now - takeoff_complete = true; + if (takeoff_complete == false && motors.armed()){ + if ((g.rc_3.control_in > g.throttle_cruise)){ + // we must be in the air by now + takeoff_complete = true; + } } + }else{ // we are on the ground takeoff_complete = false;