Copter: move setting of compass sys_status bits up

This commit is contained in:
Peter Barker 2019-04-14 09:35:28 +10:00 committed by Andrew Tridgell
parent 5449fe142f
commit 07b8473a20

View File

@ -34,10 +34,6 @@ void GCS_Copter::update_vehicle_sensor_status_flags(void)
MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION | MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION |
MAV_SYS_STATUS_SENSOR_YAW_POSITION; MAV_SYS_STATUS_SENSOR_YAW_POSITION;
if (AP::compass().enabled()) {
control_sensors_present |= MAV_SYS_STATUS_SENSOR_3D_MAG;
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_3D_MAG;
}
const AP_GPS &gps = AP::gps(); const AP_GPS &gps = AP::gps();
if (gps.status() > AP_GPS::NO_GPS) { if (gps.status() > AP_GPS::NO_GPS) {
control_sensors_present |= MAV_SYS_STATUS_SENSOR_GPS; control_sensors_present |= MAV_SYS_STATUS_SENSOR_GPS;
@ -127,11 +123,6 @@ void GCS_Copter::update_vehicle_sensor_status_flags(void)
} }
#endif #endif
AP_AHRS &ahrs = AP::ahrs();
const Compass &compass = AP::compass();
if (compass.enabled() && compass.healthy() && ahrs.use_compass()) {
control_sensors_health |= MAV_SYS_STATUS_SENSOR_3D_MAG;
}
if (gps.is_healthy()) { if (gps.is_healthy()) {
control_sensors_health |= MAV_SYS_STATUS_SENSOR_GPS; control_sensors_health |= MAV_SYS_STATUS_SENSOR_GPS;
} }