AP_Baro: changed health check for AP_Periph

avoid alt check and calibration check
This commit is contained in:
Andrew Tridgell 2021-05-07 08:38:27 +10:00
parent 11e4b62438
commit 0fd335af33
1 changed files with 5 additions and 0 deletions

View File

@ -62,7 +62,12 @@ public:
// healthy - returns true if sensor and derived altitude are good
bool healthy(void) const { return healthy(_primary); }
#ifdef HAL_BUILD_AP_PERIPH
// calibration and alt check not valid for AP_Periph
bool healthy(uint8_t instance) const { return sensors[instance].healthy; }
#else
bool healthy(uint8_t instance) const { return sensors[instance].healthy && sensors[instance].alt_ok && sensors[instance].calibrated; }
#endif
// check if all baros are healthy - used for SYS_STATUS report
bool all_healthy(void) const;