AP_NavEKF3: use INS_MAX_INSTANCES instead of MAX_EKF_CORES for IMU mask

This commit is contained in:
bugobliterator 2023-03-14 21:36:48 +11:00 committed by Andrew Tridgell
parent 4808b5bfa1
commit deeeb4134c

View File

@ -791,7 +791,7 @@ bool NavEKF3::InitialiseFilter(void)
num_cores = 0;
// count IMUs from mask
for (uint8_t i=0; i<MAX_EKF_CORES; i++) {
for (uint8_t i=0; i<INS_MAX_INSTANCES; i++) {
if (_imuMask & (1U<<i)) {
coreSetupRequired[num_cores] = true;
coreImuIndex[num_cores] = i;