mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
Dataflash: emit io thread warnings much less frequently
This commit is contained in:
parent
713c08672f
commit
9324d8e251
@ -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()) {
|
||||
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.
|
||||
|
@ -85,6 +85,7 @@ private:
|
||||
|
||||
uint32_t _io_timer_heartbeat;
|
||||
bool io_thread_alive() const;
|
||||
uint8_t io_thread_warning_decimation_counter;
|
||||
|
||||
uint16_t _cached_oldest_log;
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user