mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
Logging cleanup. Fixed missing cast, removed erase warning, added -1 to dump all option, and fix intermittent bug for log number 1.
This commit is contained in:
parent
27e68234b7
commit
0f428bd43a
@ -107,9 +107,12 @@ dump_log(uint8_t argc, const Menu::arg *argv)
|
||||
// check that the requested log number can be read
|
||||
dump_log = argv[1].i;
|
||||
last_log_num = g.log_last_filenumber;
|
||||
if ((argc != 2) || (dump_log <= (last_log_num - get_num_logs())) || (dump_log > last_log_num)) {
|
||||
if (dump_log == -1) {
|
||||
Serial.printf_P(PSTR("dumping all\n"));
|
||||
Log_Read(1, DF_LAST_PAGE);
|
||||
return(-1);
|
||||
} else if ((argc != 2) || (dump_log <= (last_log_num - get_num_logs())) || (dump_log > last_log_num)) {
|
||||
Serial.printf_P(PSTR("bad log number\n"));
|
||||
Log_Read(0, 4095);
|
||||
return(-1);
|
||||
}
|
||||
|
||||
@ -127,10 +130,6 @@ dump_log(uint8_t argc, const Menu::arg *argv)
|
||||
static int8_t
|
||||
erase_logs(uint8_t argc, const Menu::arg *argv)
|
||||
{
|
||||
for(int i = 10 ; i > 0; i--) {
|
||||
Serial.printf_P(PSTR("ATTENTION - Erasing log in %d seconds. Power off now to save log! \n"), i);
|
||||
delay(1000);
|
||||
}
|
||||
Serial.printf_P(PSTR("\nErasing log...\n"));
|
||||
DataFlash.SetFileNumber(0xFFFF);
|
||||
for(int j = 1; j <= DF_LAST_PAGE; j++) {
|
||||
@ -140,6 +139,7 @@ erase_logs(uint8_t argc, const Menu::arg *argv)
|
||||
g.log_last_filenumber.set_and_save(0);
|
||||
|
||||
Serial.printf_P(PSTR("\nLog erased.\n"));
|
||||
DataFlash.FinishWrite();
|
||||
return 0;
|
||||
}
|
||||
|
||||
@ -245,6 +245,8 @@ static void start_new_log()
|
||||
static void get_log_boundaries(byte log_num, int & start_page, int & end_page)
|
||||
{
|
||||
int num = get_num_logs();
|
||||
int look;
|
||||
|
||||
if(num == 1)
|
||||
{
|
||||
DataFlash.StartRead(DF_LAST_PAGE);
|
||||
@ -258,7 +260,6 @@ static void get_log_boundaries(byte log_num, int & start_page, int & end_page)
|
||||
}
|
||||
|
||||
} else {
|
||||
end_page = find_last_log_page((uint16_t)log_num);
|
||||
if(log_num==1) {
|
||||
DataFlash.StartRead(DF_LAST_PAGE);
|
||||
if(DataFlash.GetFileNumber() == 0xFFFF) {
|
||||
@ -270,11 +271,17 @@ static void get_log_boundaries(byte log_num, int & start_page, int & end_page)
|
||||
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;
|
||||
look = log_num-1;
|
||||
do {
|
||||
start_page = find_last_log_page(look) + 1;
|
||||
look--;
|
||||
} while (start_page <= 0);
|
||||
}
|
||||
}
|
||||
}
|
||||
if(start_page == DF_LAST_PAGE+1 || start_page == 0) start_page=1;
|
||||
end_page = find_last_log_page((uint16_t)log_num);
|
||||
if(end_page <= 0) end_page = start_page;
|
||||
}
|
||||
|
||||
static bool check_wrapped(void)
|
||||
@ -297,13 +304,13 @@ uint32_t bottom_hash;
|
||||
uint32_t top_hash;
|
||||
|
||||
DataFlash.StartRead(bottom);
|
||||
bottom_hash = DataFlash.GetFileNumber()<<16 | DataFlash.GetFilePage();
|
||||
bottom_hash = (long)DataFlash.GetFileNumber()<<16 | DataFlash.GetFilePage();
|
||||
|
||||
while(top-bottom > 1)
|
||||
{
|
||||
look = (top+bottom)/2;
|
||||
DataFlash.StartRead(look);
|
||||
look_hash = DataFlash.GetFileNumber()<<16 | DataFlash.GetFilePage();
|
||||
look_hash = (long)DataFlash.GetFileNumber()<<16 | DataFlash.GetFilePage();
|
||||
if (look_hash >= 0xFFFF0000) look_hash = 0;
|
||||
|
||||
if(look_hash < bottom_hash) {
|
||||
@ -317,7 +324,7 @@ uint32_t top_hash;
|
||||
}
|
||||
|
||||
DataFlash.StartRead(top);
|
||||
top_hash = DataFlash.GetFileNumber()<<16 | DataFlash.GetFilePage();
|
||||
top_hash = (long)DataFlash.GetFileNumber()<<16 | DataFlash.GetFilePage();
|
||||
if (top_hash >= 0xFFFF0000) top_hash = 0;
|
||||
if (top_hash > bottom_hash)
|
||||
{
|
||||
|
Loading…
Reference in New Issue
Block a user