AP_Arming: check all airspeed sensors are healthy

This commit is contained in:
Andrew Tridgell 2017-11-03 19:26:02 +11:00
parent b36911c47d
commit 5229fbd854
1 changed files with 6 additions and 4 deletions

View File

@ -133,11 +133,13 @@ bool AP_Arming::airspeed_checks(bool report)
// not an airspeed capable vehicle
return true;
}
if (airspeed->enabled() && airspeed->use() && !airspeed->healthy()) {
if (report) {
gcs().send_text(MAV_SEVERITY_CRITICAL, "PreArm: Airspeed not healthy");
for (uint8_t i=0; i<AIRSPEED_MAX_SENSORS; i++) {
if (airspeed->enabled(i) && airspeed->use(i) && !airspeed->healthy(i)) {
if (report) {
gcs().send_text(MAV_SEVERITY_CRITICAL, "PreArm: Airspeed[%u] not healthy", i);
}
return false;
}
return false;
}
}