mirror of https://github.com/ArduPilot/ardupilot
DataFlash_File: cache oldest log to avoid directory scans when downloading
This commit is contained in:
parent
0b653bb82b
commit
fc05ad81eb
|
@ -56,6 +56,7 @@ DataFlash_File::DataFlash_File(DataFlash_Class &front, const char *log_directory
|
|||
_initialised(false),
|
||||
_open_error(false),
|
||||
_log_directory(log_directory),
|
||||
_cached_oldest_log(0),
|
||||
_writebuf(NULL),
|
||||
_writebuf_size(16*1024),
|
||||
#if defined(CONFIG_ARCH_BOARD_PX4FMU_V1)
|
||||
|
@ -229,6 +230,10 @@ float DataFlash_File::avail_space_percent()
|
|||
// returns 0 if no log was found
|
||||
uint16_t DataFlash_File::find_oldest_log()
|
||||
{
|
||||
if (_cached_oldest_log != 0) {
|
||||
return _cached_oldest_log;
|
||||
}
|
||||
|
||||
uint16_t last_log_num = find_last_log();
|
||||
if (last_log_num == 0) {
|
||||
return 0;
|
||||
|
@ -281,6 +286,7 @@ uint16_t DataFlash_File::find_oldest_log()
|
|||
}
|
||||
}
|
||||
closedir(d);
|
||||
_cached_oldest_log = current_oldest_log;
|
||||
|
||||
return current_oldest_log;
|
||||
}
|
||||
|
@ -293,6 +299,8 @@ void DataFlash_File::Prep_MinSpace()
|
|||
return;
|
||||
}
|
||||
|
||||
_cached_oldest_log = 0;
|
||||
|
||||
uint16_t log_to_remove = first_log_to_remove;
|
||||
|
||||
uint16_t count = 0;
|
||||
|
@ -407,6 +415,8 @@ void DataFlash_File::EraseAll()
|
|||
unlink(fname);
|
||||
free(fname);
|
||||
}
|
||||
|
||||
_cached_oldest_log = 0;
|
||||
}
|
||||
|
||||
/* Write a block of data at current offset */
|
||||
|
@ -584,7 +594,7 @@ void DataFlash_File::get_log_boundaries(const uint16_t list_entry, uint16_t & st
|
|||
}
|
||||
|
||||
/*
|
||||
find the number of pages in a log
|
||||
retrieve data from a log file
|
||||
*/
|
||||
int16_t DataFlash_File::get_log_data(const uint16_t list_entry, const uint16_t page, const uint32_t offset, const uint16_t len, uint8_t *data)
|
||||
{
|
||||
|
@ -738,6 +748,8 @@ uint16_t DataFlash_File::start_new_log(void)
|
|||
}
|
||||
char *fname = _log_file_name(log_num);
|
||||
_write_fd = ::open(fname, O_WRONLY|O_CREAT|O_TRUNC, 0666);
|
||||
_cached_oldest_log = 0;
|
||||
|
||||
if (_write_fd == -1) {
|
||||
_initialised = false;
|
||||
_open_error = true;
|
||||
|
|
|
@ -65,6 +65,8 @@ private:
|
|||
volatile bool _open_error;
|
||||
const char *_log_directory;
|
||||
|
||||
uint16_t _cached_oldest_log;
|
||||
|
||||
/*
|
||||
read a block
|
||||
*/
|
||||
|
|
Loading…
Reference in New Issue