ArduCopter: move setting of MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW sensors flags up

This commit is contained in:
Peter Barker 2022-10-19 14:35:27 +11:00 committed by Peter Barker
parent 342a5a71a9
commit 6e25a3d52c
1 changed files with 0 additions and 11 deletions

View File

@ -114,17 +114,6 @@ void GCS_Copter::update_vehicle_sensor_status_flags(void)
}
#endif
#if AP_OPTICALFLOW_ENABLED
const AP_OpticalFlow *optflow = AP::opticalflow();
if (optflow && optflow->enabled()) {
control_sensors_present |= MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW;
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW;
}
if (optflow && optflow->healthy()) {
control_sensors_health |= MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW;
}
#endif
#if PRECISION_LANDING == ENABLED
if (copter.precland.enabled()) {
control_sensors_present |= MAV_SYS_STATUS_SENSOR_VISION_POSITION;