mirror of https://github.com/ArduPilot/ardupilot
GCS_Copter: Fixed precland condition to set SENSOR_VISION_POSITION flag
This commit is contained in:
parent
ea2de1c11a
commit
b741639002
|
@ -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
|
||||
|
|
Loading…
Reference in New Issue