AP_GPS: tidy is_healthy calculations

this removes some duplicate code and simplifies the flow of control
This commit is contained in:
Peter Barker 2023-06-24 11:27:51 +10:00 committed by Andrew Tridgell
parent da30f0b418
commit bf005731a9

View File

@ -2109,13 +2109,11 @@ bool AP_GPS::is_healthy(uint8_t instance) const
return false; return false;
} }
#ifdef HAL_BUILD_AP_PERIPH #ifndef HAL_BUILD_AP_PERIPH
/* /*
on AP_Periph handling of timing is done by the flight controller on AP_Periph handling of timing is done by the flight controller
receiving the DroneCAN messages receiving the DroneCAN messages
*/ */
return drivers[instance] != nullptr && drivers[instance]->is_healthy();
#else
/* /*
allow two lost frames before declaring the GPS unhealthy, but allow two lost frames before declaring the GPS unhealthy, but
require the average frame rate to be close to 5Hz. We allow for 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) { if (!delay_ok) {
return false; return false;
} }
#endif // HAL_BUILD_AP_PERIPH
#if defined(GPS_BLENDED_INSTANCE) #if defined(GPS_BLENDED_INSTANCE)
if (instance == 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 && return drivers[instance] != nullptr &&
drivers[instance]->is_healthy(); drivers[instance]->is_healthy();
#endif // HAL_BUILD_AP_PERIPH
} }
bool AP_GPS::prepare_for_arming(void) { bool AP_GPS::prepare_for_arming(void) {