mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 16:23:56 -04:00
DataFlash: remove unused ReadBlock method
This commit is contained in:
parent
00b2cc4a93
commit
493f958eb2
@ -141,8 +141,6 @@ protected:
|
|||||||
/*
|
/*
|
||||||
read a block
|
read a block
|
||||||
*/
|
*/
|
||||||
virtual bool ReadBlock(void *pkt, uint16_t size) = 0;
|
|
||||||
|
|
||||||
virtual bool WriteBlockCheckStartupMessages();
|
virtual bool WriteBlockCheckStartupMessages();
|
||||||
virtual void WriteMoreStartupMessages();
|
virtual void WriteMoreStartupMessages();
|
||||||
virtual void push_log_blocks();
|
virtual void push_log_blocks();
|
||||||
|
@ -580,24 +580,6 @@ bool DataFlash_File::_WritePrioritisedBlock(const void *pBuffer, uint16_t size,
|
|||||||
return true;
|
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
|
find the highest log number
|
||||||
*/
|
*/
|
||||||
|
@ -81,11 +81,6 @@ private:
|
|||||||
|
|
||||||
uint16_t _cached_oldest_log;
|
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);
|
uint16_t _log_num_from_list_entry(const uint16_t list_entry);
|
||||||
|
|
||||||
// possibly time-consuming preparations handling
|
// possibly time-consuming preparations handling
|
||||||
|
@ -501,24 +501,6 @@ bool DataFlash_File::_WritePrioritisedBlock(const void *pBuffer, uint16_t size,
|
|||||||
return true;
|
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
|
find the highest log number
|
||||||
*/
|
*/
|
||||||
|
@ -78,11 +78,6 @@ private:
|
|||||||
uint16_t _cached_oldest_log;
|
uint16_t _cached_oldest_log;
|
||||||
uint16_t _last_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);
|
uint16_t _log_num_from_list_entry(const uint16_t list_entry);
|
||||||
|
|
||||||
// possibly time-consuming preparations handling
|
// possibly time-consuming preparations handling
|
||||||
|
@ -173,9 +173,6 @@ private:
|
|||||||
uint16_t start_new_log(void) override {
|
uint16_t start_new_log(void) override {
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
bool ReadBlock(void *pkt, uint16_t size) override {
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
// performance counters
|
// performance counters
|
||||||
AP_HAL::Util::perf_counter_t _perf_errors;
|
AP_HAL::Util::perf_counter_t _perf_errors;
|
||||||
AP_HAL::Util::perf_counter_t _perf_packing;
|
AP_HAL::Util::perf_counter_t _perf_packing;
|
||||||
|
Loading…
Reference in New Issue
Block a user