Skip to content

Commit

Permalink
AP_Airspeed: healthy: check enabled first for instance range check
Browse files Browse the repository at this point in the history
  • Loading branch information
IamPete1 authored and peterbarker committed Sep 9, 2024
1 parent ae6376f commit b1fe1f1
Showing 1 changed file with 4 additions and 1 deletion.
5 changes: 4 additions & 1 deletion libraries/AP_Airspeed/AP_Airspeed.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -876,7 +876,10 @@ 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) && sensor[i] != nullptr;
if (!enabled(i)) {
return false;
}
bool ok = state[i].healthy && 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);
Expand Down

0 comments on commit b1fe1f1

Please sign in to comment.