diff --git a/ArduCopter/failsafe.pde b/ArduCopter/failsafe.pde index 45cf3f6996..8e6d17b3b4 100644 --- a/ArduCopter/failsafe.pde +++ b/ArduCopter/failsafe.pde @@ -6,7 +6,7 @@ // our failsafe strategy is to detect main loop lockup and disarm the motors // -static bool failsafe_enabled = true; +static bool failsafe_enabled = false; static uint16_t failsafe_last_mainLoop_count; static uint32_t failsafe_last_timestamp; static bool in_failsafe; diff --git a/ArduCopter/system.pde b/ArduCopter/system.pde index 80dacf5fcf..0fdbc385e7 100644 --- a/ArduCopter/system.pde +++ b/ArduCopter/system.pde @@ -258,6 +258,9 @@ static void init_ardupilot() // ready to fly serial_manager.set_blocking_writes_all(false); + // enable CPU failsafe + failsafe_enable(); + cliSerial->print_P(PSTR("\nReady to FLY ")); // flag that initialisation has completed