mirror of https://github.com/ArduPilot/ardupilot
DataFlash: convert GPS and CAM dataflash messages to 64-bit timestamps
GPS structures remove 32-bit apm_time and replace with standard time_us Significant change to GPS and GPS2 messages: Add TimeUS as first field Remove T field Due to length restrictions on labels: Renamed TimeMS to GMS (Gps MilliSeconds) Renamed Week to GWk (Gps WeeK) Renamed RelAlt to RAlt Significant change to CAM messages: Removed GPSTime (uin32_t), added TimeUS (uint64_t)
This commit is contained in:
parent
769982b8f2
commit
617043f468
|
@ -169,6 +169,7 @@ struct PACKED log_Parameter {
|
||||||
|
|
||||||
struct PACKED log_GPS {
|
struct PACKED log_GPS {
|
||||||
LOG_PACKET_HEADER;
|
LOG_PACKET_HEADER;
|
||||||
|
uint64_t time_us;
|
||||||
uint8_t status;
|
uint8_t status;
|
||||||
uint32_t gps_week_ms;
|
uint32_t gps_week_ms;
|
||||||
uint16_t gps_week;
|
uint16_t gps_week;
|
||||||
|
@ -181,11 +182,11 @@ struct PACKED log_GPS {
|
||||||
uint32_t ground_speed;
|
uint32_t ground_speed;
|
||||||
int32_t ground_course;
|
int32_t ground_course;
|
||||||
float vel_z;
|
float vel_z;
|
||||||
uint32_t apm_time;
|
|
||||||
};
|
};
|
||||||
|
|
||||||
struct PACKED log_GPS2 {
|
struct PACKED log_GPS2 {
|
||||||
LOG_PACKET_HEADER;
|
LOG_PACKET_HEADER;
|
||||||
|
uint64_t time_us;
|
||||||
uint8_t status;
|
uint8_t status;
|
||||||
uint32_t gps_week_ms;
|
uint32_t gps_week_ms;
|
||||||
uint16_t gps_week;
|
uint16_t gps_week;
|
||||||
|
@ -197,7 +198,6 @@ struct PACKED log_GPS2 {
|
||||||
uint32_t ground_speed;
|
uint32_t ground_speed;
|
||||||
int32_t ground_course;
|
int32_t ground_course;
|
||||||
float vel_z;
|
float vel_z;
|
||||||
uint32_t apm_time;
|
|
||||||
uint8_t dgps_numch;
|
uint8_t dgps_numch;
|
||||||
uint32_t dgps_age;
|
uint32_t dgps_age;
|
||||||
};
|
};
|
||||||
|
@ -399,6 +399,7 @@ struct PACKED log_Radio {
|
||||||
|
|
||||||
struct PACKED log_Camera {
|
struct PACKED log_Camera {
|
||||||
LOG_PACKET_HEADER;
|
LOG_PACKET_HEADER;
|
||||||
|
uint64_t time_us;
|
||||||
uint32_t gps_time;
|
uint32_t gps_time;
|
||||||
uint16_t gps_week;
|
uint16_t gps_week;
|
||||||
int32_t latitude;
|
int32_t latitude;
|
||||||
|
@ -582,7 +583,7 @@ Format characters in the format string for binary log messages
|
||||||
{ LOG_PARAMETER_MSG, sizeof(log_Parameter), \
|
{ LOG_PARAMETER_MSG, sizeof(log_Parameter), \
|
||||||
"PARM", "QNf", "TimeUS,Name,Value" }, \
|
"PARM", "QNf", "TimeUS,Name,Value" }, \
|
||||||
{ LOG_GPS_MSG, sizeof(log_GPS), \
|
{ LOG_GPS_MSG, sizeof(log_GPS), \
|
||||||
"GPS", "BIHBcLLeeEefI", "Status,TimeMS,Week,NSats,HDop,Lat,Lng,RelAlt,Alt,Spd,GCrs,VZ,T" }, \
|
"GPS", "QBIHBcLLeeEef", "TimeUS,Status,GMS,GWk,NSats,HDop,Lat,Lng,RAlt,Alt,Spd,GCrs,VZ" }, \
|
||||||
{ LOG_IMU_MSG, sizeof(log_IMU), \
|
{ LOG_IMU_MSG, sizeof(log_IMU), \
|
||||||
"IMU", "QffffffIIfBB", "TimeUS,GyrX,GyrY,GyrZ,AccX,AccY,AccZ,ErrG,ErrA,Temp,GyHlt,AcHlt" }, \
|
"IMU", "QffffffIIfBB", "TimeUS,GyrX,GyrY,GyrZ,AccX,AccY,AccZ,ErrG,ErrA,Temp,GyHlt,AcHlt" }, \
|
||||||
{ LOG_MESSAGE_MSG, sizeof(log_Message), \
|
{ LOG_MESSAGE_MSG, sizeof(log_Message), \
|
||||||
|
@ -602,7 +603,7 @@ Format characters in the format string for binary log messages
|
||||||
{ LOG_RADIO_MSG, sizeof(log_Radio), \
|
{ LOG_RADIO_MSG, sizeof(log_Radio), \
|
||||||
"RAD", "QBBBBBHH", "TimeUS,RSSI,RemRSSI,TxBuf,Noise,RemNoise,RxErrors,Fixed" }, \
|
"RAD", "QBBBBBHH", "TimeUS,RSSI,RemRSSI,TxBuf,Noise,RemNoise,RxErrors,Fixed" }, \
|
||||||
{ LOG_CAMERA_MSG, sizeof(log_Camera), \
|
{ LOG_CAMERA_MSG, sizeof(log_Camera), \
|
||||||
"CAM", "IHLLeeccC","GPSTime,GPSWeek,Lat,Lng,Alt,RelAlt,Roll,Pitch,Yaw" }, \
|
"CAM", "QHLLeeccC","TimeUS,GPSTime,GPSWeek,Lat,Lng,Alt,RelAlt,Roll,Pitch,Yaw" }, \
|
||||||
{ LOG_ARSP_MSG, sizeof(log_AIRSPEED), \
|
{ LOG_ARSP_MSG, sizeof(log_AIRSPEED), \
|
||||||
"ARSP", "Qffcff", "TimeUS,Airspeed,DiffPress,Temp,RawPress,Offset" }, \
|
"ARSP", "Qffcff", "TimeUS,Airspeed,DiffPress,Temp,RawPress,Offset" }, \
|
||||||
{ LOG_CURRENT_MSG, sizeof(log_Current), \
|
{ LOG_CURRENT_MSG, sizeof(log_Current), \
|
||||||
|
@ -617,7 +618,7 @@ Format characters in the format string for binary log messages
|
||||||
// messages for more advanced boards
|
// messages for more advanced boards
|
||||||
#define LOG_EXTRA_STRUCTURES \
|
#define LOG_EXTRA_STRUCTURES \
|
||||||
{ LOG_GPS2_MSG, sizeof(log_GPS2), \
|
{ LOG_GPS2_MSG, sizeof(log_GPS2), \
|
||||||
"GPS2", "BIHBcLLeEefIBI", "Status,TimeMS,Week,NSats,HDop,Lat,Lng,Alt,Spd,GCrs,VZ,T,DSc,DAg" }, \
|
"GPS2", "QBIHBcLLeEefBI", "TimeUS,Status,GMS,GWk,NSats,HDp,Lat,Lng,Alt,Spd,GCrs,VZ,DSc,DAg" }, \
|
||||||
{ LOG_IMU2_MSG, sizeof(log_IMU), \
|
{ LOG_IMU2_MSG, sizeof(log_IMU), \
|
||||||
"IMU2", "QffffffIIfBB", "TimeUS,GyrX,GyrY,GyrZ,AccX,AccY,AccZ,ErrG,ErrA,Temp,GyHlt,AcHlt" }, \
|
"IMU2", "QffffffIIfBB", "TimeUS,GyrX,GyrY,GyrZ,AccX,AccY,AccZ,ErrG,ErrA,Temp,GyHlt,AcHlt" }, \
|
||||||
{ LOG_IMU3_MSG, sizeof(log_IMU), \
|
{ LOG_IMU3_MSG, sizeof(log_IMU), \
|
||||||
|
|
|
@ -668,6 +668,7 @@ void DataFlash_Class::Log_Write_GPS(const AP_GPS &gps, uint8_t i, int32_t relati
|
||||||
const struct Location &loc = gps.location(i);
|
const struct Location &loc = gps.location(i);
|
||||||
struct log_GPS pkt = {
|
struct log_GPS pkt = {
|
||||||
LOG_PACKET_HEADER_INIT(LOG_GPS_MSG),
|
LOG_PACKET_HEADER_INIT(LOG_GPS_MSG),
|
||||||
|
time_us : hal.scheduler->micros64(),
|
||||||
status : (uint8_t)gps.status(i),
|
status : (uint8_t)gps.status(i),
|
||||||
gps_week_ms : gps.time_week_ms(i),
|
gps_week_ms : gps.time_week_ms(i),
|
||||||
gps_week : gps.time_week(i),
|
gps_week : gps.time_week(i),
|
||||||
|
@ -680,7 +681,6 @@ void DataFlash_Class::Log_Write_GPS(const AP_GPS &gps, uint8_t i, int32_t relati
|
||||||
ground_speed : (uint32_t)(gps.ground_speed(i) * 100),
|
ground_speed : (uint32_t)(gps.ground_speed(i) * 100),
|
||||||
ground_course : gps.ground_course_cd(i),
|
ground_course : gps.ground_course_cd(i),
|
||||||
vel_z : gps.velocity(i).z,
|
vel_z : gps.velocity(i).z,
|
||||||
apm_time : hal.scheduler->millis()
|
|
||||||
};
|
};
|
||||||
WriteBlock(&pkt, sizeof(pkt));
|
WriteBlock(&pkt, sizeof(pkt));
|
||||||
}
|
}
|
||||||
|
@ -689,6 +689,7 @@ void DataFlash_Class::Log_Write_GPS(const AP_GPS &gps, uint8_t i, int32_t relati
|
||||||
const struct Location &loc2 = gps.location(i);
|
const struct Location &loc2 = gps.location(i);
|
||||||
struct log_GPS2 pkt2 = {
|
struct log_GPS2 pkt2 = {
|
||||||
LOG_PACKET_HEADER_INIT(LOG_GPS2_MSG),
|
LOG_PACKET_HEADER_INIT(LOG_GPS2_MSG),
|
||||||
|
time_us : hal.scheduler->micros64(),
|
||||||
status : (uint8_t)gps.status(i),
|
status : (uint8_t)gps.status(i),
|
||||||
gps_week_ms : gps.time_week_ms(i),
|
gps_week_ms : gps.time_week_ms(i),
|
||||||
gps_week : gps.time_week(i),
|
gps_week : gps.time_week(i),
|
||||||
|
@ -700,7 +701,6 @@ void DataFlash_Class::Log_Write_GPS(const AP_GPS &gps, uint8_t i, int32_t relati
|
||||||
ground_speed : (uint32_t)(gps.ground_speed(i)*100),
|
ground_speed : (uint32_t)(gps.ground_speed(i)*100),
|
||||||
ground_course : gps.ground_course_cd(i),
|
ground_course : gps.ground_course_cd(i),
|
||||||
vel_z : gps.velocity(i).z,
|
vel_z : gps.velocity(i).z,
|
||||||
apm_time : hal.scheduler->millis(),
|
|
||||||
dgps_numch : 0,
|
dgps_numch : 0,
|
||||||
dgps_age : 0
|
dgps_age : 0
|
||||||
};
|
};
|
||||||
|
@ -1125,6 +1125,7 @@ void DataFlash_Class::Log_Write_Camera(const AP_AHRS &ahrs, const AP_GPS &gps, c
|
||||||
|
|
||||||
struct log_Camera pkt = {
|
struct log_Camera pkt = {
|
||||||
LOG_PACKET_HEADER_INIT(LOG_CAMERA_MSG),
|
LOG_PACKET_HEADER_INIT(LOG_CAMERA_MSG),
|
||||||
|
time_us : hal.scheduler->micros64(),
|
||||||
gps_time : gps.time_week_ms(),
|
gps_time : gps.time_week_ms(),
|
||||||
gps_week : gps.time_week(),
|
gps_week : gps.time_week(),
|
||||||
latitude : current_loc.lat,
|
latitude : current_loc.lat,
|
||||||
|
|
Loading…
Reference in New Issue