Sub: move setting of compass sys_status bits up

This commit is contained in:
Peter Barker 2019-04-14 09:35:44 +10:00 committed by Andrew Tridgell
parent bba902ab94
commit f66f36287e
1 changed files with 0 additions and 9 deletions

View File

@ -20,10 +20,6 @@ void GCS_Sub::update_vehicle_sensor_status_flags()
MAV_SYS_STATUS_SENSOR_YAW_POSITION;
// first what sensors/controllers we have
if (AP::compass().enabled()) {
control_sensors_present |= MAV_SYS_STATUS_SENSOR_3D_MAG;
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_3D_MAG;
}
if (sub.ap.depth_sensor_present) {
control_sensors_present |= MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE;
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE;
@ -65,11 +61,6 @@ void GCS_Sub::update_vehicle_sensor_status_flags()
if (sub.sensor_health.depth) {
control_sensors_health |= MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE;
}
AP_AHRS &ahrs = AP::ahrs();
const Compass &compass = AP::compass();
if (AP::compass().enabled() && compass.healthy() && ahrs.use_compass()) {
control_sensors_health |= MAV_SYS_STATUS_SENSOR_3D_MAG;
}
if (gps.is_healthy()) {
control_sensors_health |= MAV_SYS_STATUS_SENSOR_GPS;
}