mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
ArduSub: move setting of MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW sensors flags up
This commit is contained in:
parent
b741b9e76e
commit
1d326db931
@ -56,17 +56,6 @@ void GCS_Sub::update_vehicle_sensor_status_flags()
|
|||||||
control_sensors_health |= MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE;
|
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
|
#if AP_TERRAIN_AVAILABLE
|
||||||
switch (sub.terrain.status()) {
|
switch (sub.terrain.status()) {
|
||||||
case AP_Terrain::TerrainStatusDisabled:
|
case AP_Terrain::TerrainStatusDisabled:
|
||||||
|
Loading…
Reference in New Issue
Block a user