mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-25 10:08:28 -04:00
Simplified logging logic for finding start/end of log files
This commit is contained in:
parent
fa461ecc82
commit
06c88cf07b
@ -259,146 +259,127 @@ static void get_log_boundaries(byte log_num, int & start_page, int & end_page)
|
|||||||
|
|
||||||
} else {
|
} else {
|
||||||
end_page = find_last_log_page((uint16_t)log_num);
|
end_page = find_last_log_page((uint16_t)log_num);
|
||||||
if(log_num==1)
|
if(log_num==1) {
|
||||||
start_page = 1;
|
DataFlash.StartRead(DF_LAST_PAGE);
|
||||||
else
|
if(DataFlash.GetFileNumber() == 0xFFFF) {
|
||||||
if(log_num == g.log_last_filenumber - num + 1) {
|
start_page = 1;
|
||||||
start_page = find_last_log_page(g.log_last_filenumber) + 1;
|
|
||||||
} else {
|
} else {
|
||||||
start_page = find_last_log_page((uint16_t)(log_num-1)) + 1;
|
start_page = find_last() + 1;
|
||||||
}
|
}
|
||||||
|
} else {
|
||||||
|
if(log_num == g.log_last_filenumber - num + 1) {
|
||||||
|
start_page = find_last() + 1;
|
||||||
|
} else {
|
||||||
|
start_page = find_last_log_page((uint16_t)log_num-1) + 1;
|
||||||
|
}
|
||||||
|
}
|
||||||
}
|
}
|
||||||
if(start_page == DF_LAST_PAGE+1 || start_page == 0) start_page=1;
|
if(start_page == DF_LAST_PAGE+1 || start_page == 0) start_page=1;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
static bool check_wrapped(void)
|
||||||
|
{
|
||||||
|
DataFlash.StartRead(DF_LAST_PAGE);
|
||||||
|
if(DataFlash.GetFileNumber() == 0xFFFF)
|
||||||
|
return 0;
|
||||||
|
else
|
||||||
|
return 1;
|
||||||
|
}
|
||||||
|
|
||||||
// This function finds the last page of the last file
|
// This function finds the last page of the last file
|
||||||
// It also cleans up in the situation where a file was initiated, but no pages written
|
|
||||||
static int find_last(void)
|
static int find_last(void)
|
||||||
{
|
{
|
||||||
int16_t num;
|
uint16_t look;
|
||||||
do
|
uint16_t bottom = 1;
|
||||||
{
|
uint16_t top = DF_LAST_PAGE;
|
||||||
num = find_last_log_page(g.log_last_filenumber);
|
uint32_t look_hash;
|
||||||
if (num == -1) g.log_last_filenumber.set_and_save(g.log_last_filenumber - 1);
|
uint32_t bottom_hash;
|
||||||
} while (num == -1);
|
uint32_t top_hash;
|
||||||
return num;
|
|
||||||
|
DataFlash.StartRead(bottom);
|
||||||
|
bottom_hash = DataFlash.GetFileNumber()<<16 | DataFlash.GetFilePage();
|
||||||
|
|
||||||
|
while(top-bottom > 1)
|
||||||
|
{
|
||||||
|
look = (top+bottom)/2;
|
||||||
|
DataFlash.StartRead(look);
|
||||||
|
look_hash = DataFlash.GetFileNumber()<<16 | DataFlash.GetFilePage();
|
||||||
|
if (look_hash >= 0xFFFF0000) look_hash = 0;
|
||||||
|
|
||||||
|
if(look_hash < bottom_hash) {
|
||||||
|
// move down
|
||||||
|
top = look;
|
||||||
|
} else {
|
||||||
|
// move up
|
||||||
|
bottom = look;
|
||||||
|
bottom_hash = look_hash;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
DataFlash.StartRead(top);
|
||||||
|
top_hash = DataFlash.GetFileNumber()<<16 | DataFlash.GetFilePage();
|
||||||
|
if (top_hash >= 0xFFFF0000) top_hash = 0;
|
||||||
|
if (top_hash > bottom_hash)
|
||||||
|
{
|
||||||
|
return top;
|
||||||
|
} else {
|
||||||
|
return bottom;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// This function finds the last page of a particular log file
|
// This function finds the last page of a particular log file
|
||||||
static int find_last_log_page(uint16_t log_number)
|
static int find_last_log_page(uint16_t log_number)
|
||||||
{
|
{
|
||||||
|
|
||||||
uint16_t bottom_page;
|
uint16_t look;
|
||||||
uint16_t bottom_page_file;
|
uint16_t bottom;
|
||||||
uint16_t bottom_page_filepage;
|
uint16_t top;
|
||||||
uint16_t top_page;
|
uint32_t look_hash;
|
||||||
uint16_t top_page_file;
|
uint32_t check_hash;
|
||||||
uint16_t top_page_filepage;
|
|
||||||
uint16_t look_page;
|
|
||||||
uint16_t look_page_file;
|
|
||||||
uint16_t look_page_filepage;
|
|
||||||
|
|
||||||
bottom_page = 1;
|
if(check_wrapped())
|
||||||
DataFlash.StartRead(bottom_page);
|
{
|
||||||
bottom_page_file = DataFlash.GetFileNumber();
|
DataFlash.StartRead(1);
|
||||||
bottom_page_filepage = DataFlash.GetFilePage();
|
bottom = DataFlash.GetFileNumber();
|
||||||
|
if (bottom > log_number)
|
||||||
// First see if the logs are empty. If so we will exit right away.
|
{
|
||||||
if(bottom_page_file == 0XFFFF) {
|
bottom = find_last();
|
||||||
return 0;
|
top = DF_LAST_PAGE;
|
||||||
}
|
|
||||||
|
|
||||||
top_page = DF_LAST_PAGE;
|
|
||||||
DataFlash.StartRead(top_page);
|
|
||||||
top_page_file = DataFlash.GetFileNumber();
|
|
||||||
top_page_filepage = DataFlash.GetFilePage();
|
|
||||||
|
|
||||||
|
|
||||||
while((top_page - bottom_page) > 1) {
|
|
||||||
look_page = ((long)top_page + (long)bottom_page) / 2L;
|
|
||||||
|
|
||||||
DataFlash.StartRead(look_page);
|
|
||||||
look_page_file = DataFlash.GetFileNumber();
|
|
||||||
look_page_filepage = DataFlash.GetFilePage();
|
|
||||||
|
|
||||||
// We have a lot of different logic cases dependant on if the log space is overwritten
|
|
||||||
// and where log breaks might occur relative to binary search points.
|
|
||||||
// Someone could make work up a logic table and simplify this perhaps, or perhaps
|
|
||||||
// it is easier to interpret as is.
|
|
||||||
|
|
||||||
if (look_page_file == 0xFFFF) {
|
|
||||||
top_page = look_page;
|
|
||||||
top_page_file = look_page_file;
|
|
||||||
top_page_filepage = look_page_filepage;
|
|
||||||
|
|
||||||
} else if (look_page_file == log_number && bottom_page_file == log_number && top_page_file == log_number) {
|
|
||||||
// This case is typical if a single file fills the log and partially overwrites itself
|
|
||||||
if (bottom_page_filepage < top_page_filepage) {
|
|
||||||
bottom_page = look_page;
|
|
||||||
bottom_page_file = look_page_file;
|
|
||||||
bottom_page_filepage = look_page_filepage;
|
|
||||||
} else {
|
|
||||||
top_page = look_page;
|
|
||||||
top_page_file = look_page_file;
|
|
||||||
top_page_filepage = look_page_filepage;
|
|
||||||
}
|
|
||||||
|
|
||||||
} else if (look_page_file == log_number && look_page_file ==bottom_page_file) {
|
|
||||||
if (bottom_page_filepage < look_page_filepage) {
|
|
||||||
bottom_page = look_page;
|
|
||||||
bottom_page_file = look_page_file;
|
|
||||||
bottom_page_filepage = look_page_filepage;
|
|
||||||
} else {
|
|
||||||
top_page = look_page;
|
|
||||||
top_page_file = look_page_file;
|
|
||||||
top_page_filepage = look_page_filepage;
|
|
||||||
}
|
|
||||||
|
|
||||||
} else if (look_page_file == log_number) {
|
|
||||||
bottom_page = look_page;
|
|
||||||
bottom_page_file = look_page_file;
|
|
||||||
bottom_page_filepage = look_page_filepage;
|
|
||||||
|
|
||||||
} else if(look_page_file < log_number && bottom_page_file > look_page_file && bottom_page_file <= log_number) {
|
|
||||||
top_page = look_page;
|
|
||||||
top_page_file = look_page_file;
|
|
||||||
top_page_filepage = look_page_filepage;
|
|
||||||
} else if(look_page_file < log_number) {
|
|
||||||
bottom_page = look_page;
|
|
||||||
bottom_page_file = look_page_file;
|
|
||||||
bottom_page_filepage = look_page_filepage;
|
|
||||||
|
|
||||||
} else if(look_page_file > log_number && top_page_file < look_page_file && top_page_file >= log_number) {
|
|
||||||
bottom_page = look_page;
|
|
||||||
bottom_page_file = look_page_file;
|
|
||||||
bottom_page_filepage = look_page_filepage;
|
|
||||||
} else {
|
} else {
|
||||||
top_page = look_page;
|
bottom = 1;
|
||||||
top_page_file = look_page_file;
|
top = find_last();
|
||||||
top_page_filepage = look_page_filepage;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// End while
|
|
||||||
}
|
|
||||||
|
|
||||||
if (bottom_page_file == log_number && top_page_file == log_number) {
|
|
||||||
if( bottom_page_filepage < top_page_filepage)
|
|
||||||
return top_page;
|
|
||||||
else
|
|
||||||
return bottom_page;
|
|
||||||
} else if (bottom_page_file == log_number) {
|
|
||||||
return bottom_page;
|
|
||||||
} else if (top_page_file == log_number) {
|
|
||||||
return top_page;
|
|
||||||
} else {
|
} else {
|
||||||
return -1;
|
bottom = 1;
|
||||||
|
top = find_last();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
check_hash = (long)log_number<<16 | 0xFFFF;
|
||||||
|
|
||||||
|
while(top-bottom > 1)
|
||||||
|
{
|
||||||
|
look = (top+bottom)/2;
|
||||||
|
DataFlash.StartRead(look);
|
||||||
|
look_hash = (long)DataFlash.GetFileNumber()<<16 | DataFlash.GetFilePage();
|
||||||
|
if (look_hash >= 0xFFFF0000) look_hash = 0;
|
||||||
|
|
||||||
|
if(look_hash > check_hash) {
|
||||||
|
// move down
|
||||||
|
top = look;
|
||||||
|
} else {
|
||||||
|
// move up
|
||||||
|
bottom = look;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
DataFlash.StartRead(top);
|
||||||
|
if (DataFlash.GetFileNumber() == log_number) return top;
|
||||||
|
|
||||||
|
DataFlash.StartRead(bottom);
|
||||||
|
if (DataFlash.GetFileNumber() == log_number) return bottom;
|
||||||
|
|
||||||
|
return -1;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
// Write an attitude packet. Total length : 10 bytes
|
// Write an attitude packet. Total length : 10 bytes
|
||||||
|
Loading…
Reference in New Issue
Block a user