mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 09:28:31 -04:00
Rover: fixes for new DataFlash API
This commit is contained in:
parent
9a3bd17cfb
commit
36da75aacd
@ -29,10 +29,10 @@ MENU2(log_menu, "Log", log_menu_commands, print_log_menu);
|
||||
static bool
|
||||
print_log_menu(void)
|
||||
{
|
||||
int16_t log_start;
|
||||
int16_t log_end;
|
||||
int16_t temp;
|
||||
int16_t last_log_num = DataFlash.find_last_log();
|
||||
uint16_t log_start;
|
||||
uint16_t log_end;
|
||||
uint16_t temp;
|
||||
uint16_t last_log_num = DataFlash.find_last_log();
|
||||
|
||||
uint16_t num_logs = DataFlash.get_num_logs();
|
||||
|
||||
@ -67,7 +67,7 @@ print_log_menu(void)
|
||||
cliSerial->printf_P(PSTR("\n%d logs\n"), num_logs);
|
||||
|
||||
for(int i=num_logs;i>=1;i--) {
|
||||
int 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;
|
||||
DataFlash.get_log_boundaries(temp, log_start, log_end);
|
||||
cliSerial->printf_P(PSTR("Log %d, start %d, end %d\n"), temp, log_start, log_end);
|
||||
@ -85,8 +85,8 @@ static int8_t
|
||||
dump_log(uint8_t argc, const Menu::arg *argv)
|
||||
{
|
||||
int16_t dump_log;
|
||||
int16_t dump_log_start;
|
||||
int16_t dump_log_end;
|
||||
uint16_t dump_log_start;
|
||||
uint16_t dump_log_end;
|
||||
uint8_t last_log_num;
|
||||
|
||||
// check that the requested log number can be read
|
||||
@ -94,16 +94,11 @@ dump_log(uint8_t argc, const Menu::arg *argv)
|
||||
last_log_num = DataFlash.find_last_log();
|
||||
|
||||
if (dump_log == -2) {
|
||||
for(uint16_t count=1; count<=DataFlash.df_NumPages; count++) {
|
||||
DataFlash.StartRead(count);
|
||||
cliSerial->printf_P(PSTR("DF page, log file #, log page: %d,\t"), count);
|
||||
cliSerial->printf_P(PSTR("%d,\t"), DataFlash.GetFileNumber());
|
||||
cliSerial->printf_P(PSTR("%d\n"), DataFlash.GetFilePage());
|
||||
}
|
||||
DataFlash.DumpPageInfo(cliSerial);
|
||||
return(-1);
|
||||
} else if (dump_log <= 0) {
|
||||
cliSerial->printf_P(PSTR("dumping all\n"));
|
||||
Log_Read(1, DataFlash.df_NumPages);
|
||||
Log_Read(1, 0);
|
||||
return(-1);
|
||||
} else if ((argc != 2) || (dump_log <= (last_log_num - DataFlash.get_num_logs())) || (dump_log > last_log_num)) {
|
||||
cliSerial->printf_P(PSTR("bad log number\n"));
|
||||
@ -122,13 +117,6 @@ dump_log(uint8_t argc, const Menu::arg *argv)
|
||||
}
|
||||
|
||||
|
||||
void erase_callback(unsigned long t) {
|
||||
mavlink_delay(t);
|
||||
if (DataFlash.GetWritePage() % 128 == 0) {
|
||||
cliSerial->printf_P(PSTR("+"));
|
||||
}
|
||||
}
|
||||
|
||||
static void do_erase_logs(void)
|
||||
{
|
||||
cliSerial->printf_P(PSTR("\nErasing log...\n"));
|
||||
|
@ -345,20 +345,7 @@ static int8_t
|
||||
test_logging(uint8_t argc, const Menu::arg *argv)
|
||||
{
|
||||
cliSerial->println_P(PSTR("Testing dataflash logging"));
|
||||
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 PageSize: %u\n"),
|
||||
(unsigned)DataFlash.df_NumPages+1,
|
||||
(unsigned)DataFlash.df_PageSize);
|
||||
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);
|
||||
DataFlash.ShowDeviceInfo(cliSerial);
|
||||
return 0;
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user