mirror of https://github.com/ArduPilot/ardupilot
AP_GPS: don't consider uBlox PVT time correct unless we have 2D fix
the time may be set by an offline assistance client and may not be accurate
This commit is contained in:
parent
39e75c5b67
commit
681e2d7993
|
@ -1719,8 +1719,10 @@ AP_GPS_UBLOX::_parse_gps(void)
|
|||
state.hdop = _buffer.pvt.p_dop;
|
||||
state.vdop = _buffer.pvt.p_dop;
|
||||
}
|
||||
|
||||
state.last_gps_time_ms = AP_HAL::millis();
|
||||
|
||||
if (_buffer.pvt.fix_type >= 2) {
|
||||
state.last_gps_time_ms = AP_HAL::millis();
|
||||
}
|
||||
|
||||
// time
|
||||
state.time_week_ms = _buffer.pvt.itow;
|
||||
|
|
Loading…
Reference in New Issue