diff --git a/libraries/AP_GPS/AP_GPS.cpp b/libraries/AP_GPS/AP_GPS.cpp index c6e24f10a3..96ac8a49bb 100644 --- a/libraries/AP_GPS/AP_GPS.cpp +++ b/libraries/AP_GPS/AP_GPS.cpp @@ -2109,13 +2109,11 @@ bool AP_GPS::is_healthy(uint8_t instance) const return false; } -#ifdef HAL_BUILD_AP_PERIPH +#ifndef HAL_BUILD_AP_PERIPH /* on AP_Periph handling of timing is done by the flight controller receiving the DroneCAN messages */ - return drivers[instance] != nullptr && drivers[instance]->is_healthy(); -#else /* allow two lost frames before declaring the GPS unhealthy, but require the average frame rate to be close to 5Hz. We allow for @@ -2131,6 +2129,7 @@ bool AP_GPS::is_healthy(uint8_t instance) const if (!delay_ok) { return false; } +#endif // HAL_BUILD_AP_PERIPH #if defined(GPS_BLENDED_INSTANCE) if (instance == GPS_BLENDED_INSTANCE) { @@ -2140,7 +2139,6 @@ bool AP_GPS::is_healthy(uint8_t instance) const return drivers[instance] != nullptr && drivers[instance]->is_healthy(); -#endif // HAL_BUILD_AP_PERIPH } bool AP_GPS::prepare_for_arming(void) {