mirror of https://github.com/ArduPilot/ardupilot
AP_NavEKF3: allow define for IMU_MASK_DEFAULT
This commit is contained in:
parent
9f2082496c
commit
a89f58a775
|
@ -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 (%)
|
||||
|
|
Loading…
Reference in New Issue