mirror of https://github.com/ArduPilot/ardupilot
AP_Airspeed: Add nullptr check to healthy function
This commit is contained in:
parent
edb25340d1
commit
e82ba228ce
|
@ -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);
|
||||
|
|
Loading…
Reference in New Issue