From a89f58a775db16cfa90ef4ce87ea4c76d87b2636 Mon Sep 17 00:00:00 2001 From: Josh Henderson Date: Mon, 29 Nov 2021 00:01:21 -0500 Subject: [PATCH] AP_NavEKF3: allow define for IMU_MASK_DEFAULT --- libraries/AP_NavEKF3/AP_NavEKF3.cpp | 7 ++++++- 1 file changed, 6 insertions(+), 1 deletion(-) diff --git a/libraries/AP_NavEKF3/AP_NavEKF3.cpp b/libraries/AP_NavEKF3/AP_NavEKF3.cpp index 324d7a7af7..bbf69fb3a5 100644 --- a/libraries/AP_NavEKF3/AP_NavEKF3.cpp +++ b/libraries/AP_NavEKF3/AP_NavEKF3.cpp @@ -125,6 +125,11 @@ #define EK3_PRIMARY_DEFAULT 0 #endif +// This allows boards to default to using a specified number of IMUs and EKF lanes +#ifndef HAL_EKF_IMU_MASK_DEFAULT +#define HAL_EKF_IMU_MASK_DEFAULT 3 // Default to using two IMUs +#endif + // Define tuning parameters const AP_Param::GroupInfo NavEKF3::var_info[] = { @@ -402,7 +407,7 @@ const AP_Param::GroupInfo NavEKF3::var_info[] = { // @Bitmask: 0:FirstIMU,1:SecondIMU,2:ThirdIMU,3:FourthIMU,4:FifthIMU,5:SixthIMU // @User: Advanced // @RebootRequired: True - AP_GROUPINFO("IMU_MASK", 33, NavEKF3, _imuMask, 3), + AP_GROUPINFO("IMU_MASK", 33, NavEKF3, _imuMask, HAL_EKF_IMU_MASK_DEFAULT), // @Param: CHECK_SCALE // @DisplayName: GPS accuracy check scaler (%)