AP_GPS: fixed AP_Periph build with gcc 9.x

This commit is contained in:
Andrew Tridgell 2020-03-30 09:17:39 +11:00
parent 4456732911
commit 077ab22767

View File

@ -739,6 +739,7 @@ void AP_GPS::update_instance(uint8_t instance)
data_should_be_logged = true;
}
#if GPS_MAX_RECEIVERS > 1
if (drivers[instance] && _type[instance] == GPS_TYPE_UBLOX_RTK_BASE) {
// see if a moving baseline base has some RTCMv3 data
// which we need to pass along to the rover
@ -755,6 +756,7 @@ void AP_GPS::update_instance(uint8_t instance)
}
}
}
#endif
#ifndef HAL_BUILD_AP_PERIPH
if (data_should_be_logged &&