From 1d326db931fe1446cdbd4c1e14d0a0dba2049530 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 19 Oct 2022 14:35:27 +1100 Subject: [PATCH] ArduSub: move setting of MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW sensors flags up --- ArduSub/GCS_Sub.cpp | 11 ----------- 1 file changed, 11 deletions(-) diff --git a/ArduSub/GCS_Sub.cpp b/ArduSub/GCS_Sub.cpp index ede014dcdc..d535a823e6 100644 --- a/ArduSub/GCS_Sub.cpp +++ b/ArduSub/GCS_Sub.cpp @@ -56,17 +56,6 @@ void GCS_Sub::update_vehicle_sensor_status_flags() control_sensors_health |= MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE; } -#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 AP_TERRAIN_AVAILABLE switch (sub.terrain.status()) { case AP_Terrain::TerrainStatusDisabled: