diff --git a/libraries/AP_AHRS/AP_AHRS.cpp b/libraries/AP_AHRS/AP_AHRS.cpp index 1805993f0d..714ef56d53 100644 --- a/libraries/AP_AHRS/AP_AHRS.cpp +++ b/libraries/AP_AHRS/AP_AHRS.cpp @@ -38,9 +38,13 @@ #define ATTITUDE_CHECK_THRESH_ROLL_PITCH_RAD radians(10) #define ATTITUDE_CHECK_THRESH_YAW_RAD radians(20) +#if CONFIG_HAL_BOARD == HAL_BOARD_SITL +#define HAL_AHRS_EKF_TYPE_DEFAULT 3 +#else #ifndef HAL_AHRS_EKF_TYPE_DEFAULT #define HAL_AHRS_EKF_TYPE_DEFAULT 2 #endif +#endif // table of user settable parameters const AP_Param::GroupInfo AP_AHRS::var_info[] = { diff --git a/libraries/AP_AHRS/AP_AHRS.h b/libraries/AP_AHRS/AP_AHRS.h index d41fbd4aaf..06d732d935 100644 --- a/libraries/AP_AHRS/AP_AHRS.h +++ b/libraries/AP_AHRS/AP_AHRS.h @@ -24,6 +24,11 @@ #include #include +#if CONFIG_HAL_BOARD == HAL_BOARD_SITL +#define HAL_NAVEKF2_AVAILABLE 1 +#define HAL_NAVEKF3_AVAILABLE 1 +#else + #ifndef HAL_NAVEKF3_AVAILABLE // only default to EK2 enabled on boards with over 1M flash #define HAL_NAVEKF3_AVAILABLE (BOARD_FLASH_SIZE>1024) @@ -32,6 +37,7 @@ #ifndef HAL_NAVEKF2_AVAILABLE #define HAL_NAVEKF2_AVAILABLE 1 #endif +#endif #ifndef AP_AHRS_SIM_ENABLED #define AP_AHRS_SIM_ENABLED AP_SIM_ENABLED