DataFlash: correct zero-byte-file handling in CLI

-rw-rw-r-- 1 pbarker pbarker   2105344 Jul  1 16:10 1.BIN
-rw-rw-r-- 1 pbarker pbarker         0 Jul  1 19:35 2.BIN
-rw-rw-r-- 1 pbarker pbarker   2494464 Jul  1 16:58 3.BIN
-rw-rw-r-- 1 pbarker pbarker 128503808 Jul  1 20:22 4.BIN
-rw-rw-r-- 1 pbarker pbarker         3 Jul  1 19:46 LASTLOG.TXT

Before fix:

2 logs
Log 3 in logs/3.BIN of size 2494464 2015/7/1 6:58
Log 4 in logs/4.BIN of size 128503808 2015/7/1 10:22

After Fix:

4 logs
Log 1 in logs/1.BIN of size 2105344 2015/7/1 6:10
Log 2 in logs/2.BIN of size 0 2015/7/1 9:35
Log 3 in logs/3.BIN of size 2494464 2015/7/1 6:58
Log 4 in logs/4.BIN of size 128503808 2015/7/1 10:22

If the last file was zero bytes, no files would be shown.
This commit is contained in:
Peter Barker 2015-07-01 20:22:53 +10:00 committed by Andrew Tridgell
parent 89baeb0c78
commit 844f050cf3
2 changed files with 14 additions and 3 deletions

View File

@ -274,6 +274,18 @@ uint16_t DataFlash_File::find_last_log(void)
return ret;
}
bool DataFlash_File::_log_exists(uint16_t log_num)
{
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)
{
@ -395,7 +407,7 @@ uint16_t DataFlash_File::get_num_logs(void)
uint16_t ret;
uint16_t high = find_last_log();
for (ret=0; ret<high; ret++) {
if (_get_log_size(high - ret) <= 0) {
if (!_log_exists(high - ret)) {
break;
}
}
@ -587,7 +599,6 @@ void DataFlash_File::ListAvailableLogs(AP_HAL::BetterStream *port)
char *filename = _log_file_name(log_num);
if (filename != NULL) {
size = _get_log_size(log_num);
if (size != 0) {
struct stat st;
if (stat(filename, &st) == 0) {
struct tm *tm = gmtime(&st.st_mtime);
@ -601,7 +612,6 @@ void DataFlash_File::ListAvailableLogs(AP_HAL::BetterStream *port)
(unsigned)tm->tm_hour,
(unsigned)tm->tm_min);
}
}
free(filename);
}
}

View File

@ -44,6 +44,7 @@ public:
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);
uint16_t get_num_logs(void);
bool _log_exists(uint16_t log_num);
uint16_t start_new_log(void);
void LogReadProcess(uint16_t log_num,
uint16_t start_page, uint16_t end_page,