AP_GPS: only use PPS time when there is atleast 2D Fix

This commit is contained in:
bugobliterator 2022-03-12 14:17:28 +05:30 committed by Andrew Tridgell
parent 2dceb9a3ed
commit 79c45049e0

View File

@ -250,11 +250,12 @@ void AP_GPS_Backend::check_new_itow(uint32_t itow, uint32_t msg_length)
// get the time the packet arrived on the UART
uint64_t uart_us;
if (port && _last_pps_time_us == 0) {
uart_us = port->receive_time_constraint_us(msg_length);
} else if (_last_pps_time_us != 0) {
if (_last_pps_time_us != 0 && (state.status >= AP_GPS::GPS_OK_FIX_2D)) {
// pps is only reliable when we have some sort of GPS fix
uart_us = _last_pps_time_us;
_last_pps_time_us = 0;
} else if (port) {
uart_us = port->receive_time_constraint_us(msg_length);
} else {
uart_us = AP_HAL::micros64();
}