mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 10:28:29 -04:00
GPS: fixed a race condition in the ublox driver
the status update comes as a separate message from the lat/lon
This commit is contained in:
parent
a6c1a86c23
commit
b4fbda7a28
@ -173,12 +173,19 @@ AP_GPS_UBLOX::_parse_gps(void)
|
||||
longitude = _buffer.posllh.longitude;
|
||||
latitude = _buffer.posllh.latitude;
|
||||
altitude = _buffer.posllh.altitude_msl / 10;
|
||||
fix = next_fix;
|
||||
break;
|
||||
case MSG_STATUS:
|
||||
fix = (_buffer.status.fix_status & NAV_STATUS_FIX_VALID) && (_buffer.status.fix_type == FIX_3D);
|
||||
next_fix = (_buffer.status.fix_status & NAV_STATUS_FIX_VALID) && (_buffer.status.fix_type == FIX_3D);
|
||||
if (!next_fix) {
|
||||
fix = false;
|
||||
}
|
||||
break;
|
||||
case MSG_SOL:
|
||||
fix = (_buffer.solution.fix_status & NAV_STATUS_FIX_VALID) && (_buffer.solution.fix_type == FIX_3D);
|
||||
next_fix = (_buffer.solution.fix_status & NAV_STATUS_FIX_VALID) && (_buffer.solution.fix_type == FIX_3D);
|
||||
if (!next_fix) {
|
||||
fix = false;
|
||||
}
|
||||
num_sats = _buffer.solution.satellites;
|
||||
hdop = _buffer.solution.position_DOP;
|
||||
break;
|
||||
|
@ -119,6 +119,9 @@ private:
|
||||
|
||||
// Buffer parse & GPS state update
|
||||
bool _parse_gps();
|
||||
|
||||
// used to update fix between status and position packets
|
||||
bool next_fix;
|
||||
};
|
||||
|
||||
#endif
|
||||
|
Loading…
Reference in New Issue
Block a user