We read every piece of feedback, and take your input very seriously.
To see all available qualifiers, see our documentation.
1 parent aab0c31 commit ab8c40dCopy full SHA for ab8c40d
libraries/GCS_MAVLink/GCS.cpp
@@ -269,10 +269,12 @@ void GCS::update_sensor_status_flags()
269
const AP_Airspeed *airspeed = AP_Airspeed::get_singleton();
270
if (airspeed && airspeed->enabled()) {
271
control_sensors_present |= MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE;
272
- if (airspeed->use()) {
+ const bool use = airspeed->use();
273
+ const bool enabled = AP::ahrs().airspeed_sensor_enabled();
274
+ if (use) {
275
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE;
276
}
- if (airspeed->all_healthy()) {
277
+ if (airspeed->all_healthy() && (!use || enabled)) {
278
control_sensors_health |= MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE;
279
280
0 commit comments