mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-26 18:48:30 -04:00
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.
This commit is contained in:
parent
730b5d228e
commit
4f9fbc5aa7
@ -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…
Reference in New Issue
Block a user