mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Replay: print message when gap perceived in log
This commit is contained in:
parent
f6c7a73170
commit
eefdc32f51
@ -445,6 +445,14 @@ void LR_MsgHandler_PARM::process_message(uint8_t *msg)
|
||||
}
|
||||
}
|
||||
|
||||
void LR_MsgHandler_PM::process_message(uint8_t *msg)
|
||||
{
|
||||
uint32_t new_logdrop;
|
||||
if (field_value(msg, "LogDrop", new_logdrop) &&
|
||||
new_logdrop != 0) {
|
||||
printf("PM.LogDrop: %u dropped at timestamp %lu\n", new_logdrop, last_timestamp_usec);
|
||||
}
|
||||
}
|
||||
|
||||
void LR_MsgHandler_SIM::process_message(uint8_t *msg)
|
||||
{
|
||||
|
@ -435,6 +435,18 @@ public:
|
||||
virtual void process_message(uint8_t *msg);
|
||||
};
|
||||
|
||||
class LR_MsgHandler_PM : public LR_MsgHandler
|
||||
{
|
||||
public:
|
||||
LR_MsgHandler_PM(log_Format &_f, DataFlash_Class &_dataflash,
|
||||
uint64_t &_last_timestamp_usec)
|
||||
: LR_MsgHandler(_f, _dataflash, _last_timestamp_usec) { };
|
||||
|
||||
virtual void process_message(uint8_t *msg);
|
||||
|
||||
private:
|
||||
|
||||
};
|
||||
|
||||
class LR_MsgHandler_SIM : public LR_MsgHandler
|
||||
{
|
||||
|
@ -266,6 +266,9 @@ bool LogReader::handle_log_format_msg(const struct log_Format &f)
|
||||
msgparser[f.type] = new LR_MsgHandler_CHEK(formats[f.type], dataflash,
|
||||
last_timestamp_usec,
|
||||
check_state);
|
||||
} else if (streq(name, "PM")) {
|
||||
msgparser[f.type] = new LR_MsgHandler_PM(formats[f.type], dataflash,
|
||||
last_timestamp_usec);
|
||||
} else {
|
||||
debug(" No parser for (%s)\n", name);
|
||||
}
|
||||
|
@ -765,6 +765,7 @@ void Replay::log_check_solution(void)
|
||||
|
||||
void Replay::loop()
|
||||
{
|
||||
uint64_t last_timestamp = 0;
|
||||
while (true) {
|
||||
char type[5];
|
||||
|
||||
@ -780,6 +781,16 @@ void Replay::loop()
|
||||
fclose(plotf);
|
||||
break;
|
||||
}
|
||||
|
||||
if (last_timestamp != 0) {
|
||||
uint64_t gap = AP_HAL::micros64() - last_timestamp;
|
||||
if (gap > 40000) {
|
||||
::printf("Gap in log at timestamp=%lu of length %luus\n",
|
||||
last_timestamp, gap);
|
||||
}
|
||||
}
|
||||
last_timestamp = AP_HAL::micros64();
|
||||
|
||||
read_sensors(type);
|
||||
|
||||
if (streq(type,"ATT")) {
|
||||
|
Loading…
Reference in New Issue
Block a user