Dataflash: Log GPS delta times

This is particularly useful for assessing if a GPS actually is dropping out in a users log, or if the log is just dropping messages
This commit is contained in:
Michael du Breuil 2017-07-08 16:06:47 -07:00 committed by Francisco Ferreira
parent 04eb7f411e
commit cf02204e6c
2 changed files with 5 additions and 3 deletions

View File

@ -282,7 +282,8 @@ void DataFlash_Class::Log_Write_GPS(const AP_GPS &gps, uint8_t i, uint64_t time_
vacc : (uint16_t)MIN((vacc*100), UINT16_MAX),
sacc : (uint16_t)MIN((sacc*100), UINT16_MAX),
have_vv : (uint8_t)gps.have_vertical_velocity(i),
sample_ms : gps.last_message_time_ms(i)
sample_ms : gps.last_message_time_ms(i),
delta_ms : gps.last_message_delta_time_ms(i)
};
WriteBlock(&pkt2, sizeof(pkt2));
}

View File

@ -79,6 +79,7 @@ struct PACKED log_GPA {
uint16_t sacc;
uint8_t have_vv;
uint32_t sample_ms;
uint16_t delta_ms;
};
struct PACKED log_Message {
@ -909,8 +910,8 @@ struct PACKED log_SRTL {
#define ESC_LABELS "TimeUS,RPM,Volt,Curr,Temp"
#define ESC_FMT "Qcccc"
#define GPA_LABELS "TimeUS,VDop,HAcc,VAcc,SAcc,VV,SMS"
#define GPA_FMT "QCCCCBI"
#define GPA_LABELS "TimeUS,VDop,HAcc,VAcc,SAcc,VV,SMS,Delta"
#define GPA_FMT "QCCCCBIH"
// see "struct GPS_State" and "Log_Write_GPS":
#define GPS_LABELS "TimeUS,Status,GMS,GWk,NSats,HDop,Lat,Lng,Alt,Spd,GCrs,VZ,U"