Browse Source

DataFlash: print FMT messages for wrapped logs

this ensures we have FMT messages in every log, even if the log was
wrapped and the FMT messages were overwritten
mission-4.1.18
Andrew Tridgell 11 years ago
parent
commit
3262022195
  1. 4
      libraries/DataFlash/DataFlash_Block.h
  2. 25
      libraries/DataFlash/LogFile.cpp

4
libraries/DataFlash/DataFlash_Block.h

@ -95,6 +95,10 @@ private: @@ -95,6 +95,10 @@ private:
uint16_t GetFilePage();
uint16_t GetFileNumber();
void _print_log_formats(uint8_t num_types,
const struct LogStructure *structure,
AP_HAL::BetterStream *port);
protected:
uint8_t df_manufacturer;
uint16_t df_device;

25
libraries/DataFlash/LogFile.cpp

@ -396,6 +396,26 @@ void DataFlash_Class::_print_log_entry(uint8_t msg_type, @@ -396,6 +396,26 @@ void DataFlash_Class::_print_log_entry(uint8_t msg_type,
port->println();
}
/*
print FMT specifiers for log dumps where we have wrapped in the
dataflash and so have no formats. This assumes the log being dumped
using the same log formats as the current formats, but it is better
than falling back to old defaults in the GCS
*/
void DataFlash_Block::_print_log_formats(uint8_t num_types,
const struct LogStructure *structure,
AP_HAL::BetterStream *port)
{
for (uint8_t i=0; i<num_types; i++) {
const struct LogStructure *s = &structure[i];
port->printf_P(PSTR("FMT, %u, %u, %S, %S, %S\n"),
(unsigned)PGM_UINT8(&s->msg_type),
(unsigned)PGM_UINT8(&s->msg_len),
s->name, s->format, s->labels);
}
}
/*
Read the log and print it on port
*/
@ -408,6 +428,7 @@ void DataFlash_Block::LogReadProcess(uint16_t log_num, @@ -408,6 +428,7 @@ void DataFlash_Block::LogReadProcess(uint16_t log_num,
{
uint8_t log_step = 0;
uint16_t page = start_page;
bool first_entry = true;
if (df_BufferIdx != 0) {
FinishWrite();
@ -438,6 +459,10 @@ void DataFlash_Block::LogReadProcess(uint16_t log_num, @@ -438,6 +459,10 @@ void DataFlash_Block::LogReadProcess(uint16_t log_num,
case 2:
log_step = 0;
if (first_entry && data != LOG_FORMAT_MSG) {
_print_log_formats(num_types, structure, port);
}
first_entry = false;
_print_log_entry(data, num_types, structure, print_mode, port);
break;
}

Loading…
Cancel
Save