diff --git a/libraries/AP_AHRS/AP_AHRS.cpp b/libraries/AP_AHRS/AP_AHRS.cpp index 7596c9a24e..0057c10353 100644 --- a/libraries/AP_AHRS/AP_AHRS.cpp +++ b/libraries/AP_AHRS/AP_AHRS.cpp @@ -24,6 +24,10 @@ extern const AP_HAL::HAL& hal; +#ifndef HAL_AHRS_EKF_TYPE_DEFAULT +#define HAL_AHRS_EKF_TYPE_DEFAULT 3 +#endif + // table of user settable parameters const AP_Param::GroupInfo AP_AHRS::var_info[] = { // index 0 and 1 are for old parameters that are no longer not used @@ -127,9 +131,9 @@ const AP_Param::GroupInfo AP_AHRS::var_info[] = { // @Param: EKF_TYPE // @DisplayName: Use NavEKF Kalman filter for attitude and position estimation // @Description: This controls which NavEKF Kalman filter version is used for attitude and position estimation - // @Values: 0:Disabled,2:Enable EKF2,3:Enable EKF3 + // @Values: 0:Disabled,2:Enable EKF2,3:Enable EKF3,11:ExternalAHRS // @User: Advanced - AP_GROUPINFO("EKF_TYPE", 14, AP_AHRS, _ekf_type, 3), + AP_GROUPINFO("EKF_TYPE", 14, AP_AHRS, _ekf_type, HAL_AHRS_EKF_TYPE_DEFAULT), #endif // @Param: CUSTOM_ROLL