From 4f9fbc5aa7bb6ef86a491b1cb25ecf92a83a2c7e Mon Sep 17 00:00:00 2001 From: Michael du Breuil Date: Wed, 12 Aug 2015 21:01:55 -0700 Subject: [PATCH] AP_GPS: Fix a bound error when calculating GNSS minimum channels. This is really just calculating the hamming weight of the GNSS_MODE bitmask, but I don't know if the APM compiler could handle the GCC intrinsic that could calculate it faster, and this is done so rarely there isn't a significant penalty to using the for loop. --- libraries/AP_GPS/AP_GPS_UBLOX.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_GPS/AP_GPS_UBLOX.cpp b/libraries/AP_GPS/AP_GPS_UBLOX.cpp index 7927fb6816..23ef284fa3 100644 --- a/libraries/AP_GPS/AP_GPS_UBLOX.cpp +++ b/libraries/AP_GPS/AP_GPS_UBLOX.cpp @@ -459,7 +459,7 @@ AP_GPS_UBLOX::_parse_gps(void) } #endif - for(int i = 1; i <= UBLOX_MAX_GNSS_CONFIG_BLOCKS; i++) { + for(int i = 0; i < UBLOX_MAX_GNSS_CONFIG_BLOCKS; i++) { if((gps._gnss_mode & (1 << i)) && i != GNSS_SBAS) { gnssCount++; }