diff --git a/libraries/DataFlash/DataFlash_Backend.cpp b/libraries/DataFlash/DataFlash_Backend.cpp index b76a4798fe..ce6286b9ee 100644 --- a/libraries/DataFlash/DataFlash_Backend.cpp +++ b/libraries/DataFlash/DataFlash_Backend.cpp @@ -268,6 +268,9 @@ bool DataFlash_Backend::WritesOK() const if (!_front.vehicle_is_armed() && !_front.log_while_disarmed()) { return false; } + if (!_initialised) { + return false; + } return true; } diff --git a/libraries/DataFlash/DataFlash_Backend.h b/libraries/DataFlash/DataFlash_Backend.h index fcf0eecec2..2c44209adb 100644 --- a/libraries/DataFlash/DataFlash_Backend.h +++ b/libraries/DataFlash/DataFlash_Backend.h @@ -157,6 +157,8 @@ protected: // must be called when a new log is being started: virtual void start_new_log_reset_variables(); + bool _initialised; + private: uint32_t _last_periodic_1Hz; diff --git a/libraries/DataFlash/DataFlash_File.cpp b/libraries/DataFlash/DataFlash_File.cpp index 667ec4a251..9734eefdbe 100644 --- a/libraries/DataFlash/DataFlash_File.cpp +++ b/libraries/DataFlash/DataFlash_File.cpp @@ -53,7 +53,6 @@ DataFlash_File::DataFlash_File(DataFlash_Class &front, _read_fd_log_num(0), _read_offset(0), _write_offset(0), - _initialised(false), _open_error(false), _log_directory(log_directory), _cached_oldest_log(0), @@ -520,9 +519,6 @@ bool DataFlash_File::WritesOK() const if (_write_fd == -1) { return false; } - if (!_initialised) { - return false; - } if (_open_error) { return false; } diff --git a/libraries/DataFlash/DataFlash_File.h b/libraries/DataFlash/DataFlash_File.h index 0e46b3b13e..4eec8d64be 100644 --- a/libraries/DataFlash/DataFlash_File.h +++ b/libraries/DataFlash/DataFlash_File.h @@ -83,7 +83,6 @@ private: uint16_t _read_fd_log_num; uint32_t _read_offset; uint32_t _write_offset; - volatile bool _initialised; volatile bool _open_error; const char *_log_directory; diff --git a/libraries/DataFlash/DataFlash_MAVLink.cpp b/libraries/DataFlash/DataFlash_MAVLink.cpp index 12e9de460d..80fdc78a0d 100644 --- a/libraries/DataFlash/DataFlash_MAVLink.cpp +++ b/libraries/DataFlash/DataFlash_MAVLink.cpp @@ -124,9 +124,6 @@ bool DataFlash_MAVLink::WritesOK() const if (!DataFlash_Backend::WritesOK()) { return false; } - if (!_initialised) { - return false; - } if (!_sending_to_client) { return false; } diff --git a/libraries/DataFlash/DataFlash_MAVLink.h b/libraries/DataFlash/DataFlash_MAVLink.h index 472d03f3a3..7996b59542 100644 --- a/libraries/DataFlash/DataFlash_MAVLink.h +++ b/libraries/DataFlash/DataFlash_MAVLink.h @@ -131,8 +131,6 @@ private: uint8_t _target_system_id; uint8_t _target_component_id; - bool _initialised; - // this controls the maximum number of blocks we will push from // the pending and send queues in any call to push_log_blocks. // push_log_blocks is called by periodic_tasks. Each block is 200