AP_Airspeed: Add nullptr check to healthy function

This commit is contained in:
Gone4Dirt 2022-04-20 10:07:57 +01:00 committed by Peter Barker
parent edb25340d1
commit e82ba228ce
1 changed files with 1 additions and 1 deletions

View File

@ -747,7 +747,7 @@ bool AP_Airspeed::enabled(uint8_t i) const {
// return health status of sensor
bool AP_Airspeed::healthy(uint8_t i) const {
bool ok = state[i].healthy && enabled(i);
bool ok = state[i].healthy && enabled(i) && sensor[i] != nullptr;
#ifndef HAL_BUILD_AP_PERIPH
// sanity check the offset parameter. Zero is permitted if we are skipping calibration.
ok &= (fabsf(param[i].offset) > 0 || state[i].use_zero_offset || param[i].skip_cal);