mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
DataFlash: removed logging of relative alt in GPS messages
not related to GPS and makes it impossible to do bit-identical replay
This commit is contained in:
parent
223c512188
commit
7ab1367ec4
@ -105,7 +105,7 @@ public:
|
||||
void StopLogging();
|
||||
|
||||
void Log_Write_Parameter(const char *name, float value);
|
||||
void Log_Write_GPS(const AP_GPS &gps, uint8_t instance, int32_t relative_alt);
|
||||
void Log_Write_GPS(const AP_GPS &gps, uint8_t instance);
|
||||
void Log_Write_RFND(const RangeFinder &rangefinder);
|
||||
void Log_Write_IMU(const AP_InertialSensor &ins);
|
||||
void Log_Write_IMUDT(const AP_InertialSensor &ins);
|
||||
|
@ -707,7 +707,7 @@ bool DataFlash_Backend::Log_Write_Parameter(const AP_Param *ap,
|
||||
}
|
||||
|
||||
// Write an GPS packet
|
||||
void DataFlash_Class::Log_Write_GPS(const AP_GPS &gps, uint8_t i, int32_t relative_alt)
|
||||
void DataFlash_Class::Log_Write_GPS(const AP_GPS &gps, uint8_t i)
|
||||
{
|
||||
const struct Location &loc = gps.location(i);
|
||||
struct log_GPS pkt = {
|
||||
@ -720,7 +720,6 @@ void DataFlash_Class::Log_Write_GPS(const AP_GPS &gps, uint8_t i, int32_t relati
|
||||
hdop : gps.get_hdop(i),
|
||||
latitude : loc.lat,
|
||||
longitude : loc.lng,
|
||||
rel_altitude : relative_alt,
|
||||
altitude : loc.alt,
|
||||
ground_speed : (uint32_t)(gps.ground_speed(i) * 100),
|
||||
ground_course : gps.ground_course_cd(i),
|
||||
|
@ -51,7 +51,6 @@ struct PACKED log_GPS {
|
||||
uint16_t hdop;
|
||||
int32_t latitude;
|
||||
int32_t longitude;
|
||||
int32_t rel_altitude;
|
||||
int32_t altitude;
|
||||
uint32_t ground_speed;
|
||||
int32_t ground_course;
|
||||
@ -714,9 +713,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", "QBIHBcLLeeEefB", "TimeUS,Status,GMS,GWk,NSats,HDop,Lat,Lng,RAlt,Alt,Spd,GCrs,VZ,U" }, \
|
||||
"GPS", "QBIHBcLLeEefB", "TimeUS,Status,GMS,GWk,NSats,HDop,Lat,Lng,Alt,Spd,GCrs,VZ,U" }, \
|
||||
{ LOG_GPS2_MSG, sizeof(log_GPS), \
|
||||
"GPS2", "QBIHBcLLeeEefB", "TimeUS,Status,GMS,GWk,NSats,HDop,Lat,Lng,RAlt,Alt,Spd,GCrs,VZ,U" }, \
|
||||
"GPS2", "QBIHBcLLeEefB", "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