Browse Source

GCS_Copter: Fixed precland condition to set SENSOR_VISION_POSITION flag

master
hoangthien94 6 years ago committed by Randy Mackay
parent
commit
b741639002
  1. 2
      ArduCopter/GCS_Copter.cpp

2
ArduCopter/GCS_Copter.cpp

@ -135,7 +135,7 @@ void GCS_Copter::update_vehicle_sensor_status_flags(void) @@ -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…
Cancel
Save