mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
DataFlash: switched to float for GPS ground speed
same size and more precision
This commit is contained in:
parent
0571f86c17
commit
d61ba14037
@ -721,7 +721,7 @@ void DataFlash_Class::Log_Write_GPS(const AP_GPS &gps, uint8_t i)
|
||||
latitude : loc.lat,
|
||||
longitude : loc.lng,
|
||||
altitude : loc.alt,
|
||||
ground_speed : (uint32_t)(gps.ground_speed(i) * 100),
|
||||
ground_speed : gps.ground_speed(i),
|
||||
ground_course : gps.ground_course_cd(i),
|
||||
vel_z : gps.velocity(i).z,
|
||||
used : (uint8_t)(gps.primary_sensor() == i)
|
||||
|
@ -52,7 +52,7 @@ struct PACKED log_GPS {
|
||||
int32_t latitude;
|
||||
int32_t longitude;
|
||||
int32_t altitude;
|
||||
uint32_t ground_speed;
|
||||
float ground_speed;
|
||||
int32_t ground_course;
|
||||
float vel_z;
|
||||
uint8_t used;
|
||||
@ -714,9 +714,9 @@ Format characters in the format string for binary log messages
|
||||
{ LOG_PARAMETER_MSG, sizeof(log_Parameter), \
|
||||
"PARM", "QNf", "TimeUS,Name,Value" }, \
|
||||
{ LOG_GPS_MSG, sizeof(log_GPS), \
|
||||
"GPS", "QBIHBcLLeEefB", "TimeUS,Status,GMS,GWk,NSats,HDop,Lat,Lng,Alt,Spd,GCrs,VZ,U" }, \
|
||||
"GPS", "QBIHBcLLefefB", "TimeUS,Status,GMS,GWk,NSats,HDop,Lat,Lng,Alt,Spd,GCrs,VZ,U" }, \
|
||||
{ LOG_GPS2_MSG, sizeof(log_GPS), \
|
||||
"GPS2", "QBIHBcLLeEefB", "TimeUS,Status,GMS,GWk,NSats,HDop,Lat,Lng,Alt,Spd,GCrs,VZ,U" }, \
|
||||
"GPS2", "QBIHBcLLefefB", "TimeUS,Status,GMS,GWk,NSats,HDop,Lat,Lng,Alt,Spd,GCrs,VZ,U" }, \
|
||||
{ LOG_GPA_MSG, sizeof(log_GPA), \
|
||||
"GPA", "QCCCC", "TimeUS,VDop,HAcc,VAcc,SAcc" }, \
|
||||
{ LOG_GPA2_MSG, sizeof(log_GPA), \
|
||||
|
Loading…
Reference in New Issue
Block a user