diff --git a/ArduCopter/Copter.h b/ArduCopter/Copter.h index f563e2742f..6b8222a197 100644 --- a/ArduCopter/Copter.h +++ b/ArduCopter/Copter.h @@ -405,7 +405,6 @@ private: struct { uint8_t baro : 1; // true if baro is healthy uint8_t compass : 1; // true if compass is healthy - uint8_t primary_gps : 2; // primary gps index } sensor_health; // Motor Output diff --git a/ArduCopter/Log.cpp b/ArduCopter/Log.cpp index d655aadde1..b62e75adb6 100644 --- a/ArduCopter/Log.cpp +++ b/ArduCopter/Log.cpp @@ -265,12 +265,6 @@ void Copter::Log_Sensor_Health() sensor_health.compass = compass.healthy(); AP::logger().Write_Error(LogErrorSubsystem::COMPASS, (sensor_health.compass ? LogErrorCode::ERROR_RESOLVED : LogErrorCode::UNHEALTHY)); } - - // check primary GPS - if (sensor_health.primary_gps != gps.primary_sensor()) { - sensor_health.primary_gps = gps.primary_sensor(); - AP::logger().Write_Event(LogEvent::GPS_PRIMARY_CHANGED); - } } struct PACKED log_SysIdD {