From bc45ab5409bd2aea6ad29da39f4d91ddd2e920e5 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Sun, 6 Nov 2016 17:09:39 +1100 Subject: [PATCH] DataFlash: add a heartbeat for the io thread in DataFlash_File --- libraries/DataFlash/DataFlash_File.cpp | 29 +++++++++++++++++++++++++- libraries/DataFlash/DataFlash_File.h | 4 ++++ 2 files changed, 32 insertions(+), 1 deletion(-) diff --git a/libraries/DataFlash/DataFlash_File.cpp b/libraries/DataFlash/DataFlash_File.cpp index fdb1294080..a8360a9192 100644 --- a/libraries/DataFlash/DataFlash_File.cpp +++ b/libraries/DataFlash/DataFlash_File.cpp @@ -29,6 +29,7 @@ #include #include #include +#include #if defined(__APPLE__) && defined(__MACH__) #include #include @@ -182,6 +183,18 @@ bool DataFlash_File::log_exists(const uint16_t lognum) const return ret; } +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 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. + _write_fd = -1; + _initialised = false; + } +} + void DataFlash_File::periodic_fullrate(const uint32_t now) { DataFlash_Backend::push_log_blocks(); @@ -1017,6 +1030,8 @@ void DataFlash_File::flush(void) void DataFlash_File::_io_timer(void) { + uint32_t tnow = AP_HAL::millis(); + _io_timer_heartbeat = tnow; if (_write_fd == -1 || !_initialised || _open_error) { return; } @@ -1025,7 +1040,6 @@ void DataFlash_File::_io_timer(void) if (nbytes == 0) { return; } - uint32_t tnow = AP_HAL::millis(); if (nbytes < _writebuf_chunk && tnow - _last_write_time < 2000UL) { // write in _writebuf_chunk-sized chunks, but always write at @@ -1094,6 +1108,13 @@ bool DataFlash_File::logging_enabled() const return false; } +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; +} + bool DataFlash_File::logging_failed() const { if (_write_fd == -1 && @@ -1104,6 +1125,12 @@ bool DataFlash_File::logging_failed() const if (_open_error) { return true; } + if (!io_thread_alive()) { + // No heartbeat in a second. IO thread is dead?! Very Not + // Good. + return true; + } + return false; } diff --git a/libraries/DataFlash/DataFlash_File.h b/libraries/DataFlash/DataFlash_File.h index 58cd1b041d..585b37b981 100644 --- a/libraries/DataFlash/DataFlash_File.h +++ b/libraries/DataFlash/DataFlash_File.h @@ -64,6 +64,7 @@ public: #if CONFIG_HAL_BOARD == HAL_BOARD_SITL || CONFIG_HAL_BOARD == HAL_BOARD_LINUX void flush(void); #endif + void periodic_1Hz(const uint32_t now) override; void periodic_fullrate(const uint32_t now); // this method is used when reporting system status over mavlink @@ -82,6 +83,9 @@ private: volatile bool _open_error; const char *_log_directory; + uint32_t _io_timer_heartbeat; + bool io_thread_alive() const; + uint16_t _cached_oldest_log; /*