mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
DataFlash: delete oldest file rather than the lowest-numbered file
Also reference log numbers by their list index to accomodate log number wrapping in DataFlash_File
This commit is contained in:
parent
ab7148386c
commit
e481497574
@ -49,7 +49,7 @@ uint16_t DataFlash_Class::bufferspace_available(void) {
|
|||||||
return backend->bufferspace_available();
|
return backend->bufferspace_available();
|
||||||
}
|
}
|
||||||
|
|
||||||
uint16_t DataFlash_Class::find_last_log(void) {
|
uint16_t DataFlash_Class::find_last_log() const {
|
||||||
return backend->find_last_log();
|
return backend->find_last_log();
|
||||||
}
|
}
|
||||||
void DataFlash_Class::get_log_boundaries(uint16_t log_num, uint16_t & start_page, uint16_t & end_page) {
|
void DataFlash_Class::get_log_boundaries(uint16_t log_num, uint16_t & start_page, uint16_t & end_page) {
|
||||||
|
@ -63,7 +63,7 @@ public:
|
|||||||
bool WriteCriticalBlock(const void *pBuffer, uint16_t size);
|
bool WriteCriticalBlock(const void *pBuffer, uint16_t size);
|
||||||
|
|
||||||
// high level interface
|
// high level interface
|
||||||
uint16_t find_last_log(void);
|
uint16_t find_last_log() const;
|
||||||
void get_log_boundaries(uint16_t log_num, uint16_t & start_page, uint16_t & end_page);
|
void get_log_boundaries(uint16_t log_num, uint16_t & start_page, uint16_t & end_page);
|
||||||
void get_log_info(uint16_t log_num, uint32_t &size, uint32_t &time_utc);
|
void get_log_info(uint16_t log_num, uint32_t &size, uint32_t &time_utc);
|
||||||
int16_t get_log_data(uint16_t log_num, uint16_t page, uint32_t offset, uint16_t len, uint8_t *data);
|
int16_t get_log_data(uint16_t log_num, uint16_t page, uint32_t offset, uint16_t len, uint8_t *data);
|
||||||
|
@ -43,13 +43,13 @@ public:
|
|||||||
virtual bool WritePrioritisedBlock(const void *pBuffer, uint16_t size, bool is_critical) = 0;
|
virtual bool WritePrioritisedBlock(const void *pBuffer, uint16_t size, bool is_critical) = 0;
|
||||||
|
|
||||||
// high level interface
|
// high level interface
|
||||||
virtual uint16_t find_last_log(void) = 0;
|
virtual uint16_t find_last_log() = 0;
|
||||||
virtual void get_log_boundaries(uint16_t log_num, uint16_t & start_page, uint16_t & end_page) = 0;
|
virtual void get_log_boundaries(uint16_t log_num, uint16_t & start_page, uint16_t & end_page) = 0;
|
||||||
virtual void get_log_info(uint16_t log_num, uint32_t &size, uint32_t &time_utc) = 0;
|
virtual void get_log_info(uint16_t log_num, uint32_t &size, uint32_t &time_utc) = 0;
|
||||||
virtual int16_t get_log_data(uint16_t log_num, uint16_t page, uint32_t offset, uint16_t len, uint8_t *data) = 0;
|
virtual int16_t get_log_data(uint16_t log_num, uint16_t page, uint32_t offset, uint16_t len, uint8_t *data) = 0;
|
||||||
virtual uint16_t get_num_logs(void) = 0;
|
virtual uint16_t get_num_logs() = 0;
|
||||||
#ifndef DATAFLASH_NO_CLI
|
#ifndef DATAFLASH_NO_CLI
|
||||||
virtual void LogReadProcess(uint16_t log_num,
|
virtual void LogReadProcess(const uint16_t list_entry,
|
||||||
uint16_t start_page, uint16_t end_page,
|
uint16_t start_page, uint16_t end_page,
|
||||||
print_mode_fn printMode,
|
print_mode_fn printMode,
|
||||||
AP_HAL::BetterStream *port) = 0;
|
AP_HAL::BetterStream *port) = 0;
|
||||||
|
@ -31,15 +31,15 @@ public:
|
|||||||
bool WritePrioritisedBlock(const void *pBuffer, uint16_t size, bool is_critical);
|
bool WritePrioritisedBlock(const void *pBuffer, uint16_t size, bool is_critical);
|
||||||
|
|
||||||
// high level interface
|
// high level interface
|
||||||
uint16_t find_last_log(void);
|
uint16_t find_last_log() override;
|
||||||
void get_log_boundaries(uint16_t log_num, uint16_t & start_page, uint16_t & end_page);
|
void get_log_boundaries(uint16_t log_num, uint16_t & start_page, uint16_t & end_page);
|
||||||
void get_log_info(uint16_t log_num, uint32_t &size, uint32_t &time_utc);
|
void get_log_info(uint16_t log_num, uint32_t &size, uint32_t &time_utc);
|
||||||
int16_t get_log_data_raw(uint16_t log_num, uint16_t page, uint32_t offset, uint16_t len, uint8_t *data);
|
int16_t get_log_data_raw(uint16_t log_num, uint16_t page, uint32_t offset, uint16_t len, uint8_t *data);
|
||||||
int16_t get_log_data(uint16_t log_num, uint16_t page, uint32_t offset, uint16_t len, uint8_t *data);
|
int16_t get_log_data(uint16_t log_num, uint16_t page, uint32_t offset, uint16_t len, uint8_t *data);
|
||||||
uint16_t get_num_logs(void);
|
uint16_t get_num_logs() override;
|
||||||
uint16_t start_new_log(void);
|
uint16_t start_new_log(void);
|
||||||
#ifndef DATAFLASH_NO_CLI
|
#ifndef DATAFLASH_NO_CLI
|
||||||
void LogReadProcess(uint16_t log_num,
|
void LogReadProcess(const uint16_t list_entry,
|
||||||
uint16_t start_page, uint16_t end_page,
|
uint16_t start_page, uint16_t end_page,
|
||||||
print_mode_fn print_mode,
|
print_mode_fn print_mode,
|
||||||
AP_HAL::BetterStream *port);
|
AP_HAL::BetterStream *port);
|
||||||
|
@ -5,6 +5,11 @@
|
|||||||
|
|
||||||
This uses posix file IO to create log files called logs/NN.bin in the
|
This uses posix file IO to create log files called logs/NN.bin in the
|
||||||
given directory
|
given directory
|
||||||
|
|
||||||
|
SD Card Rates on PixHawk:
|
||||||
|
- deletion rate seems to be ~50 files/second.
|
||||||
|
- stat seems to be ~150/second
|
||||||
|
- readdir loop of 511 entry directory ~62,000 microseconds
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
@ -141,6 +146,29 @@ void DataFlash_File::Init(const struct LogStructure *structure, uint8_t num_type
|
|||||||
hal.scheduler->register_io_process(FUNCTOR_BIND_MEMBER(&DataFlash_File::_io_timer, void));
|
hal.scheduler->register_io_process(FUNCTOR_BIND_MEMBER(&DataFlash_File::_io_timer, void));
|
||||||
}
|
}
|
||||||
|
|
||||||
|
bool DataFlash_File::file_exists(const char *filename) const
|
||||||
|
{
|
||||||
|
struct stat st;
|
||||||
|
if (stat(filename, &st) == -1) {
|
||||||
|
// hopefully errno==ENOENT. If some error occurs it is
|
||||||
|
// probably better to assume this file exists.
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool DataFlash_File::log_exists(const uint16_t lognum) const
|
||||||
|
{
|
||||||
|
char *filename = _log_file_name(lognum);
|
||||||
|
if (filename == NULL) {
|
||||||
|
// internal_error();
|
||||||
|
return false; // ?!
|
||||||
|
}
|
||||||
|
bool ret = file_exists(filename);
|
||||||
|
free(filename);
|
||||||
|
return ret;
|
||||||
|
}
|
||||||
|
|
||||||
void DataFlash_File::periodic_fullrate(const uint32_t now)
|
void DataFlash_File::periodic_fullrate(const uint32_t now)
|
||||||
{
|
{
|
||||||
DataFlash_Backend::push_log_blocks();
|
DataFlash_Backend::push_log_blocks();
|
||||||
@ -158,37 +186,56 @@ bool DataFlash_File::CardInserted(void)
|
|||||||
return _initialised && !_open_error;
|
return _initialised && !_open_error;
|
||||||
}
|
}
|
||||||
|
|
||||||
uint64_t DataFlash_File::disk_space_avail()
|
// returns the amount of disk space available in _log_directory (in bytes)
|
||||||
|
// returns -1 on error
|
||||||
|
int64_t DataFlash_File::disk_space_avail()
|
||||||
{
|
{
|
||||||
struct statfs stats;
|
struct statfs stats;
|
||||||
if (statfs(_log_directory, &stats) < 0) {
|
if (statfs(_log_directory, &stats) < 0) {
|
||||||
return -1;
|
return -1;
|
||||||
}
|
}
|
||||||
return (((uint64_t)stats.f_bavail) * stats.f_bsize);
|
return (((int64_t)stats.f_bavail) * stats.f_bsize);
|
||||||
}
|
}
|
||||||
|
|
||||||
uint64_t DataFlash_File::disk_space()
|
// returns the total amount of disk space (in use + available) in
|
||||||
|
// _log_directory (in bytes).
|
||||||
|
// returns -1 on error
|
||||||
|
int64_t DataFlash_File::disk_space()
|
||||||
{
|
{
|
||||||
struct statfs stats;
|
struct statfs stats;
|
||||||
if (statfs(_log_directory, &stats) < 0) {
|
if (statfs(_log_directory, &stats) < 0) {
|
||||||
return -1;
|
return -1;
|
||||||
}
|
}
|
||||||
return (((uint64_t)stats.f_blocks) * stats.f_bsize);
|
return (((int64_t)stats.f_blocks) * stats.f_bsize);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// returns the available space in _log_directory as a percentage
|
||||||
|
// returns -1.0f on error
|
||||||
float DataFlash_File::avail_space_percent()
|
float DataFlash_File::avail_space_percent()
|
||||||
{
|
{
|
||||||
uint64_t avail = disk_space_avail();
|
int64_t avail = disk_space_avail();
|
||||||
uint64_t space = disk_space();
|
if (avail == -1) {
|
||||||
|
return -1.0f;
|
||||||
|
}
|
||||||
|
int64_t space = disk_space();
|
||||||
|
if (space == -1) {
|
||||||
|
return -1.0f;
|
||||||
|
}
|
||||||
|
|
||||||
return (avail/(float)space) * 100;
|
return (avail/(float)space) * 100;
|
||||||
}
|
}
|
||||||
|
|
||||||
// find_first_log - find lowest-numbered log in _log_directory
|
// find_oldest_log - find oldest log in _log_directory
|
||||||
// returns 0 if no log was found
|
// returns 0 if no log was found
|
||||||
uint16_t DataFlash_File::find_first_log(void)
|
uint16_t DataFlash_File::find_oldest_log()
|
||||||
{
|
{
|
||||||
// iterate through directory entries to find lowest log number.
|
uint16_t last_log_num = find_last_log();
|
||||||
|
if (last_log_num == 0) {
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
uint16_t current_oldest_log = 0; // 0 is invalid
|
||||||
|
|
||||||
// We could count up to find_last_log(), but if people start
|
// We could count up to find_last_log(), but if people start
|
||||||
// relying on the min_avail_space_percent feature we could end up
|
// relying on the min_avail_space_percent feature we could end up
|
||||||
// doing a *lot* of asprintf()s and stat()s
|
// doing a *lot* of asprintf()s and stat()s
|
||||||
@ -199,7 +246,6 @@ uint16_t DataFlash_File::find_first_log(void)
|
|||||||
}
|
}
|
||||||
|
|
||||||
// we only remove files which look like xxx.BIN
|
// we only remove files which look like xxx.BIN
|
||||||
uint32_t lowest_number = (uint32_t)-1; // unsigned integer wrap
|
|
||||||
for (struct dirent *de=readdir(d); de; de=readdir(d)) {
|
for (struct dirent *de=readdir(d); de; de=readdir(d)) {
|
||||||
uint8_t length = strlen(de->d_name);
|
uint8_t length = strlen(de->d_name);
|
||||||
if (length < 5) {
|
if (length < 5) {
|
||||||
@ -212,30 +258,55 @@ uint16_t DataFlash_File::find_first_log(void)
|
|||||||
}
|
}
|
||||||
|
|
||||||
uint16_t thisnum = strtoul(de->d_name, NULL, 10);
|
uint16_t thisnum = strtoul(de->d_name, NULL, 10);
|
||||||
if (thisnum < lowest_number) {
|
if (thisnum > MAX_LOG_FILES) {
|
||||||
lowest_number = thisnum;
|
// ignore files above our official maximum...
|
||||||
|
continue;
|
||||||
|
}
|
||||||
|
if (current_oldest_log == 0) {
|
||||||
|
current_oldest_log = thisnum;
|
||||||
|
} else {
|
||||||
|
if (current_oldest_log <= last_log_num) {
|
||||||
|
if (thisnum > last_log_num) {
|
||||||
|
current_oldest_log = thisnum;
|
||||||
|
} else if (thisnum < current_oldest_log) {
|
||||||
|
current_oldest_log = thisnum;
|
||||||
|
}
|
||||||
|
} else { // current_oldest_log > last_log_num
|
||||||
|
if (thisnum > last_log_num) {
|
||||||
|
if (thisnum < current_oldest_log) {
|
||||||
|
current_oldest_log = thisnum;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
closedir(d);
|
closedir(d);
|
||||||
|
|
||||||
if (lowest_number == (uint32_t)-1) {
|
return current_oldest_log;
|
||||||
return 0;
|
|
||||||
}
|
|
||||||
return lowest_number;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void DataFlash_File::Prep_MinSpace()
|
void DataFlash_File::Prep_MinSpace()
|
||||||
{
|
{
|
||||||
uint16_t log_to_remove = find_first_log();
|
const uint16_t first_log_to_remove = find_oldest_log();
|
||||||
if (log_to_remove == 0) {
|
if (first_log_to_remove == 0) {
|
||||||
// no files to remove
|
// no files to remove
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
uint16_t log_to_remove = first_log_to_remove;
|
||||||
|
|
||||||
uint16_t count = 0;
|
uint16_t count = 0;
|
||||||
while (avail_space_percent() < min_avail_space_percent) {
|
do {
|
||||||
if (count++ > 500) {
|
float avail = avail_space_percent();
|
||||||
|
if (is_equal(avail, -1.0f)) {
|
||||||
|
// internal_error()
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
if (avail >= min_avail_space_percent) {
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
if (count++ > MAX_LOG_FILES+10) {
|
||||||
// *way* too many deletions going on here. Possible internal error.
|
// *way* too many deletions going on here. Possible internal error.
|
||||||
// deletion rate seems to be ~50 files/second.
|
|
||||||
// internal_error();
|
// internal_error();
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
@ -244,28 +315,29 @@ void DataFlash_File::Prep_MinSpace()
|
|||||||
// internal_error();
|
// internal_error();
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
hal.console->printf("Removing (%s) for minimum-space requirements\n",
|
if (file_exists(filename_to_remove)) {
|
||||||
filename_to_remove);
|
hal.console->printf("Removing (%s) for minimum-space requirements (%.2f%% < %.0f%%)\n",
|
||||||
if (unlink(filename_to_remove) == -1) {
|
filename_to_remove, avail, min_avail_space_percent);
|
||||||
hal.console->printf("Failed to remove %s: (%d/%d) %s\n", filename_to_remove, errno, ENOENT, strerror(errno));
|
if (unlink(filename_to_remove) == -1) {
|
||||||
free(filename_to_remove);
|
hal.console->printf("Failed to remove %s: %s\n", filename_to_remove, strerror(errno));
|
||||||
if (errno == ENOENT) {
|
free(filename_to_remove);
|
||||||
log_to_remove = find_first_log();
|
if (errno == ENOENT) {
|
||||||
if (log_to_remove == 0) {
|
// corruption - should always have a continuous
|
||||||
// out of files to remove...
|
// sequence of files... however, there may be still
|
||||||
|
// files out there, so keep going.
|
||||||
|
} else {
|
||||||
|
// internal_error();
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
// corruption - should always have a continuous
|
|
||||||
// sequence of files... however, we now have a file
|
|
||||||
// we can delete, so keep going.
|
|
||||||
} else {
|
} else {
|
||||||
break;
|
free(filename_to_remove);
|
||||||
}
|
}
|
||||||
} else {
|
|
||||||
free(filename_to_remove);
|
|
||||||
log_to_remove++;
|
|
||||||
}
|
}
|
||||||
}
|
log_to_remove++;
|
||||||
|
if (log_to_remove > MAX_LOG_FILES) {
|
||||||
|
log_to_remove = 1;
|
||||||
|
}
|
||||||
|
} while (log_to_remove != first_log_to_remove);
|
||||||
}
|
}
|
||||||
|
|
||||||
void DataFlash_File::Prep() {
|
void DataFlash_File::Prep() {
|
||||||
@ -294,7 +366,7 @@ bool DataFlash_File::NeedPrep()
|
|||||||
construct a log file name given a log number.
|
construct a log file name given a log number.
|
||||||
Note: Caller must free.
|
Note: Caller must free.
|
||||||
*/
|
*/
|
||||||
char *DataFlash_File::_log_file_name(uint16_t log_num)
|
char *DataFlash_File::_log_file_name(const uint16_t log_num) const
|
||||||
{
|
{
|
||||||
char *buf = NULL;
|
char *buf = NULL;
|
||||||
if (asprintf(&buf, "%s/%u.BIN", _log_directory, (unsigned)log_num) == 0) {
|
if (asprintf(&buf, "%s/%u.BIN", _log_directory, (unsigned)log_num) == 0) {
|
||||||
@ -307,7 +379,7 @@ char *DataFlash_File::_log_file_name(uint16_t log_num)
|
|||||||
return path name of the lastlog.txt marker file
|
return path name of the lastlog.txt marker file
|
||||||
Note: Caller must free.
|
Note: Caller must free.
|
||||||
*/
|
*/
|
||||||
char *DataFlash_File::_lastlog_file_name(void)
|
char *DataFlash_File::_lastlog_file_name(void) const
|
||||||
{
|
{
|
||||||
char *buf = NULL;
|
char *buf = NULL;
|
||||||
if (asprintf(&buf, "%s/LASTLOG.TXT", _log_directory) == 0) {
|
if (asprintf(&buf, "%s/LASTLOG.TXT", _log_directory) == 0) {
|
||||||
@ -322,7 +394,7 @@ void DataFlash_File::EraseAll()
|
|||||||
{
|
{
|
||||||
uint16_t log_num;
|
uint16_t log_num;
|
||||||
stop_logging();
|
stop_logging();
|
||||||
for (log_num=0; log_num<MAX_LOG_FILES; log_num++) {
|
for (log_num=1; log_num<=MAX_LOG_FILES; log_num++) {
|
||||||
char *fname = _log_file_name(log_num);
|
char *fname = _log_file_name(log_num);
|
||||||
if (fname == NULL) {
|
if (fname == NULL) {
|
||||||
break;
|
break;
|
||||||
@ -421,7 +493,7 @@ bool DataFlash_File::ReadBlock(void *pkt, uint16_t size)
|
|||||||
/*
|
/*
|
||||||
find the highest log number
|
find the highest log number
|
||||||
*/
|
*/
|
||||||
uint16_t DataFlash_File::find_last_log(void)
|
uint16_t DataFlash_File::find_last_log()
|
||||||
{
|
{
|
||||||
unsigned ret = 0;
|
unsigned ret = 0;
|
||||||
char *fname = _lastlog_file_name();
|
char *fname = _lastlog_file_name();
|
||||||
@ -442,20 +514,7 @@ uint16_t DataFlash_File::find_last_log(void)
|
|||||||
return ret;
|
return ret;
|
||||||
}
|
}
|
||||||
|
|
||||||
bool DataFlash_File::_log_exists(uint16_t log_num)
|
uint32_t DataFlash_File::_get_log_size(const uint16_t log_num) const
|
||||||
{
|
|
||||||
char *fname = _log_file_name(log_num);
|
|
||||||
if (fname == NULL) {
|
|
||||||
return 0;
|
|
||||||
}
|
|
||||||
struct stat st;
|
|
||||||
// stat return 0 if the file exists:
|
|
||||||
bool ret = ::stat(fname, &st) ? false : true;
|
|
||||||
free(fname);
|
|
||||||
return ret;
|
|
||||||
}
|
|
||||||
|
|
||||||
uint32_t DataFlash_File::_get_log_size(uint16_t log_num)
|
|
||||||
{
|
{
|
||||||
char *fname = _log_file_name(log_num);
|
char *fname = _log_file_name(log_num);
|
||||||
if (fname == NULL) {
|
if (fname == NULL) {
|
||||||
@ -470,7 +529,7 @@ uint32_t DataFlash_File::_get_log_size(uint16_t log_num)
|
|||||||
return st.st_size;
|
return st.st_size;
|
||||||
}
|
}
|
||||||
|
|
||||||
uint32_t DataFlash_File::_get_log_time(uint16_t log_num)
|
uint32_t DataFlash_File::_get_log_time(const uint16_t log_num) const
|
||||||
{
|
{
|
||||||
char *fname = _log_file_name(log_num);
|
char *fname = _log_file_name(log_num);
|
||||||
if (fname == NULL) {
|
if (fname == NULL) {
|
||||||
@ -485,11 +544,41 @@ uint32_t DataFlash_File::_get_log_time(uint16_t log_num)
|
|||||||
return st.st_mtime;
|
return st.st_mtime;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/*
|
||||||
|
convert a list entry number back into a log number (which can then
|
||||||
|
be converted into a filename). A "list entry number" is a sequence
|
||||||
|
where the oldest log has a number of 1, the second-from-oldest 2,
|
||||||
|
and so on. Thus the highest list entry number is equal to the
|
||||||
|
number of logs.
|
||||||
|
*/
|
||||||
|
uint16_t DataFlash_File::_log_num_from_list_entry(const uint16_t list_entry)
|
||||||
|
{
|
||||||
|
uint16_t oldest_log = find_oldest_log();
|
||||||
|
if (oldest_log == 0) {
|
||||||
|
// We don't have any logs...
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
uint32_t log_num = oldest_log + list_entry - 1;
|
||||||
|
if (log_num > MAX_LOG_FILES) {
|
||||||
|
log_num -= MAX_LOG_FILES;
|
||||||
|
}
|
||||||
|
return (uint16_t)log_num;
|
||||||
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
find the number of pages in a log
|
find the number of pages in a log
|
||||||
*/
|
*/
|
||||||
void DataFlash_File::get_log_boundaries(uint16_t log_num, uint16_t & start_page, uint16_t & end_page)
|
void DataFlash_File::get_log_boundaries(const uint16_t list_entry, uint16_t & start_page, uint16_t & end_page)
|
||||||
{
|
{
|
||||||
|
const uint16_t log_num = _log_num_from_list_entry(list_entry);
|
||||||
|
if (log_num == 0) {
|
||||||
|
// that failed - probably no logs
|
||||||
|
start_page = 0;
|
||||||
|
end_page = 0;
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
start_page = 0;
|
start_page = 0;
|
||||||
end_page = _get_log_size(log_num) / DATAFLASH_PAGE_SIZE;
|
end_page = _get_log_size(log_num) / DATAFLASH_PAGE_SIZE;
|
||||||
}
|
}
|
||||||
@ -497,11 +586,18 @@ void DataFlash_File::get_log_boundaries(uint16_t log_num, uint16_t & start_page,
|
|||||||
/*
|
/*
|
||||||
find the number of pages in a log
|
find the number of pages in a log
|
||||||
*/
|
*/
|
||||||
int16_t DataFlash_File::get_log_data(uint16_t log_num, uint16_t page, uint32_t offset, uint16_t len, uint8_t *data)
|
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)
|
||||||
{
|
{
|
||||||
if (!_initialised || _open_error) {
|
if (!_initialised || _open_error) {
|
||||||
return -1;
|
return -1;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
const uint16_t log_num = _log_num_from_list_entry(list_entry);
|
||||||
|
if (log_num == 0) {
|
||||||
|
// that failed - probably no logs
|
||||||
|
return -1;
|
||||||
|
}
|
||||||
|
|
||||||
if (_read_fd != -1 && log_num != _read_fd_log_num) {
|
if (_read_fd != -1 && log_num != _read_fd_log_num) {
|
||||||
::close(_read_fd);
|
::close(_read_fd);
|
||||||
_read_fd = -1;
|
_read_fd = -1;
|
||||||
@ -559,8 +655,16 @@ int16_t DataFlash_File::get_log_data(uint16_t log_num, uint16_t page, uint32_t o
|
|||||||
/*
|
/*
|
||||||
find size and date of a log
|
find size and date of a log
|
||||||
*/
|
*/
|
||||||
void DataFlash_File::get_log_info(uint16_t log_num, uint32_t &size, uint32_t &time_utc)
|
void DataFlash_File::get_log_info(const uint16_t list_entry, uint32_t &size, uint32_t &time_utc)
|
||||||
{
|
{
|
||||||
|
uint16_t log_num = _log_num_from_list_entry(list_entry);
|
||||||
|
if (log_num == 0) {
|
||||||
|
// that failed - probably no logs
|
||||||
|
size = 0;
|
||||||
|
time_utc = 0;
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
size = _get_log_size(log_num);
|
size = _get_log_size(log_num);
|
||||||
time_utc = _get_log_time(log_num);
|
time_utc = _get_log_time(log_num);
|
||||||
}
|
}
|
||||||
@ -570,14 +674,24 @@ void DataFlash_File::get_log_info(uint16_t log_num, uint32_t &size, uint32_t &ti
|
|||||||
/*
|
/*
|
||||||
get the number of logs - note that the log numbers must be consecutive
|
get the number of logs - note that the log numbers must be consecutive
|
||||||
*/
|
*/
|
||||||
uint16_t DataFlash_File::get_num_logs(void)
|
uint16_t DataFlash_File::get_num_logs()
|
||||||
{
|
{
|
||||||
uint16_t ret;
|
uint16_t ret = 0;
|
||||||
uint16_t high = find_last_log();
|
uint16_t high = find_last_log();
|
||||||
for (ret=0; ret<high; ret++) {
|
uint16_t i;
|
||||||
if (!_log_exists(high - ret)) {
|
for (i=high; i>0; i--) {
|
||||||
|
if (! log_exists(i)) {
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
ret++;
|
||||||
|
}
|
||||||
|
if (i == 0) {
|
||||||
|
for (i=MAX_LOG_FILES; i>high; i--) {
|
||||||
|
if (! log_exists(i)) {
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
ret++;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
return ret;
|
return ret;
|
||||||
}
|
}
|
||||||
@ -654,7 +768,7 @@ uint16_t DataFlash_File::start_new_log(void)
|
|||||||
/*
|
/*
|
||||||
Read the log and print it on port
|
Read the log and print it on port
|
||||||
*/
|
*/
|
||||||
void DataFlash_File::LogReadProcess(uint16_t log_num,
|
void DataFlash_File::LogReadProcess(const uint16_t list_entry,
|
||||||
uint16_t start_page, uint16_t end_page,
|
uint16_t start_page, uint16_t end_page,
|
||||||
print_mode_fn print_mode,
|
print_mode_fn print_mode,
|
||||||
AP_HAL::BetterStream *port)
|
AP_HAL::BetterStream *port)
|
||||||
@ -663,6 +777,12 @@ void DataFlash_File::LogReadProcess(uint16_t log_num,
|
|||||||
if (!_initialised || _open_error) {
|
if (!_initialised || _open_error) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
const uint16_t log_num = _log_num_from_list_entry(list_entry);
|
||||||
|
if (log_num == 0) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
if (_read_fd != -1) {
|
if (_read_fd != -1) {
|
||||||
::close(_read_fd);
|
::close(_read_fd);
|
||||||
_read_fd = -1;
|
_read_fd = -1;
|
||||||
@ -752,7 +872,6 @@ void DataFlash_File::ShowDeviceInfo(AP_HAL::BetterStream *port)
|
|||||||
void DataFlash_File::ListAvailableLogs(AP_HAL::BetterStream *port)
|
void DataFlash_File::ListAvailableLogs(AP_HAL::BetterStream *port)
|
||||||
{
|
{
|
||||||
uint16_t num_logs = get_num_logs();
|
uint16_t num_logs = get_num_logs();
|
||||||
int16_t last_log_num = find_last_log();
|
|
||||||
|
|
||||||
if (num_logs == 0) {
|
if (num_logs == 0) {
|
||||||
port->printf_P(PSTR("\nNo logs\n\n"));
|
port->printf_P(PSTR("\nNo logs\n\n"));
|
||||||
@ -760,20 +879,17 @@ void DataFlash_File::ListAvailableLogs(AP_HAL::BetterStream *port)
|
|||||||
}
|
}
|
||||||
port->printf_P(PSTR("\n%u logs\n"), (unsigned)num_logs);
|
port->printf_P(PSTR("\n%u logs\n"), (unsigned)num_logs);
|
||||||
|
|
||||||
for (uint16_t i=num_logs; i>=1; i--) {
|
for (uint16_t i=1; i<=num_logs; i++) {
|
||||||
uint16_t log_num = last_log_num - i + 1;
|
uint16_t log_num = _log_num_from_list_entry(i);
|
||||||
off_t size;
|
|
||||||
|
|
||||||
char *filename = _log_file_name(log_num);
|
char *filename = _log_file_name(log_num);
|
||||||
if (filename != NULL) {
|
if (filename != NULL) {
|
||||||
size = _get_log_size(log_num);
|
|
||||||
struct stat st;
|
struct stat st;
|
||||||
if (stat(filename, &st) == 0) {
|
if (stat(filename, &st) == 0) {
|
||||||
struct tm *tm = gmtime(&st.st_mtime);
|
struct tm *tm = gmtime(&st.st_mtime);
|
||||||
port->printf_P(PSTR("Log %u in %s of size %u %u/%u/%u %u:%u\n"),
|
port->printf_P(PSTR("Log %u in %s of size %u %u/%u/%u %u:%u\n"),
|
||||||
(unsigned)log_num,
|
(unsigned)i,
|
||||||
filename,
|
filename,
|
||||||
(unsigned)size,
|
(unsigned)st.st_size,
|
||||||
(unsigned)tm->tm_year+1900,
|
(unsigned)tm->tm_year+1900,
|
||||||
(unsigned)tm->tm_mon+1,
|
(unsigned)tm->tm_mon+1,
|
||||||
(unsigned)tm->tm_mday,
|
(unsigned)tm->tm_mday,
|
||||||
|
@ -36,14 +36,13 @@ public:
|
|||||||
uint16_t bufferspace_available();
|
uint16_t bufferspace_available();
|
||||||
|
|
||||||
// high level interface
|
// high level interface
|
||||||
uint16_t find_last_log(void);
|
uint16_t find_last_log() override;
|
||||||
void get_log_boundaries(uint16_t log_num, uint16_t & start_page, uint16_t & end_page);
|
void get_log_boundaries(uint16_t log_num, uint16_t & start_page, uint16_t & end_page);
|
||||||
void get_log_info(uint16_t log_num, uint32_t &size, uint32_t &time_utc);
|
void get_log_info(uint16_t log_num, uint32_t &size, uint32_t &time_utc);
|
||||||
int16_t get_log_data(uint16_t log_num, uint16_t page, uint32_t offset, uint16_t len, uint8_t *data);
|
int16_t get_log_data(uint16_t log_num, uint16_t page, uint32_t offset, uint16_t len, uint8_t *data);
|
||||||
uint16_t get_num_logs(void);
|
uint16_t get_num_logs() override;
|
||||||
bool _log_exists(uint16_t log_num);
|
|
||||||
uint16_t start_new_log(void);
|
uint16_t start_new_log(void);
|
||||||
void LogReadProcess(uint16_t log_num,
|
void LogReadProcess(const uint16_t log_num,
|
||||||
uint16_t start_page, uint16_t end_page,
|
uint16_t start_page, uint16_t end_page,
|
||||||
print_mode_fn print_mode,
|
print_mode_fn print_mode,
|
||||||
AP_HAL::BetterStream *port);
|
AP_HAL::BetterStream *port);
|
||||||
@ -71,13 +70,18 @@ private:
|
|||||||
*/
|
*/
|
||||||
bool ReadBlock(void *pkt, uint16_t size);
|
bool ReadBlock(void *pkt, uint16_t size);
|
||||||
|
|
||||||
|
uint16_t _log_num_from_list_entry(const uint16_t list_entry);
|
||||||
|
|
||||||
// possibly time-consuming preparations handling
|
// possibly time-consuming preparations handling
|
||||||
void Prep_MinSpace();
|
void Prep_MinSpace();
|
||||||
uint16_t find_first_log(void);
|
uint16_t find_oldest_log();
|
||||||
uint64_t disk_space_avail();
|
int64_t disk_space_avail();
|
||||||
uint64_t disk_space();
|
int64_t disk_space();
|
||||||
float avail_space_percent();
|
float avail_space_percent();
|
||||||
|
|
||||||
|
bool file_exists(const char *filename) const;
|
||||||
|
bool log_exists(const uint16_t lognum) const;
|
||||||
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL || CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL || CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
||||||
// I always seem to have less than 10% free space on my laptop:
|
// I always seem to have less than 10% free space on my laptop:
|
||||||
const float min_avail_space_percent = 0.1f;
|
const float min_avail_space_percent = 0.1f;
|
||||||
@ -93,10 +97,10 @@ private:
|
|||||||
uint32_t _last_write_time;
|
uint32_t _last_write_time;
|
||||||
|
|
||||||
/* construct a file name given a log number. Caller must free. */
|
/* construct a file name given a log number. Caller must free. */
|
||||||
char *_log_file_name(uint16_t log_num);
|
char *_log_file_name(const uint16_t log_num) const;
|
||||||
char *_lastlog_file_name(void);
|
char *_lastlog_file_name() const;
|
||||||
uint32_t _get_log_size(uint16_t log_num);
|
uint32_t _get_log_size(const uint16_t log_num) const;
|
||||||
uint32_t _get_log_time(uint16_t log_num);
|
uint32_t _get_log_time(const uint16_t log_num) const;
|
||||||
|
|
||||||
void stop_logging(void);
|
void stop_logging(void);
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user