mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Airspeed: allow zero offset if we are skipping calibration
This commit is contained in:
parent
bf695e4eeb
commit
16c11fc4fa
@ -123,7 +123,8 @@ public:
|
||||
bool healthy(uint8_t i) const {
|
||||
bool ok = state[i].healthy && enabled(i);
|
||||
#ifndef HAL_BUILD_AP_PERIPH
|
||||
ok &= (fabsf(param[i].offset) > 0 || state[i].use_zero_offset);
|
||||
// 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);
|
||||
#endif
|
||||
return ok;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user