mirror of https://github.com/ArduPilot/ardupilot
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:
parent
82f6bb3c17
commit
a20a89181c
|
@ -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;
|
||||
|
|
|
@ -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
|
||||
|
|
Loading…
Reference in New Issue