AP_NavEKF2: allow define for IMU_MASK_DEFAULT

This commit is contained in:
Josh Henderson 2021-11-29 00:00:58 -05:00 committed by Andrew Tridgell
parent c7b986f30a
commit 9f2082496c
1 changed files with 6 additions and 1 deletions

View File

@ -117,6 +117,11 @@
#endif // APM_BUILD_DIRECTORY
// 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
extern const AP_HAL::HAL& hal;
// Define tuning parameters
@ -408,7 +413,7 @@ const AP_Param::GroupInfo NavEKF2::var_info[] = {
// @Bitmask: 0:FirstIMU,1:SecondIMU,2:ThirdIMU,3:FourthIMU,4:FifthIMU,5:SixthIMU
// @User: Advanced
// @RebootRequired: True
AP_GROUPINFO("IMU_MASK", 33, NavEKF2, _imuMask, 3),
AP_GROUPINFO("IMU_MASK", 33, NavEKF2, _imuMask, HAL_EKF_IMU_MASK_DEFAULT),
// @Param: CHECK_SCALE
// @DisplayName: GPS accuracy check scaler (%)