Copter: enable CPU failsafe after initialisation

This removes a false positive during startup that lead to an error
appearing at the start of the dataflash log
This commit is contained in:
Randy Mackay 2015-04-13 15:57:44 +09:00
parent 82f6bb3c17
commit a20a89181c
2 changed files with 4 additions and 1 deletions

View File

@ -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;

View File

@ -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