From 493f958eb2f47e8670ce80c3102c66ef71359b8c Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Sun, 17 Jun 2018 10:41:33 +1000 Subject: [PATCH] DataFlash: remove unused ReadBlock method --- libraries/DataFlash/DataFlash_Backend.h | 2 -- libraries/DataFlash/DataFlash_File.cpp | 18 ------------------ libraries/DataFlash/DataFlash_File.h | 5 ----- libraries/DataFlash/DataFlash_File_sd.cpp | 18 ------------------ libraries/DataFlash/DataFlash_File_sd.h | 5 ----- libraries/DataFlash/DataFlash_MAVLink.h | 3 --- 6 files changed, 51 deletions(-) diff --git a/libraries/DataFlash/DataFlash_Backend.h b/libraries/DataFlash/DataFlash_Backend.h index 583f172289..0579d2dc99 100644 --- a/libraries/DataFlash/DataFlash_Backend.h +++ b/libraries/DataFlash/DataFlash_Backend.h @@ -141,8 +141,6 @@ protected: /* read a block */ - virtual bool ReadBlock(void *pkt, uint16_t size) = 0; - virtual bool WriteBlockCheckStartupMessages(); virtual void WriteMoreStartupMessages(); virtual void push_log_blocks(); diff --git a/libraries/DataFlash/DataFlash_File.cpp b/libraries/DataFlash/DataFlash_File.cpp index db620c5b46..6d46048156 100644 --- a/libraries/DataFlash/DataFlash_File.cpp +++ b/libraries/DataFlash/DataFlash_File.cpp @@ -580,24 +580,6 @@ bool DataFlash_File::_WritePrioritisedBlock(const void *pBuffer, uint16_t size, return true; } -/* - read a packet. The header bytes have already been read. -*/ -bool DataFlash_File::ReadBlock(void *pkt, uint16_t size) -{ - if (_read_fd == -1 || !_initialised || _open_error) { - return false; - } - - memset(pkt, 0, size); - if (::read(_read_fd, pkt, size) != size) { - return false; - } - _read_offset += size; - return true; -} - - /* find the highest log number */ diff --git a/libraries/DataFlash/DataFlash_File.h b/libraries/DataFlash/DataFlash_File.h index 1dbe85705f..83a8df51f1 100644 --- a/libraries/DataFlash/DataFlash_File.h +++ b/libraries/DataFlash/DataFlash_File.h @@ -81,11 +81,6 @@ private: uint16_t _cached_oldest_log; - /* - read a block - */ - bool ReadBlock(void *pkt, uint16_t size) override; - uint16_t _log_num_from_list_entry(const uint16_t list_entry); // possibly time-consuming preparations handling diff --git a/libraries/DataFlash/DataFlash_File_sd.cpp b/libraries/DataFlash/DataFlash_File_sd.cpp index 77455e3b3b..728bc4237f 100644 --- a/libraries/DataFlash/DataFlash_File_sd.cpp +++ b/libraries/DataFlash/DataFlash_File_sd.cpp @@ -501,24 +501,6 @@ bool DataFlash_File::_WritePrioritisedBlock(const void *pBuffer, uint16_t size, return true; } -/* - read a packet. The header bytes have already been read. -*/ -bool DataFlash_File::ReadBlock(void *pkt, uint16_t size) -{ - if (!(_read_fd) || !_initialised || _open_error) { - return false; - } - - memset(pkt, 0, size); - if (_read_fd.read(pkt, size) != size) { - return false; - } - _read_offset += size; - return true; -} - - /* find the highest log number */ diff --git a/libraries/DataFlash/DataFlash_File_sd.h b/libraries/DataFlash/DataFlash_File_sd.h index 51660b47fb..32d98eab18 100644 --- a/libraries/DataFlash/DataFlash_File_sd.h +++ b/libraries/DataFlash/DataFlash_File_sd.h @@ -78,11 +78,6 @@ private: uint16_t _cached_oldest_log; uint16_t _last_oldest_log; - /* - read a block - */ - bool ReadBlock(void *pkt, uint16_t size) override; - uint16_t _log_num_from_list_entry(const uint16_t list_entry); // possibly time-consuming preparations handling diff --git a/libraries/DataFlash/DataFlash_MAVLink.h b/libraries/DataFlash/DataFlash_MAVLink.h index 33450ddd20..efc37f3db8 100644 --- a/libraries/DataFlash/DataFlash_MAVLink.h +++ b/libraries/DataFlash/DataFlash_MAVLink.h @@ -173,9 +173,6 @@ private: uint16_t start_new_log(void) override { return 0; } - bool ReadBlock(void *pkt, uint16_t size) override { - return false; - } // performance counters AP_HAL::Util::perf_counter_t _perf_errors; AP_HAL::Util::perf_counter_t _perf_packing;