From 0f8f5bc048fded53aff16e2935a1aeb7b0b2c8be Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Mon, 29 Jul 2013 16:46:05 +0900 Subject: [PATCH] Copter: remove unused ap.gps_status flag --- ArduCopter/AP_State.pde | 10 ---------- ArduCopter/ArduCopter.pde | 2 -- 2 files changed, 12 deletions(-) diff --git a/ArduCopter/AP_State.pde b/ArduCopter/AP_State.pde index 792e7bbcd8..2217b4f677 100644 --- a/ArduCopter/AP_State.pde +++ b/ArduCopter/AP_State.pde @@ -127,13 +127,3 @@ void set_compass_healthy(bool b) } ap.compass_status = b; } - -void set_gps_healthy(bool b) -{ - if(ap.gps_status != b){ - if(false == b){ - Log_Write_Event(DATA_LOST_GPS); - } - } - ap.gps_status = b; -} diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde index a1ef3dd48f..9ad705ba1d 100644 --- a/ArduCopter/ArduCopter.pde +++ b/ArduCopter/ArduCopter.pde @@ -1337,8 +1337,6 @@ static void update_GPS(void) g_gps->update(); update_GPS_light(); - set_gps_healthy(g_gps->status() >= GPS::GPS_OK_FIX_3D); - if (g_gps->new_data && last_gps_time != g_gps->time && g_gps->status() >= GPS::GPS_OK_FIX_2D) { // clear new data flag g_gps->new_data = false;