mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_NavEKF3: use INS_MAX_INSTANCES instead of MAX_EKF_CORES for IMU mask
This commit is contained in:
parent
4808b5bfa1
commit
deeeb4134c
@ -791,7 +791,7 @@ bool NavEKF3::InitialiseFilter(void)
|
|||||||
num_cores = 0;
|
num_cores = 0;
|
||||||
|
|
||||||
// count IMUs from mask
|
// 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)) {
|
if (_imuMask & (1U<<i)) {
|
||||||
coreSetupRequired[num_cores] = true;
|
coreSetupRequired[num_cores] = true;
|
||||||
coreImuIndex[num_cores] = i;
|
coreImuIndex[num_cores] = i;
|
||||||
|
Loading…
Reference in New Issue
Block a user