Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

AP_Airspeed: healthy: check enabled first for instance range check #28051

Merged
merged 1 commit into from
Sep 9, 2024
Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
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
Loading