Plane: check all airspeed sensors are healthy
This commit is contained in:
parent
8bb0ad7f3a
commit
c1cbbf9203
@ -321,7 +321,7 @@ void Plane::update_sensor_status_flags(void)
|
|||||||
if (!ins.get_accel_health_all()) {
|
if (!ins.get_accel_health_all()) {
|
||||||
control_sensors_health &= ~MAV_SYS_STATUS_SENSOR_3D_ACCEL;
|
control_sensors_health &= ~MAV_SYS_STATUS_SENSOR_3D_ACCEL;
|
||||||
}
|
}
|
||||||
if (airspeed.healthy()) {
|
if (airspeed.all_healthy()) {
|
||||||
control_sensors_health |= MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE;
|
control_sensors_health |= MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE;
|
||||||
}
|
}
|
||||||
#if GEOFENCE_ENABLED
|
#if GEOFENCE_ENABLED
|
||||||
|
Loading…
Reference in New Issue
Block a user