Browse Source

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.
master
Michael du Breuil 10 years ago committed by Andrew Tridgell
parent
commit
4f9fbc5aa7
  1. 2
      libraries/AP_GPS/AP_GPS_UBLOX.cpp

2
libraries/AP_GPS/AP_GPS_UBLOX.cpp

@ -459,7 +459,7 @@ AP_GPS_UBLOX::_parse_gps(void) @@ -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++;
}

Loading…
Cancel
Save