Tracker: move setting of compass sys_status bits up

This commit is contained in:
Peter Barker 2019-04-14 09:35:18 +10:00 committed by Andrew Tridgell
parent 482bb27fe3
commit 5449fe142f
1 changed files with 0 additions and 10 deletions

View File

@ -57,22 +57,12 @@ void GCS_Tracker::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;
}
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;
}
AP_AHRS &ahrs = AP::ahrs();
const Compass &compass = AP::compass();
if (AP::compass().enabled() && compass.healthy(0) && ahrs.use_compass()) {
control_sensors_health |= MAV_SYS_STATUS_SENSOR_3D_MAG;
}
if (gps.is_healthy()) {
control_sensors_health |= MAV_SYS_STATUS_SENSOR_GPS;
}