From 482bb27fe379855db9fe0724e2d521dd97d44f09 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Sun, 14 Apr 2019 09:35:09 +1000 Subject: [PATCH] Rover: move setting of compass sys_status bits up --- APMrover2/GCS_Rover.cpp | 9 --------- 1 file changed, 9 deletions(-) diff --git a/APMrover2/GCS_Rover.cpp b/APMrover2/GCS_Rover.cpp index 4b128eecc6..c009a820fc 100644 --- a/APMrover2/GCS_Rover.cpp +++ b/APMrover2/GCS_Rover.cpp @@ -23,10 +23,6 @@ bool GCS_Rover::supersimple_input_active() const void GCS_Rover::update_vehicle_sensor_status_flags(void) { // 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; @@ -62,11 +58,6 @@ void GCS_Rover::update_vehicle_sensor_status_flags(void) control_sensors_health |= MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL; // X/Y position control } - AP_AHRS &ahrs = AP::ahrs(); - - if (AP::compass().enabled() && AP::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; }