GCS_Copter: Fixed precland condition to set SENSOR_VISION_POSITION flag

This commit is contained in:
hoangthien94 2019-06-24 21:03:52 +08:00 committed by Randy Mackay
parent ea2de1c11a
commit b741639002
1 changed files with 1 additions and 1 deletions

View File

@ -135,7 +135,7 @@ void GCS_Copter::update_vehicle_sensor_status_flags(void)
}
#endif
#if PRECISION_LANDING == ENABLED
if (!copter.precland.enabled() || copter.precland.healthy()) {
if (copter.precland.enabled() && copter.precland.healthy()) {
control_sensors_health |= MAV_SYS_STATUS_SENSOR_VISION_POSITION;
}
#endif