mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 09:28:31 -04:00
Plane: fixes for new DataFlash API
This commit is contained in:
parent
0ffcffa81c
commit
b3213b7113
@ -28,9 +28,9 @@ MENU2(log_menu, "Log", log_menu_commands, print_log_menu);
|
|||||||
static bool
|
static bool
|
||||||
print_log_menu(void)
|
print_log_menu(void)
|
||||||
{
|
{
|
||||||
int16_t log_start;
|
uint16_t log_start;
|
||||||
int16_t log_end;
|
uint16_t log_end;
|
||||||
int16_t temp;
|
uint16_t temp;
|
||||||
int16_t last_log_num = DataFlash.find_last_log();
|
int16_t last_log_num = DataFlash.find_last_log();
|
||||||
|
|
||||||
uint16_t num_logs = DataFlash.get_num_logs();
|
uint16_t num_logs = DataFlash.get_num_logs();
|
||||||
@ -66,7 +66,7 @@ print_log_menu(void)
|
|||||||
cliSerial->printf_P(PSTR("\n%u logs\n"), (unsigned)num_logs);
|
cliSerial->printf_P(PSTR("\n%u logs\n"), (unsigned)num_logs);
|
||||||
|
|
||||||
for(int16_t i=num_logs; i>=1; i--) {
|
for(int16_t i=num_logs; i>=1; i--) {
|
||||||
int16_t last_log_start = log_start, last_log_end = log_end;
|
uint16_t last_log_start = log_start, last_log_end = log_end;
|
||||||
temp = last_log_num-i+1;
|
temp = last_log_num-i+1;
|
||||||
DataFlash.get_log_boundaries(temp, log_start, log_end);
|
DataFlash.get_log_boundaries(temp, log_start, log_end);
|
||||||
cliSerial->printf_P(PSTR("Log %d, start %d, end %d\n"), (int)temp, (int)log_start, (int)log_end);
|
cliSerial->printf_P(PSTR("Log %d, start %d, end %d\n"), (int)temp, (int)log_start, (int)log_end);
|
||||||
@ -84,39 +84,33 @@ static int8_t
|
|||||||
dump_log(uint8_t argc, const Menu::arg *argv)
|
dump_log(uint8_t argc, const Menu::arg *argv)
|
||||||
{
|
{
|
||||||
int16_t dump_log;
|
int16_t dump_log;
|
||||||
int16_t dump_log_start;
|
uint16_t dump_log_start;
|
||||||
int16_t dump_log_end;
|
uint16_t dump_log_end;
|
||||||
int16_t last_log_num;
|
uint16_t last_log_num;
|
||||||
|
|
||||||
// check that the requested log number can be read
|
// check that the requested log number can be read
|
||||||
dump_log = argv[1].i;
|
dump_log = argv[1].i;
|
||||||
last_log_num = DataFlash.find_last_log();
|
last_log_num = DataFlash.find_last_log();
|
||||||
|
|
||||||
if (dump_log == -2) {
|
if (dump_log == -2) {
|
||||||
for(uint16_t count=1; count<=DataFlash.df_NumPages; count++) {
|
DataFlash.DumpPageInfo(cliSerial);
|
||||||
DataFlash.StartRead(count);
|
|
||||||
cliSerial->printf_P(PSTR("DF page, log file #, log page: %d,\t"), (int)count);
|
|
||||||
cliSerial->printf_P(PSTR("%d,\t"), (int)DataFlash.GetFileNumber());
|
|
||||||
cliSerial->printf_P(PSTR("%d\n"), (int)DataFlash.GetFilePage());
|
|
||||||
}
|
|
||||||
return(-1);
|
return(-1);
|
||||||
} else if (dump_log <= 0) {
|
} else if (dump_log <= 0) {
|
||||||
cliSerial->printf_P(PSTR("dumping all\n"));
|
cliSerial->printf_P(PSTR("dumping all\n"));
|
||||||
Log_Read(1, DataFlash.df_NumPages);
|
Log_Read(1, 0);
|
||||||
return(-1);
|
return(-1);
|
||||||
} else if ((argc != 2)
|
} else if ((argc != 2)
|
||||||
|| (dump_log <= (last_log_num - DataFlash.get_num_logs()))
|
|| ((uint16_t)dump_log > last_log_num))
|
||||||
|| (dump_log > last_log_num))
|
|
||||||
{
|
{
|
||||||
cliSerial->printf_P(PSTR("bad log number\n"));
|
cliSerial->printf_P(PSTR("bad log number\n"));
|
||||||
return(-1);
|
return(-1);
|
||||||
}
|
}
|
||||||
|
|
||||||
DataFlash.get_log_boundaries(dump_log, dump_log_start, dump_log_end);
|
DataFlash.get_log_boundaries(dump_log, dump_log_start, dump_log_end);
|
||||||
cliSerial->printf_P(PSTR("Dumping Log %d, start pg %d, end pg %d\n"),
|
cliSerial->printf_P(PSTR("Dumping Log %u, start pg %u, end pg %u\n"),
|
||||||
(int)dump_log,
|
(unsigned)dump_log,
|
||||||
(int)dump_log_start,
|
(unsigned)dump_log_start,
|
||||||
(int)dump_log_end);
|
(unsigned)dump_log_end);
|
||||||
|
|
||||||
Log_Read(dump_log_start, dump_log_end);
|
Log_Read(dump_log_start, dump_log_end);
|
||||||
cliSerial->printf_P(PSTR("Done\n"));
|
cliSerial->printf_P(PSTR("Done\n"));
|
||||||
|
@ -394,21 +394,7 @@ test_modeswitch(uint8_t argc, const Menu::arg *argv)
|
|||||||
static int8_t
|
static int8_t
|
||||||
test_logging(uint8_t argc, const Menu::arg *argv)
|
test_logging(uint8_t argc, const Menu::arg *argv)
|
||||||
{
|
{
|
||||||
cliSerial->println_P(PSTR("Testing dataflash logging"));
|
DataFlash.ShowDeviceInfo(cliSerial);
|
||||||
if (!DataFlash.CardInserted()) {
|
|
||||||
cliSerial->println_P(PSTR("ERR: No dataflash inserted"));
|
|
||||||
return 0;
|
|
||||||
}
|
|
||||||
DataFlash.ReadManufacturerID();
|
|
||||||
cliSerial->printf_P(PSTR("Manufacturer: 0x%02x Device: 0x%04x\n"),
|
|
||||||
(unsigned)DataFlash.df_manufacturer,
|
|
||||||
(unsigned)DataFlash.df_device);
|
|
||||||
cliSerial->printf_P(PSTR("NumPages: %u\n"),
|
|
||||||
(unsigned)DataFlash.df_NumPages+1);
|
|
||||||
DataFlash.StartRead(DataFlash.df_NumPages+1);
|
|
||||||
cliSerial->printf_P(PSTR("Format version: %lx Expected format version: %lx\n"),
|
|
||||||
(unsigned long)DataFlash.ReadLong(),
|
|
||||||
(unsigned long)DF_LOGGING_FORMAT);
|
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user