mirror of https://github.com/ArduPilot/ardupilot
ArduPlane: move setting of MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW sensors flags up
This commit is contained in:
parent
6e25a3d52c
commit
b741b9e76e
|
@ -98,17 +98,6 @@ void GCS_Plane::update_vehicle_sensor_status_flags(void)
|
|||
control_sensors_health |= MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION;
|
||||
}
|
||||
|
||||
#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
|
||||
|
||||
control_sensors_present |= MAV_SYS_STATUS_SENSOR_RC_RECEIVER;
|
||||
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_RC_RECEIVER;
|
||||
uint32_t last_valid = plane.failsafe.last_valid_rc_ms;
|
||||
|
|
Loading…
Reference in New Issue