From 08bf04dd08dd4b2842017b45f686136295767aee Mon Sep 17 00:00:00 2001 From: Jason Short Date: Tue, 29 May 2012 11:21:04 -0700 Subject: [PATCH] pulling throttle low in flight turns out to be more common than thought. Removed clearing of takeoff_complete flag. This is still cleared during disarm which is automatic after 30 seconds of no throttle. --- ArduCopter/ArduCopter.pde | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde index 72c689344e..dd12caa419 100644 --- a/ArduCopter/ArduCopter.pde +++ b/ArduCopter/ArduCopter.pde @@ -1633,7 +1633,7 @@ void update_throttle_mode(void) }else{ // we are on the ground - takeoff_complete = false; + //takeoff_complete = false; // reset baro data if we are near home if(home_distance < 400 || GPS_enabled == false){ // 4m from home