mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 09:58:28 -04:00
DataFlash: updates for new GPS API
This commit is contained in:
parent
19ba07a3f9
commit
d7a9888e26
@ -141,7 +141,8 @@ struct PACKED log_Parameter {
|
|||||||
struct PACKED log_GPS {
|
struct PACKED log_GPS {
|
||||||
LOG_PACKET_HEADER;
|
LOG_PACKET_HEADER;
|
||||||
uint8_t status;
|
uint8_t status;
|
||||||
uint32_t gps_time;
|
uint32_t gps_week_ms;
|
||||||
|
uint16_t gps_week;
|
||||||
uint8_t num_sats;
|
uint8_t num_sats;
|
||||||
int16_t hdop;
|
int16_t hdop;
|
||||||
int32_t latitude;
|
int32_t latitude;
|
||||||
@ -169,7 +170,7 @@ struct PACKED log_IMU {
|
|||||||
{ LOG_PARAMETER_MSG, sizeof(log_Parameter), \
|
{ LOG_PARAMETER_MSG, sizeof(log_Parameter), \
|
||||||
"PARM", "Nf", "Name,Value" }, \
|
"PARM", "Nf", "Name,Value" }, \
|
||||||
{ LOG_GPS_MSG, sizeof(log_GPS), \
|
{ LOG_GPS_MSG, sizeof(log_GPS), \
|
||||||
"GPS", "BIBcLLeeEe", "Status,Time,NSats,HDop,Lat,Lng,RelAlt,Alt,Spd,GCrs" }, \
|
"GPS", "BIHBcLLeeEe", "Status,TimeMS,Week,NSats,HDop,Lat,Lng,RelAlt,Alt,Spd,GCrs" }, \
|
||||||
{ LOG_IMU_MSG, sizeof(log_IMU), \
|
{ LOG_IMU_MSG, sizeof(log_IMU), \
|
||||||
"IMU", "ffffff", "GyrX,GyrY,GyrZ,AccX,AccY,AccZ" }, \
|
"IMU", "ffffff", "GyrX,GyrY,GyrZ,AccX,AccY,AccZ" }, \
|
||||||
{ LOG_MESSAGE_MSG, sizeof(log_Message), \
|
{ LOG_MESSAGE_MSG, sizeof(log_Message), \
|
||||||
|
@ -606,7 +606,8 @@ void DataFlash_Class::Log_Write_GPS(const GPS *gps, int32_t relative_alt)
|
|||||||
struct log_GPS pkt = {
|
struct log_GPS pkt = {
|
||||||
LOG_PACKET_HEADER_INIT(LOG_GPS_MSG),
|
LOG_PACKET_HEADER_INIT(LOG_GPS_MSG),
|
||||||
status : (uint8_t)gps->status(),
|
status : (uint8_t)gps->status(),
|
||||||
gps_time : gps->time,
|
gps_week_ms : gps->time_week_ms,
|
||||||
|
gps_week : gps->time_week,
|
||||||
num_sats : gps->num_sats,
|
num_sats : gps->num_sats,
|
||||||
hdop : gps->hdop,
|
hdop : gps->hdop,
|
||||||
latitude : gps->latitude,
|
latitude : gps->latitude,
|
||||||
|
Loading…
Reference in New Issue
Block a user