From 7e4972a061af78f3d7743725de5a751dc6b33444 Mon Sep 17 00:00:00 2001 From: Michael du Breuil Date: Sun, 13 May 2018 01:33:58 -0700 Subject: [PATCH] DataFlash: Fix a false reporting of dead IO thread when millis() wraps --- libraries/DataFlash/DataFlash_File.cpp | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/libraries/DataFlash/DataFlash_File.cpp b/libraries/DataFlash/DataFlash_File.cpp index 00fd126319..015aac7afd 100644 --- a/libraries/DataFlash/DataFlash_File.cpp +++ b/libraries/DataFlash/DataFlash_File.cpp @@ -1098,9 +1098,8 @@ bool DataFlash_File::logging_enabled() const bool DataFlash_File::io_thread_alive() const { - uint32_t tnow = AP_HAL::millis(); // if the io thread hasn't had a heartbeat in a full second then it is dead - return _io_timer_heartbeat + 1000 > tnow; + return (AP_HAL::millis() - _io_timer_heartbeat) < 1000; } bool DataFlash_File::logging_failed() const