mirror of https://github.com/ArduPilot/ardupilot
DataFlash: log the last message sample time for GPS
This commit is contained in:
parent
428923b4b1
commit
2f4f38b85f
|
@ -743,7 +743,8 @@ void DataFlash_Class::Log_Write_GPS(const AP_GPS &gps, uint8_t i, uint64_t time_
|
|||
hacc : (uint16_t)(hacc*100),
|
||||
vacc : (uint16_t)(vacc*100),
|
||||
sacc : (uint16_t)(sacc*100),
|
||||
have_vv : (uint8_t)gps.have_vertical_velocity(i)
|
||||
have_vv : (uint8_t)gps.have_vertical_velocity(i),
|
||||
sample_ms : gps.last_message_time_ms(i)
|
||||
};
|
||||
WriteBlock(&pkt2, sizeof(pkt2));
|
||||
}
|
||||
|
|
|
@ -66,6 +66,7 @@ struct PACKED log_GPA {
|
|||
uint16_t vacc;
|
||||
uint16_t sacc;
|
||||
uint8_t have_vv;
|
||||
uint32_t sample_ms;
|
||||
};
|
||||
|
||||
struct PACKED log_Message {
|
||||
|
@ -720,9 +721,9 @@ Format characters in the format string for binary log messages
|
|||
{ LOG_GPS2_MSG, sizeof(log_GPS), \
|
||||
"GPS2", "QBIHBcLLefefB", "TimeUS,Status,GMS,GWk,NSats,HDop,Lat,Lng,Alt,Spd,GCrs,VZ,U" }, \
|
||||
{ LOG_GPA_MSG, sizeof(log_GPA), \
|
||||
"GPA", "QCCCCB", "TimeUS,VDop,HAcc,VAcc,SAcc,VV" }, \
|
||||
"GPA", "QCCCCBI", "TimeUS,VDop,HAcc,VAcc,SAcc,VV,SMS" }, \
|
||||
{ LOG_GPA2_MSG, sizeof(log_GPA), \
|
||||
"GPA2", "QCCCCB", "TimeUS,VDop,HAcc,VAcc,SAcc,VV" }, \
|
||||
"GPA2", "QCCCCBI", "TimeUS,VDop,HAcc,VAcc,SAcc,VV,SMS" }, \
|
||||
{ LOG_IMU_MSG, sizeof(log_IMU), \
|
||||
"IMU", "QffffffIIfBB", "TimeUS,GyrX,GyrY,GyrZ,AccX,AccY,AccZ,ErrG,ErrA,Temp,GyHlt,AcHlt" }, \
|
||||
{ LOG_MESSAGE_MSG, sizeof(log_Message), \
|
||||
|
|
Loading…
Reference in New Issue