mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 00:04:02 -04:00
DataFlash: chamged FMT message to include labels
this makes it easier for MP to parse and display
This commit is contained in:
parent
9ef34943af
commit
709a277c7f
@ -64,13 +64,6 @@ public:
|
|||||||
};
|
};
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
/*
|
|
||||||
print column headers
|
|
||||||
*/
|
|
||||||
void _print_format_headers(uint8_t num_types,
|
|
||||||
const struct LogStructure *structure,
|
|
||||||
AP_HAL::BetterStream *port);
|
|
||||||
|
|
||||||
/*
|
/*
|
||||||
read and print a log entry using the format strings from the given structure
|
read and print a log entry using the format strings from the given structure
|
||||||
*/
|
*/
|
||||||
@ -115,6 +108,7 @@ Format characters in the format string for binary log messages
|
|||||||
f : float
|
f : float
|
||||||
n : char[4]
|
n : char[4]
|
||||||
N : char[16]
|
N : char[16]
|
||||||
|
Z : char[64]
|
||||||
c : int16_t * 100
|
c : int16_t * 100
|
||||||
C : uint16_t * 100
|
C : uint16_t * 100
|
||||||
e : int32_t * 100
|
e : int32_t * 100
|
||||||
@ -141,6 +135,7 @@ struct PACKED log_Format {
|
|||||||
uint8_t length;
|
uint8_t length;
|
||||||
char name[4];
|
char name[4];
|
||||||
char format[16];
|
char format[16];
|
||||||
|
char labels[64];
|
||||||
};
|
};
|
||||||
|
|
||||||
struct PACKED log_Parameter {
|
struct PACKED log_Parameter {
|
||||||
@ -170,8 +165,8 @@ struct PACKED log_IMU {
|
|||||||
};
|
};
|
||||||
|
|
||||||
#define LOG_COMMON_STRUCTURES \
|
#define LOG_COMMON_STRUCTURES \
|
||||||
{ LOG_FORMAT_MSG, sizeof(log_Parameter), \
|
{ LOG_FORMAT_MSG, sizeof(log_Format), \
|
||||||
"FMT", "BBnN", "Type,Length,Name,Format" }, \
|
"FMT", "BBnNZ", "Type,Length,Name,Format" }, \
|
||||||
{ LOG_PARAMETER_MSG, sizeof(log_Parameter), \
|
{ LOG_PARAMETER_MSG, sizeof(log_Parameter), \
|
||||||
"PARM", "Nf", "Name,Value" }, \
|
"PARM", "Nf", "Name,Value" }, \
|
||||||
{ LOG_GPS_MSG, sizeof(log_GPS), \
|
{ LOG_GPS_MSG, sizeof(log_GPS), \
|
||||||
|
@ -319,8 +319,6 @@ void DataFlash_File::LogReadProcess(uint16_t log_num,
|
|||||||
::lseek(_read_fd, start_page * DATAFLASH_PAGE_SIZE, SEEK_SET);
|
::lseek(_read_fd, start_page * DATAFLASH_PAGE_SIZE, SEEK_SET);
|
||||||
}
|
}
|
||||||
|
|
||||||
_print_format_headers(num_types, structure, port);
|
|
||||||
|
|
||||||
while (true) {
|
while (true) {
|
||||||
uint8_t data;
|
uint8_t data;
|
||||||
if (::read(_read_fd, &data, 1) != 1) {
|
if (::read(_read_fd, &data, 1) != 1) {
|
||||||
|
@ -247,23 +247,6 @@ uint16_t DataFlash_Block::find_last_page_of_log(uint16_t log_number)
|
|||||||
|
|
||||||
#define PGM_UINT8(addr) pgm_read_byte((const prog_char *)addr)
|
#define PGM_UINT8(addr) pgm_read_byte((const prog_char *)addr)
|
||||||
|
|
||||||
/*
|
|
||||||
print the log column names
|
|
||||||
*/
|
|
||||||
void DataFlash_Class::_print_format_headers(uint8_t num_types,
|
|
||||||
const struct LogStructure *structure,
|
|
||||||
AP_HAL::BetterStream *port)
|
|
||||||
{
|
|
||||||
uint8_t i;
|
|
||||||
for (i=0; i<num_types; i++) {
|
|
||||||
port->printf_P(PSTR("LABL, %S, %u, %S, %S\n"),
|
|
||||||
structure[i].name,
|
|
||||||
(unsigned)PGM_UINT8(&structure[i].msg_type),
|
|
||||||
structure[i].format,
|
|
||||||
structure[i].labels);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
/*
|
/*
|
||||||
read and print a log entry using the format strings from the given structure
|
read and print a log entry using the format strings from the given structure
|
||||||
*/
|
*/
|
||||||
@ -386,6 +369,14 @@ void DataFlash_Class::_print_log_entry(uint8_t msg_type,
|
|||||||
ofs += sizeof(v)-1;
|
ofs += sizeof(v)-1;
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
case 'Z': {
|
||||||
|
char v[65];
|
||||||
|
memcpy(&v, &pkt[ofs], sizeof(v));
|
||||||
|
v[sizeof(v)-1] = 0;
|
||||||
|
port->printf_P(PSTR("%s"), v);
|
||||||
|
ofs += sizeof(v)-1;
|
||||||
|
break;
|
||||||
|
}
|
||||||
case 'M': {
|
case 'M': {
|
||||||
print_mode(port, pkt[ofs]);
|
print_mode(port, pkt[ofs]);
|
||||||
ofs += 1;
|
ofs += 1;
|
||||||
@ -419,8 +410,6 @@ void DataFlash_Block::LogReadProcess(uint16_t log_num,
|
|||||||
FinishWrite();
|
FinishWrite();
|
||||||
}
|
}
|
||||||
|
|
||||||
_print_format_headers(num_types, structure, port);
|
|
||||||
|
|
||||||
StartRead(start_page);
|
StartRead(start_page);
|
||||||
|
|
||||||
while (true) {
|
while (true) {
|
||||||
@ -531,6 +520,8 @@ uint16_t DataFlash_Class::StartNewLog(uint8_t num_types, const struct LogStructu
|
|||||||
// write log formats so the log is self-describing
|
// write log formats so the log is self-describing
|
||||||
for (uint8_t i=0; i<num_types; i++) {
|
for (uint8_t i=0; i<num_types; i++) {
|
||||||
Log_Write_Format(&structures[i]);
|
Log_Write_Format(&structures[i]);
|
||||||
|
// avoid corrupting the APM1/APM2 dataflash by writing too fast
|
||||||
|
hal.scheduler->delay(10);
|
||||||
}
|
}
|
||||||
|
|
||||||
// and all current parameters
|
// and all current parameters
|
||||||
@ -548,10 +539,12 @@ void DataFlash_Class::Log_Write_Format(const struct LogStructure *s)
|
|||||||
type : PGM_UINT8(&s->msg_type),
|
type : PGM_UINT8(&s->msg_type),
|
||||||
length : PGM_UINT8(&s->msg_len),
|
length : PGM_UINT8(&s->msg_len),
|
||||||
name : {},
|
name : {},
|
||||||
format : {}
|
format : {},
|
||||||
|
labels : {}
|
||||||
};
|
};
|
||||||
strncpy_P(pkt.name, s->name, sizeof(pkt.name));
|
strncpy_P(pkt.name, s->name, sizeof(pkt.name));
|
||||||
strncpy_P(pkt.format, s->format, sizeof(pkt.format));
|
strncpy_P(pkt.format, s->format, sizeof(pkt.format));
|
||||||
|
strncpy_P(pkt.labels, s->labels, sizeof(pkt.labels));
|
||||||
WriteBlock(&pkt, sizeof(pkt));
|
WriteBlock(&pkt, sizeof(pkt));
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user