From 8a776f8ff85782471f9548e468fab685b1043eb2 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Wed, 29 Oct 2014 12:02:59 +0900 Subject: [PATCH] GPS: init primary_instance to zero --- libraries/AP_GPS/AP_GPS.cpp | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/libraries/AP_GPS/AP_GPS.cpp b/libraries/AP_GPS/AP_GPS.cpp index fe9847dbac..7de3e0e0a0 100644 --- a/libraries/AP_GPS/AP_GPS.cpp +++ b/libraries/AP_GPS/AP_GPS.cpp @@ -87,8 +87,8 @@ void AP_GPS::init(DataFlash_Class *dataflash) { _DataFlash = dataflash; hal.uartB->begin(38400UL, 256, 16); -#if GPS_MAX_INSTANCES > 1 primary_instance = 0; +#if GPS_MAX_INSTANCES > 1 if (hal.uartE != NULL) { hal.uartE->begin(38400UL, 256, 16); } @@ -378,7 +378,6 @@ AP_GPS::update(void) } } #else - primary_instance=0; num_instances = 1; #endif // GPS_MAX_INSTANCES // update notify with gps status. We always base this on the primary_instance