mirror of https://github.com/ArduPilot/ardupilot
AP_GPS: fixed resolution of KSXT parsing for NMEA
needs to be double precision for lat/lon
This commit is contained in:
parent
4812b67ad6
commit
6f805cb537
|
@ -389,7 +389,7 @@ bool AP_GPS_NMEA::_term_complete()
|
|||
state.ground_speed = state.velocity.xy().length();
|
||||
_last_3D_velocity_ms = now;
|
||||
}
|
||||
if (is_equal(3.0f, _ksxt.fields[10])) {
|
||||
if (is_equal(3.0f, float(_ksxt.fields[10]))) {
|
||||
// have good yaw (from RTK fixed moving baseline solution)
|
||||
_last_yaw_ms = now;
|
||||
state.gps_yaw = _ksxt.fields[4];
|
||||
|
|
|
@ -188,7 +188,7 @@ private:
|
|||
example: $KSXT,20211016083433.00,116.31296102,39.95817066,49.4911,223.57,-11.32,330.19,0.024,,1,3,28,27,,,,-0.012,0.021,0.020,,*2D
|
||||
*/
|
||||
struct {
|
||||
float fields[21];
|
||||
double fields[21];
|
||||
} _ksxt;
|
||||
|
||||
};
|
||||
|
|
Loading…
Reference in New Issue