From a8a6368f05c885d395f8bbd987c8669bb55e46a1 Mon Sep 17 00:00:00 2001 From: Benoit PEREIRA DA SILVA Date: Sun, 21 Sep 2014 14:48:35 +0200 Subject: [PATCH] GPS: use primary for Notification --- libraries/AP_GPS/AP_GPS.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/libraries/AP_GPS/AP_GPS.cpp b/libraries/AP_GPS/AP_GPS.cpp index adbcfcad66..28130fffa2 100644 --- a/libraries/AP_GPS/AP_GPS.cpp +++ b/libraries/AP_GPS/AP_GPS.cpp @@ -334,9 +334,6 @@ AP_GPS::update(void) update_instance(i); } - // update notify with gps status. We always base this on the first GPS - AP_Notify::flags.gps_status = state[0].status; - #if GPS_MAX_INSTANCES > 1 // work out which GPS is the primary, and how many sensors we have for (uint8_t i=0; i