mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 08:38:36 -04:00
DataFlash: Fix a false reporting of dead IO thread when millis() wraps
This commit is contained in:
parent
703c7fb4b7
commit
7e4972a061
@ -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…
Reference in New Issue
Block a user