|
|
|
@ -186,7 +186,12 @@ bool DataFlash_File::log_exists(const uint16_t lognum) const
@@ -186,7 +186,12 @@ bool DataFlash_File::log_exists(const uint16_t lognum) const
|
|
|
|
|
void DataFlash_File::periodic_1Hz(const uint32_t now) |
|
|
|
|
{ |
|
|
|
|
if (!io_thread_alive()) { |
|
|
|
|
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, "No IO Thread Heartbeat"); |
|
|
|
|
if (io_thread_warning_decimation_counter == 0) { |
|
|
|
|
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, "No IO Thread Heartbeat"); |
|
|
|
|
} |
|
|
|
|
if (io_thread_warning_decimation_counter++ > 57) { |
|
|
|
|
io_thread_warning_decimation_counter = 0; |
|
|
|
|
} |
|
|
|
|
// If you try to close the file here then it will almost
|
|
|
|
|
// certainly block. Since this is the main thread, this is
|
|
|
|
|
// likely to cause a crash.
|
|
|
|
|