From c523a9822b4517e5393c247f241614ae233804e2 Mon Sep 17 00:00:00 2001 From: Jason Short Date: Tue, 29 May 2012 11:24:41 -0700 Subject: [PATCH] Failsafe: Looking for takeoff_complete now vs unreliable GPS --- ArduCopter/radio.pde | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduCopter/radio.pde b/ArduCopter/radio.pde index 653813c300..b1cb39d0d6 100644 --- a/ArduCopter/radio.pde +++ b/ArduCopter/radio.pde @@ -147,7 +147,7 @@ static void throttle_failsafe(uint16_t pwm) // Don't enter Failsafe if we are not armed // home distance is in meters // This is to prevent accidental RTL - if(motors.armed() && (home_distance > 1000)){ + if(motors.armed() && takeoff_complete){ SendDebug("MSG FS ON "); SendDebugln(pwm, DEC); set_failsafe(true);