|
|
|
@ -8,6 +8,14 @@
@@ -8,6 +8,14 @@
|
|
|
|
|
|
|
|
|
|
extern const AP_HAL::HAL& hal; |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
void DataFlash_Class::Init(const struct LogStructure *structure, uint8_t num_types) |
|
|
|
|
{ |
|
|
|
|
_num_types = num_types; |
|
|
|
|
_structures = structure; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
// This function determines the number of whole or partial log files in the DataFlash
|
|
|
|
|
// Wholly overwritten files are (of course) lost.
|
|
|
|
|
uint16_t DataFlash_Block::get_num_logs(void) |
|
|
|
@ -267,27 +275,25 @@ uint16_t DataFlash_Block::find_last_page_of_log(uint16_t log_number)
@@ -267,27 +275,25 @@ uint16_t DataFlash_Block::find_last_page_of_log(uint16_t log_number)
|
|
|
|
|
read and print a log entry using the format strings from the given structure |
|
|
|
|
*/ |
|
|
|
|
void DataFlash_Class::_print_log_entry(uint8_t msg_type,
|
|
|
|
|
uint8_t num_types,
|
|
|
|
|
const struct LogStructure *structure, |
|
|
|
|
void (*print_mode)(AP_HAL::BetterStream *port, uint8_t mode), |
|
|
|
|
AP_HAL::BetterStream *port) |
|
|
|
|
{ |
|
|
|
|
uint8_t i; |
|
|
|
|
for (i=0; i<num_types; i++) { |
|
|
|
|
if (msg_type == PGM_UINT8(&structure[i].msg_type)) { |
|
|
|
|
for (i=0; i<_num_types; i++) { |
|
|
|
|
if (msg_type == PGM_UINT8(&_structures[i].msg_type)) { |
|
|
|
|
break; |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
if (i == num_types) { |
|
|
|
|
if (i == _num_types) { |
|
|
|
|
port->printf_P(PSTR("UNKN, %u\n"), (unsigned)msg_type); |
|
|
|
|
return; |
|
|
|
|
} |
|
|
|
|
uint8_t msg_len = PGM_UINT8(&structure[i].msg_len) - 3; |
|
|
|
|
uint8_t msg_len = PGM_UINT8(&_structures[i].msg_len) - 3; |
|
|
|
|
uint8_t pkt[msg_len]; |
|
|
|
|
ReadBlock(pkt, msg_len); |
|
|
|
|
port->printf_P(PSTR("%S, "), structure[i].name); |
|
|
|
|
port->printf_P(PSTR("%S, "), _structures[i].name); |
|
|
|
|
for (uint8_t ofs=0, fmt_ofs=0; ofs<msg_len; fmt_ofs++) { |
|
|
|
|
char fmt = PGM_UINT8(&structure[i].format[fmt_ofs]); |
|
|
|
|
char fmt = PGM_UINT8(&_structures[i].format[fmt_ofs]); |
|
|
|
|
switch (fmt) { |
|
|
|
|
case 'b': { |
|
|
|
|
port->printf_P(PSTR("%d"), (int)pkt[ofs]); |
|
|
|
@ -416,12 +422,10 @@ void DataFlash_Class::_print_log_entry(uint8_t msg_type,
@@ -416,12 +422,10 @@ void DataFlash_Class::_print_log_entry(uint8_t msg_type,
|
|
|
|
|
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) |
|
|
|
|
void DataFlash_Block::_print_log_formats(AP_HAL::BetterStream *port) |
|
|
|
|
{ |
|
|
|
|
for (uint8_t i=0; i<num_types; i++) { |
|
|
|
|
const struct LogStructure *s = &structure[i]; |
|
|
|
|
for (uint8_t i=0; i<_num_types; i++) { |
|
|
|
|
const struct LogStructure *s = &_structures[i]; |
|
|
|
|
port->printf_P(PSTR("FMT, %u, %u, %S, %S, %S\n"), |
|
|
|
|
(unsigned)PGM_UINT8(&s->msg_type),
|
|
|
|
|
(unsigned)PGM_UINT8(&s->msg_len),
|
|
|
|
@ -434,8 +438,6 @@ void DataFlash_Block::_print_log_formats(uint8_t num_types,
@@ -434,8 +438,6 @@ void DataFlash_Block::_print_log_formats(uint8_t num_types,
|
|
|
|
|
*/ |
|
|
|
|
void DataFlash_Block::LogReadProcess(uint16_t log_num, |
|
|
|
|
uint16_t start_page, uint16_t end_page,
|
|
|
|
|
uint8_t num_types, |
|
|
|
|
const struct LogStructure *structure, |
|
|
|
|
void (*print_mode)(AP_HAL::BetterStream *port, uint8_t mode), |
|
|
|
|
AP_HAL::BetterStream *port) |
|
|
|
|
{ |
|
|
|
@ -473,10 +475,10 @@ void DataFlash_Block::LogReadProcess(uint16_t log_num,
@@ -473,10 +475,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); |
|
|
|
|
_print_log_formats(port); |
|
|
|
|
} |
|
|
|
|
first_entry = false; |
|
|
|
|
_print_log_entry(data, num_types, structure, print_mode, port); |
|
|
|
|
_print_log_entry(data, print_mode, port); |
|
|
|
|
break; |
|
|
|
|
} |
|
|
|
|
uint16_t new_page = GetPage(); |
|
|
|
@ -554,17 +556,19 @@ void DataFlash_Block::ListAvailableLogs(AP_HAL::BetterStream *port)
@@ -554,17 +556,19 @@ void DataFlash_Block::ListAvailableLogs(AP_HAL::BetterStream *port)
|
|
|
|
|
|
|
|
|
|
// This function starts a new log file in the DataFlash, and writes
|
|
|
|
|
// the format of supported messages in the log, plus all parameters
|
|
|
|
|
uint16_t DataFlash_Class::StartNewLog(uint8_t num_types, const struct LogStructure *structures) |
|
|
|
|
uint16_t DataFlash_Class::StartNewLog(void) |
|
|
|
|
{ |
|
|
|
|
uint16_t ret; |
|
|
|
|
ret = start_new_log(); |
|
|
|
|
|
|
|
|
|
#if 0 |
|
|
|
|
// write log formats so the log is self-describing
|
|
|
|
|
for (uint8_t i=0; i<num_types; i++) { |
|
|
|
|
Log_Write_Format(&structures[i]); |
|
|
|
|
for (uint8_t i=0; i<_num_types; i++) { |
|
|
|
|
Log_Write_Format(&_structures[i]); |
|
|
|
|
// avoid corrupting the APM1/APM2 dataflash by writing too fast
|
|
|
|
|
hal.scheduler->delay(10); |
|
|
|
|
} |
|
|
|
|
#endif |
|
|
|
|
|
|
|
|
|
// and all current parameters
|
|
|
|
|
Log_Write_Parameters(); |
|
|
|
@ -574,22 +578,29 @@ uint16_t DataFlash_Class::StartNewLog(uint8_t num_types, const struct LogStructu
@@ -574,22 +578,29 @@ uint16_t DataFlash_Class::StartNewLog(uint8_t num_types, const struct LogStructu
|
|
|
|
|
/*
|
|
|
|
|
write a structure format to the log |
|
|
|
|
*/ |
|
|
|
|
void DataFlash_Class::Log_Write_Format(const struct LogStructure *s) |
|
|
|
|
void DataFlash_Class::Log_Fill_Format(const struct LogStructure *s, struct log_Format &pkt) |
|
|
|
|
{ |
|
|
|
|
struct log_Format pkt = { |
|
|
|
|
LOG_PACKET_HEADER_INIT(LOG_FORMAT_MSG), |
|
|
|
|
type : PGM_UINT8(&s->msg_type), |
|
|
|
|
length : PGM_UINT8(&s->msg_len), |
|
|
|
|
name : {}, |
|
|
|
|
format : {}, |
|
|
|
|
labels : {} |
|
|
|
|
}; |
|
|
|
|
pkt.head1 = HEAD_BYTE1; |
|
|
|
|
pkt.head2 = HEAD_BYTE2; |
|
|
|
|
pkt.msgid = LOG_FORMAT_MSG; |
|
|
|
|
pkt.type = PGM_UINT8(&s->msg_type); |
|
|
|
|
pkt.length = PGM_UINT8(&s->msg_len); |
|
|
|
|
strncpy_P(pkt.name, s->name, sizeof(pkt.name)); |
|
|
|
|
strncpy_P(pkt.format, s->format, sizeof(pkt.format)); |
|
|
|
|
strncpy_P(pkt.labels, s->labels, sizeof(pkt.labels)); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
/*
|
|
|
|
|
write a structure format to the log |
|
|
|
|
*/ |
|
|
|
|
void DataFlash_Class::Log_Write_Format(const struct LogStructure *s) |
|
|
|
|
{ |
|
|
|
|
struct log_Format pkt; |
|
|
|
|
Log_Fill_Format(s, pkt); |
|
|
|
|
WriteBlock(&pkt, sizeof(pkt)); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
/*
|
|
|
|
|
write a parameter to the log |
|
|
|
|
*/ |
|
|
|
|