mirror of https://github.com/ArduPilot/ardupilot
AP_GPS: Fix accidental quantization to float on SBF logging
This commit is contained in:
parent
af6303c82b
commit
70e587b572
|
@ -250,8 +250,8 @@ AP_GPS_SBF::log_ExtEventPVTGeodetic(const msg4007 &temp)
|
|||
WNc:temp.WNc,
|
||||
Mode:temp.Mode,
|
||||
Error:temp.Error,
|
||||
Latitude:ToDeg(temp.Latitude),
|
||||
Longitude:ToDeg(temp.Longitude),
|
||||
Latitude:temp.Latitude*RAD_TO_DEG_DOUBLE,
|
||||
Longitude:temp.Longitude*RAD_TO_DEG_DOUBLE,
|
||||
Height:temp.Height,
|
||||
Undulation:temp.Undulation,
|
||||
Vn:temp.Vn,
|
||||
|
|
Loading…
Reference in New Issue