SITL: send sv_info from both GPS instances

Without sv_info we don't get the correct ublox type, meaning we get the wrong lag time, meaning EKF2 gets rather more annoyed than it should when we do loops in SITL.
This commit is contained in:
Peter Barker 2021-11-05 13:50:42 +11:00 committed by Peter Barker
parent 8a4001817b
commit a88464c928

View File

@ -310,7 +310,7 @@ void GPS::update_ubx(const struct gps_data *d)
const uint8_t MSG_SVINFO = 0x30; const uint8_t MSG_SVINFO = 0x30;
const uint8_t MSG_RELPOSNED = 0x3c; const uint8_t MSG_RELPOSNED = 0x3c;
static uint32_t _next_nav_sv_info_time = 0; uint32_t _next_nav_sv_info_time = 0;
uint16_t time_week; uint16_t time_week;
uint32_t time_week_ms; uint32_t time_week_ms;