From 14ae4310563e6a45ec3ec59664cf3dc68db188e4 Mon Sep 17 00:00:00 2001 From: bugobliterator Date: Fri, 17 Feb 2023 17:58:57 +1100 Subject: [PATCH] AP_DAL: use MAX_EKF_CORES instead of INS_MAX_INSTANCES in ekf_low_time_remaining --- libraries/AP_DAL/AP_DAL.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_DAL/AP_DAL.cpp b/libraries/AP_DAL/AP_DAL.cpp index 1d7830919b..8e2b6fe87b 100644 --- a/libraries/AP_DAL/AP_DAL.cpp +++ b/libraries/AP_DAL/AP_DAL.cpp @@ -303,7 +303,7 @@ void AP_DAL::WriteLogMessage(enum LogMessages msg_type, void *msg, const void *o */ bool AP_DAL::ekf_low_time_remaining(EKFType etype, uint8_t core) { - static_assert(INS_MAX_INSTANCES <= 4, "max 4 IMUs"); + static_assert(MAX_EKF_CORES <= 4, "max 4 EKF cores supported"); const uint8_t mask = (1U<<(core+(uint8_t(etype)*4))); #if !APM_BUILD_TYPE(APM_BUILD_AP_DAL_Standalone) && !APM_BUILD_TYPE(APM_BUILD_Replay) /*