Wrong RTC time when using u-blox F9P

Hi, I have been flying with the u-blox F9P GNSS receiver lately, using the 3.9.9 beta where support for it was added.

I noticed that even if the autoconfig enables the NAV-TIMEGPS message used to get the GPS week, the date in the dataflash logs are wrong for most of the logs (once in a while after rebooting it is correct). The date corresponds to GPS week 0, but the correct time of week (today this gives logs with date 1980-1-11). After looking at the code, I find that AP_GPS::update_instance will set the time of the RTC as long as we have 3D fix, even if a NAV-TIMEGPS message has not yet been received (autoconfig sets this up with a 1 Hz rate) such that the week number has not yet been set:

if (state[instance].status >= GPS_OK_FIX_3D) {
    const uint64_t now = time_epoch_usec(instance);
    AP::rtc().set_utc_usec(now, AP_RTC::SOURCE_GPS);
}

(here)
This will happen if a NAV-PVT message is received (received at 5 Hz) and AP_GPS::update_instance (called at 10Hz or greater) runs before the NAV-TIMEGPS message is received. Since the RTC will never allow the GPS to set its time a second time after getting a valid week, this date error persists until a reboot where it is likely to happen again.

2 Likes

thanks!
PR to fix it here: https://github.com/ArduPilot/ardupilot/pull/11917

1 Like