mirror of https://github.com/ArduPilot/ardupilot
AP_Logger: check is_system_initialized() when determining liveness
This commit is contained in:
parent
c8e464ebea
commit
048deeb43e
|
@ -827,7 +827,7 @@ bool AP_Logger_Block::logging_failed() const
|
|||
bool AP_Logger_Block::io_thread_alive() const
|
||||
{
|
||||
// if the io thread hasn't had a heartbeat in 3s it is dead
|
||||
return (AP_HAL::millis() - io_timer_heartbeat) < 3000U || hal.scheduler->in_expected_delay();
|
||||
return (AP_HAL::millis() - io_timer_heartbeat) < 3000U || !hal.scheduler->is_system_initialized();
|
||||
}
|
||||
|
||||
/*
|
||||
|
|
|
@ -1003,7 +1003,7 @@ bool AP_Logger_File::io_thread_alive() const
|
|||
{
|
||||
// if the io thread hasn't had a heartbeat in a full seconds then it is dead
|
||||
// this is enough time for a sdcard remount
|
||||
return (AP_HAL::millis() - _io_timer_heartbeat) < 3000U;
|
||||
return (AP_HAL::millis() - _io_timer_heartbeat) < 3000U || !hal.scheduler->is_system_initialized();
|
||||
}
|
||||
|
||||
bool AP_Logger_File::logging_failed() const
|
||||
|
|
Loading…
Reference in New Issue