mirror of https://github.com/ArduPilot/ardupilot
DataFlash: added functions for load download support
This commit is contained in:
parent
d034a4108b
commit
5d53b780ba
|
@ -29,6 +29,8 @@ public:
|
|||
// high level interface
|
||||
virtual uint16_t find_last_log(void) = 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 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 void LogReadProcess(uint16_t log_num,
|
||||
uint16_t start_page, uint16_t end_page,
|
||||
|
|
|
@ -88,6 +88,9 @@ void DataFlash_Block::StartRead(uint16_t PageAdr)
|
|||
df_Read_BufferNum = 0;
|
||||
df_Read_PageAdr = PageAdr;
|
||||
|
||||
// disable writing while reading
|
||||
log_write_started = false;
|
||||
|
||||
WaitReady();
|
||||
|
||||
// copy flash page to buffer
|
||||
|
@ -181,3 +184,24 @@ bool DataFlash_Block::NeedErase(void)
|
|||
StartRead(1);
|
||||
return version != DF_LOGGING_FORMAT;
|
||||
}
|
||||
|
||||
/*
|
||||
find the number of pages in a log
|
||||
*/
|
||||
int16_t DataFlash_Block::get_log_data(uint16_t log_num, uint16_t page, uint32_t offset, uint16_t len, uint8_t *data)
|
||||
{
|
||||
uint16_t data_page_size = df_PageSize - sizeof(struct PageHeader);
|
||||
if (offset >= data_page_size) {
|
||||
page += offset / data_page_size;
|
||||
offset = offset % data_page_size;
|
||||
page = page % df_NumPages;
|
||||
}
|
||||
if (log_write_started || df_Read_PageAdr != page) {
|
||||
StartRead(page);
|
||||
}
|
||||
|
||||
df_Read_BufferIdx = offset + sizeof(struct PageHeader);
|
||||
ReadBlock(data, len);
|
||||
return (int16_t)len;
|
||||
}
|
||||
|
||||
|
|
|
@ -26,6 +26,8 @@ public:
|
|||
// high level interface
|
||||
uint16_t find_last_log(void);
|
||||
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);
|
||||
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 start_new_log(void);
|
||||
void LogReadProcess(uint16_t log_num,
|
||||
|
|
|
@ -227,6 +227,21 @@ uint32_t DataFlash_File::_get_log_size(uint16_t log_num)
|
|||
return st.st_size;
|
||||
}
|
||||
|
||||
uint32_t DataFlash_File::_get_log_time(uint16_t log_num)
|
||||
{
|
||||
char *fname = _log_file_name(log_num);
|
||||
if (fname == NULL) {
|
||||
return 0;
|
||||
}
|
||||
struct stat st;
|
||||
if (::stat(fname, &st) != 0) {
|
||||
free(fname);
|
||||
return 0;
|
||||
}
|
||||
free(fname);
|
||||
return st.st_mtime;
|
||||
}
|
||||
|
||||
/*
|
||||
find the number of pages in a log
|
||||
*/
|
||||
|
@ -236,6 +251,51 @@ void DataFlash_File::get_log_boundaries(uint16_t log_num, uint16_t & start_page,
|
|||
end_page = _get_log_size(log_num) / DATAFLASH_PAGE_SIZE;
|
||||
}
|
||||
|
||||
/*
|
||||
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)
|
||||
{
|
||||
if (!_initialised) {
|
||||
return -1;
|
||||
}
|
||||
if (_read_fd != -1 && log_num != _read_fd_log_num) {
|
||||
::close(_read_fd);
|
||||
_read_fd = -1;
|
||||
}
|
||||
if (_read_fd == -1) {
|
||||
char *fname = _log_file_name(log_num);
|
||||
if (fname == NULL) {
|
||||
return -1;
|
||||
}
|
||||
_read_fd = open(fname, O_RDONLY);
|
||||
free(fname);
|
||||
if (_read_fd == -1) {
|
||||
return -1;
|
||||
}
|
||||
_read_offset = 0;
|
||||
_read_fd_log_num = log_num;
|
||||
}
|
||||
uint32_t ofs = page * (uint32_t)DATAFLASH_PAGE_SIZE + offset;
|
||||
if (ofs != _read_offset) {
|
||||
::lseek(_read_fd, ofs, SEEK_SET);
|
||||
}
|
||||
int16_t ret = (int16_t)::read(_read_fd, data, len);
|
||||
if (ret > 0) {
|
||||
_read_offset += ret;
|
||||
}
|
||||
return ret;
|
||||
}
|
||||
|
||||
/*
|
||||
find size and date of a log
|
||||
*/
|
||||
void DataFlash_File::get_log_info(uint16_t log_num, uint32_t &size, uint32_t &time_utc)
|
||||
{
|
||||
size = _get_log_size(log_num);
|
||||
time_utc = _get_log_time(log_num);
|
||||
}
|
||||
|
||||
|
||||
|
||||
/*
|
||||
|
@ -264,6 +324,10 @@ uint16_t DataFlash_File::start_new_log(void)
|
|||
_write_fd = -1;
|
||||
::close(fd);
|
||||
}
|
||||
if (_read_fd != -1) {
|
||||
::close(_read_fd);
|
||||
_read_fd = -1;
|
||||
}
|
||||
|
||||
uint16_t log_num = find_last_log();
|
||||
// re-use empty logs if possible
|
||||
|
@ -307,6 +371,7 @@ void DataFlash_File::LogReadProcess(uint16_t log_num,
|
|||
}
|
||||
if (_read_fd != -1) {
|
||||
::close(_read_fd);
|
||||
_read_fd = -1;
|
||||
}
|
||||
char *fname = _log_file_name(log_num);
|
||||
if (fname == NULL) {
|
||||
|
@ -317,6 +382,7 @@ void DataFlash_File::LogReadProcess(uint16_t log_num,
|
|||
if (_read_fd == -1) {
|
||||
return;
|
||||
}
|
||||
_read_fd_log_num = log_num;
|
||||
_read_offset = 0;
|
||||
if (start_page != 0) {
|
||||
::lseek(_read_fd, start_page * DATAFLASH_PAGE_SIZE, SEEK_SET);
|
||||
|
|
|
@ -30,6 +30,8 @@ public:
|
|||
// high level interface
|
||||
uint16_t find_last_log(void);
|
||||
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);
|
||||
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 start_new_log(void);
|
||||
void LogReadProcess(uint16_t log_num,
|
||||
|
@ -45,6 +47,7 @@ public:
|
|||
private:
|
||||
int _write_fd;
|
||||
int _read_fd;
|
||||
uint16_t _read_fd_log_num;
|
||||
uint32_t _read_offset;
|
||||
volatile bool _initialised;
|
||||
const char *_log_directory;
|
||||
|
@ -65,6 +68,7 @@ private:
|
|||
char *_log_file_name(uint16_t log_num);
|
||||
char *_lastlog_file_name(void);
|
||||
uint32_t _get_log_size(uint16_t log_num);
|
||||
uint32_t _get_log_time(uint16_t log_num);
|
||||
|
||||
void _io_timer(void);
|
||||
};
|
||||
|
|
|
@ -136,6 +136,19 @@ void DataFlash_Block::get_log_boundaries(uint16_t log_num, uint16_t & start_page
|
|||
}
|
||||
}
|
||||
|
||||
// find log size and time
|
||||
void DataFlash_Block::get_log_info(uint16_t log_num, uint32_t &size, uint32_t &time_utc)
|
||||
{
|
||||
uint16_t start, end;
|
||||
get_log_boundaries(log_num, start, end);
|
||||
if (end >= start) {
|
||||
size = (end + 1 - start) * (uint32_t)df_PageSize;
|
||||
} else {
|
||||
size = (df_NumPages + end - start) * (uint32_t)df_PageSize;
|
||||
}
|
||||
time_utc = 0;
|
||||
}
|
||||
|
||||
bool DataFlash_Block::check_wrapped(void)
|
||||
{
|
||||
StartRead(df_NumPages);
|
||||
|
|
Loading…
Reference in New Issue