Copter: move setting of GPS SYS_STATUS bits up to base class

This commit is contained in:
Peter Barker 2019-11-08 17:59:24 +11:00 committed by Andrew Tridgell
parent da184ffdaf
commit d63788a09f
1 changed files with 0 additions and 8 deletions

View File

@ -34,11 +34,6 @@ void GCS_Copter::update_vehicle_sensor_status_flags(void)
MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION |
MAV_SYS_STATUS_SENSOR_YAW_POSITION;
const AP_GPS &gps = AP::gps();
if (gps.status() > AP_GPS::NO_GPS) {
control_sensors_present |= MAV_SYS_STATUS_SENSOR_GPS;
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_GPS;
}
#if OPTFLOW == ENABLED
const OpticalFlow *optflow = AP::opticalflow();
if (optflow && optflow->enabled()) {
@ -113,9 +108,6 @@ void GCS_Copter::update_vehicle_sensor_status_flags(void)
}
#endif
if (gps.is_healthy()) {
control_sensors_health |= MAV_SYS_STATUS_SENSOR_GPS;
}
if (ap.rc_receiver_present && !copter.failsafe.radio) {
control_sensors_health |= MAV_SYS_STATUS_SENSOR_RC_RECEIVER;
}