mirror of https://github.com/ArduPilot/ardupilot
DataFlash: added support for printing flight mode as a string
makes analysing logs easier. Pair-Programmed-With: Randy
This commit is contained in:
parent
c3abdaf308
commit
844e1b9ef9
|
@ -42,6 +42,7 @@ public:
|
||||||
uint16_t start_page, uint16_t end_page,
|
uint16_t start_page, uint16_t end_page,
|
||||||
uint8_t num_types,
|
uint8_t num_types,
|
||||||
const struct LogStructure *structure,
|
const struct LogStructure *structure,
|
||||||
|
void (*printMode)(AP_HAL::BetterStream *port, uint8_t mode),
|
||||||
AP_HAL::BetterStream *port) = 0;
|
AP_HAL::BetterStream *port) = 0;
|
||||||
virtual void DumpPageInfo(AP_HAL::BetterStream *port) = 0;
|
virtual void DumpPageInfo(AP_HAL::BetterStream *port) = 0;
|
||||||
virtual void ShowDeviceInfo(AP_HAL::BetterStream *port) = 0;
|
virtual void ShowDeviceInfo(AP_HAL::BetterStream *port) = 0;
|
||||||
|
@ -76,6 +77,7 @@ protected:
|
||||||
void _print_log_entry(uint8_t msg_type,
|
void _print_log_entry(uint8_t msg_type,
|
||||||
uint8_t num_types,
|
uint8_t num_types,
|
||||||
const struct LogStructure *structure,
|
const struct LogStructure *structure,
|
||||||
|
void (*print_mode)(AP_HAL::BetterStream *port, uint8_t mode),
|
||||||
AP_HAL::BetterStream *port);
|
AP_HAL::BetterStream *port);
|
||||||
|
|
||||||
void Log_Write_Parameter(const AP_Param *ap, const AP_Param::ParamToken &token,
|
void Log_Write_Parameter(const AP_Param *ap, const AP_Param::ParamToken &token,
|
||||||
|
@ -118,6 +120,7 @@ Format characters in the format string for binary log messages
|
||||||
e : int32_t * 100
|
e : int32_t * 100
|
||||||
E : uint32_t * 100
|
E : uint32_t * 100
|
||||||
L : int32_t latitude/longitude
|
L : int32_t latitude/longitude
|
||||||
|
M : uint8_t flight mode
|
||||||
*/
|
*/
|
||||||
|
|
||||||
// structure used to define logging format
|
// structure used to define logging format
|
||||||
|
|
|
@ -39,6 +39,7 @@ public:
|
||||||
uint16_t start_page, uint16_t end_page,
|
uint16_t start_page, uint16_t end_page,
|
||||||
uint8_t num_types,
|
uint8_t num_types,
|
||||||
const struct LogStructure *structure,
|
const struct LogStructure *structure,
|
||||||
|
void (*print_mode)(AP_HAL::BetterStream *port, uint8_t mode),
|
||||||
AP_HAL::BetterStream *port);
|
AP_HAL::BetterStream *port);
|
||||||
void DumpPageInfo(AP_HAL::BetterStream *port);
|
void DumpPageInfo(AP_HAL::BetterStream *port);
|
||||||
void ShowDeviceInfo(AP_HAL::BetterStream *port);
|
void ShowDeviceInfo(AP_HAL::BetterStream *port);
|
||||||
|
|
|
@ -174,7 +174,7 @@ void DataFlash_File::WriteBlock(const void *pBuffer, uint16_t size)
|
||||||
*/
|
*/
|
||||||
void DataFlash_File::ReadBlock(void *pkt, uint16_t size)
|
void DataFlash_File::ReadBlock(void *pkt, uint16_t size)
|
||||||
{
|
{
|
||||||
if (_read_fd == -1 || !_initialised || size <= 3) {
|
if (_read_fd == -1 || !_initialised) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -295,6 +295,7 @@ void DataFlash_File::LogReadProcess(uint16_t log_num,
|
||||||
uint16_t start_page, uint16_t end_page,
|
uint16_t start_page, uint16_t end_page,
|
||||||
uint8_t num_types,
|
uint8_t num_types,
|
||||||
const struct LogStructure *structure,
|
const struct LogStructure *structure,
|
||||||
|
void (*print_mode)(AP_HAL::BetterStream *port, uint8_t mode),
|
||||||
AP_HAL::BetterStream *port)
|
AP_HAL::BetterStream *port)
|
||||||
{
|
{
|
||||||
uint8_t log_step = 0;
|
uint8_t log_step = 0;
|
||||||
|
@ -346,7 +347,7 @@ void DataFlash_File::LogReadProcess(uint16_t log_num,
|
||||||
|
|
||||||
case 2:
|
case 2:
|
||||||
log_step = 0;
|
log_step = 0;
|
||||||
_print_log_entry(data, num_types, structure, port);
|
_print_log_entry(data, num_types, structure, print_mode, port);
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
if (_read_offset >= (end_page+1) * DATAFLASH_PAGE_SIZE) {
|
if (_read_offset >= (end_page+1) * DATAFLASH_PAGE_SIZE) {
|
||||||
|
|
|
@ -36,6 +36,7 @@ public:
|
||||||
uint16_t start_page, uint16_t end_page,
|
uint16_t start_page, uint16_t end_page,
|
||||||
uint8_t num_types,
|
uint8_t num_types,
|
||||||
const struct LogStructure *structure,
|
const struct LogStructure *structure,
|
||||||
|
void (*print_mode)(AP_HAL::BetterStream *port, uint8_t mode),
|
||||||
AP_HAL::BetterStream *port);
|
AP_HAL::BetterStream *port);
|
||||||
void DumpPageInfo(AP_HAL::BetterStream *port);
|
void DumpPageInfo(AP_HAL::BetterStream *port);
|
||||||
void ShowDeviceInfo(AP_HAL::BetterStream *port);
|
void ShowDeviceInfo(AP_HAL::BetterStream *port);
|
||||||
|
|
|
@ -270,6 +270,7 @@ void DataFlash_Class::_print_format_headers(uint8_t num_types,
|
||||||
void DataFlash_Class::_print_log_entry(uint8_t msg_type,
|
void DataFlash_Class::_print_log_entry(uint8_t msg_type,
|
||||||
uint8_t num_types,
|
uint8_t num_types,
|
||||||
const struct LogStructure *structure,
|
const struct LogStructure *structure,
|
||||||
|
void (*print_mode)(AP_HAL::BetterStream *port, uint8_t mode),
|
||||||
AP_HAL::BetterStream *port)
|
AP_HAL::BetterStream *port)
|
||||||
{
|
{
|
||||||
uint8_t i;
|
uint8_t i;
|
||||||
|
@ -385,6 +386,11 @@ void DataFlash_Class::_print_log_entry(uint8_t msg_type,
|
||||||
ofs += sizeof(v)-1;
|
ofs += sizeof(v)-1;
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
case 'M': {
|
||||||
|
print_mode(port, pkt[ofs]);
|
||||||
|
ofs += 1;
|
||||||
|
break;
|
||||||
|
}
|
||||||
default:
|
default:
|
||||||
ofs = msg_len;
|
ofs = msg_len;
|
||||||
break;
|
break;
|
||||||
|
@ -403,6 +409,7 @@ void DataFlash_Block::LogReadProcess(uint16_t log_num,
|
||||||
uint16_t start_page, uint16_t end_page,
|
uint16_t start_page, uint16_t end_page,
|
||||||
uint8_t num_types,
|
uint8_t num_types,
|
||||||
const struct LogStructure *structure,
|
const struct LogStructure *structure,
|
||||||
|
void (*print_mode)(AP_HAL::BetterStream *port, uint8_t mode),
|
||||||
AP_HAL::BetterStream *port)
|
AP_HAL::BetterStream *port)
|
||||||
{
|
{
|
||||||
uint8_t log_step = 0;
|
uint8_t log_step = 0;
|
||||||
|
@ -438,7 +445,7 @@ void DataFlash_Block::LogReadProcess(uint16_t log_num,
|
||||||
|
|
||||||
case 2:
|
case 2:
|
||||||
log_step = 0;
|
log_step = 0;
|
||||||
_print_log_entry(data, num_types, structure, port);
|
_print_log_entry(data, num_types, structure, print_mode, port);
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
uint16_t new_page = GetPage();
|
uint16_t new_page = GetPage();
|
||||||
|
@ -632,4 +639,3 @@ void DataFlash_Class::Log_Write_IMU(const AP_InertialSensor *ins)
|
||||||
};
|
};
|
||||||
WriteBlock(&pkt, sizeof(pkt));
|
WriteBlock(&pkt, sizeof(pkt));
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -108,6 +108,12 @@ void setup()
|
||||||
hal.scheduler->delay(100);
|
hal.scheduler->delay(100);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
static void
|
||||||
|
print_mode(AP_HAL::BetterStream *port, uint8_t mode)
|
||||||
|
{
|
||||||
|
port->printf_P(PSTR("Mode(%u)"), (unsigned)mode);
|
||||||
|
}
|
||||||
|
|
||||||
void loop()
|
void loop()
|
||||||
{
|
{
|
||||||
uint16_t start, end;
|
uint16_t start, end;
|
||||||
|
@ -117,7 +123,9 @@ void loop()
|
||||||
DataFlash.get_log_boundaries(log_num, start, end);
|
DataFlash.get_log_boundaries(log_num, start, end);
|
||||||
DataFlash.LogReadProcess(log_num, start, end,
|
DataFlash.LogReadProcess(log_num, start, end,
|
||||||
sizeof(log_structure)/sizeof(log_structure[0]),
|
sizeof(log_structure)/sizeof(log_structure[0]),
|
||||||
log_structure, hal.console);
|
log_structure,
|
||||||
|
print_mode,
|
||||||
|
hal.console);
|
||||||
hal.console->printf("\nTest complete. Test will repeat in 20 seconds\n");
|
hal.console->printf("\nTest complete. Test will repeat in 20 seconds\n");
|
||||||
hal.scheduler->delay(20000);
|
hal.scheduler->delay(20000);
|
||||||
}
|
}
|
||||||
|
|
Loading…
Reference in New Issue