mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 13:38:38 -04:00
GCS_MAVLink: report airspeed unhealthy when being rejected
this gives the pilot feedback on airspeed failing EKF innnovation checks and switching to synthetic airspeed
This commit is contained in:
parent
aab0c31385
commit
ab8c40d9bc
@ -269,10 +269,12 @@ void GCS::update_sensor_status_flags()
|
||||
const AP_Airspeed *airspeed = AP_Airspeed::get_singleton();
|
||||
if (airspeed && airspeed->enabled()) {
|
||||
control_sensors_present |= MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE;
|
||||
if (airspeed->use()) {
|
||||
const bool use = airspeed->use();
|
||||
const bool enabled = AP::ahrs().airspeed_sensor_enabled();
|
||||
if (use) {
|
||||
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE;
|
||||
}
|
||||
if (airspeed->all_healthy()) {
|
||||
if (airspeed->all_healthy() && (!use || enabled)) {
|
||||
control_sensors_health |= MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE;
|
||||
}
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user