|
|
|
@ -8,7 +8,7 @@
@@ -8,7 +8,7 @@
|
|
|
|
|
//
|
|
|
|
|
|
|
|
|
|
static bool failsafe_enabled = false; |
|
|
|
|
static uint16_t failsafe_last_mainLoop_count; |
|
|
|
|
static uint16_t failsafe_last_ticks; |
|
|
|
|
static uint32_t failsafe_last_timestamp; |
|
|
|
|
static bool in_failsafe; |
|
|
|
|
|
|
|
|
@ -36,9 +36,10 @@ void Copter::failsafe_check()
@@ -36,9 +36,10 @@ void Copter::failsafe_check()
|
|
|
|
|
{ |
|
|
|
|
uint32_t tnow = AP_HAL::micros(); |
|
|
|
|
|
|
|
|
|
if (mainLoop_count != failsafe_last_mainLoop_count) { |
|
|
|
|
const uint16_t ticks = scheduler.ticks(); |
|
|
|
|
if (ticks != failsafe_last_ticks) { |
|
|
|
|
// the main loop is running, all is OK
|
|
|
|
|
failsafe_last_mainLoop_count = mainLoop_count; |
|
|
|
|
failsafe_last_ticks = ticks; |
|
|
|
|
failsafe_last_timestamp = tnow; |
|
|
|
|
if (in_failsafe) { |
|
|
|
|
in_failsafe = false; |
|
|
|
|