Browse Source

DataFlash: Fix a false reporting of dead IO thread when millis() wraps

master
Michael du Breuil 7 years ago committed by Randy Mackay
parent
commit
7e4972a061
  1. 3
      libraries/DataFlash/DataFlash_File.cpp

3
libraries/DataFlash/DataFlash_File.cpp

@ -1098,9 +1098,8 @@ bool DataFlash_File::logging_enabled() const @@ -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

Loading…
Cancel
Save