Browse Source

DataFlash: remove unused ReadBlock method

mission-4.1.18
Peter Barker 7 years ago committed by Peter Barker
parent
commit
493f958eb2
  1. 2
      libraries/DataFlash/DataFlash_Backend.h
  2. 18
      libraries/DataFlash/DataFlash_File.cpp
  3. 5
      libraries/DataFlash/DataFlash_File.h
  4. 18
      libraries/DataFlash/DataFlash_File_sd.cpp
  5. 5
      libraries/DataFlash/DataFlash_File_sd.h
  6. 3
      libraries/DataFlash/DataFlash_MAVLink.h

2
libraries/DataFlash/DataFlash_Backend.h

@ -141,8 +141,6 @@ protected: @@ -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();

18
libraries/DataFlash/DataFlash_File.cpp

@ -580,24 +580,6 @@ bool DataFlash_File::_WritePrioritisedBlock(const void *pBuffer, uint16_t size, @@ -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
*/

5
libraries/DataFlash/DataFlash_File.h

@ -81,11 +81,6 @@ private: @@ -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

18
libraries/DataFlash/DataFlash_File_sd.cpp

@ -501,24 +501,6 @@ bool DataFlash_File::_WritePrioritisedBlock(const void *pBuffer, uint16_t size, @@ -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
*/

5
libraries/DataFlash/DataFlash_File_sd.h

@ -78,11 +78,6 @@ private: @@ -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

3
libraries/DataFlash/DataFlash_MAVLink.h

@ -173,9 +173,6 @@ private: @@ -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;

Loading…
Cancel
Save