diff --git a/libraries/AP_AHRS/AP_AHRS.h b/libraries/AP_AHRS/AP_AHRS.h index f69d12f47b..bffe898418 100644 --- a/libraries/AP_AHRS/AP_AHRS.h +++ b/libraries/AP_AHRS/AP_AHRS.h @@ -33,13 +33,6 @@ #include -// Copter defaults to EKF on by default, all others off -#if APM_BUILD_TYPE(APM_BUILD_ArduCopter) -# define AHRS_EKF_USE_ALWAYS 1 -#else -# define AHRS_EKF_USE_ALWAYS 0 -#endif - #define AP_AHRS_TRIM_LIMIT 10.0f // maximum trim angle in degrees #define AP_AHRS_RP_P_MIN 0.05f // minimum value for AHRS_RP_P parameter #define AP_AHRS_YAW_P_MIN 0.05f // minimum value for AHRS_YAW_P parameter diff --git a/libraries/AP_AHRS/AP_AHRS_NavEKF.h b/libraries/AP_AHRS/AP_AHRS_NavEKF.h index 8a25547d5b..099aaddf7e 100644 --- a/libraries/AP_AHRS/AP_AHRS_NavEKF.h +++ b/libraries/AP_AHRS/AP_AHRS_NavEKF.h @@ -43,12 +43,7 @@ public: // Constructor AP_AHRS_NavEKF(AP_InertialSensor &ins, AP_Baro &baro, AP_GPS &gps, RangeFinder &rng, - NavEKF &_EKF1, NavEKF2 &_EKF2, -#if AHRS_EKF_USE_ALWAYS - Flags flags = FLAG_ALWAYS_USE_EKF -#else - Flags flags = FLAG_NONE -#endif + NavEKF &_EKF1, NavEKF2 &_EKF2, Flags flags = FLAG_NONE ) : AP_AHRS_DCM(ins, baro, gps), EKF1(_EKF1),