diff --git a/ArduCopter/config.h b/ArduCopter/config.h index 201f0a9a3a..390071c67e 100644 --- a/ArduCopter/config.h +++ b/ArduCopter/config.h @@ -312,7 +312,7 @@ ////////////////////////////////////////////////////////////////////////////// // EKF Checker #ifndef EKFCHECK_THRESHOLD_DEFAULT - # define EKFCHECK_THRESHOLD_DEFAULT 0.6f // EKF checker's default compass and velocity variance above which the EKF's horizontal position will be considered bad + # define EKFCHECK_THRESHOLD_DEFAULT 0.8f // EKF checker's default compass and velocity variance above which the EKF's horizontal position will be considered bad #endif ////////////////////////////////////////////////////////////////////////////// diff --git a/ArduCopter/ekf_check.pde b/ArduCopter/ekf_check.pde index bb4ae2ac63..11c59ac486 100644 --- a/ArduCopter/ekf_check.pde +++ b/ArduCopter/ekf_check.pde @@ -11,10 +11,6 @@ # define EKF_CHECK_ITERATIONS_MAX 10 // 1 second (ie. 10 iterations at 10hz) of bad variances signals a failure #endif -#ifndef EKF_CHECK_COMPASS_INAV_CONVERSION - # define EKF_CHECK_COMPASS_INAV_CONVERSION 0.0075f // converts the inertial nav's acceleration corrections to a form that is comparable to the ekf variance -#endif - #ifndef EKF_CHECK_WARNING_TIME # define EKF_CHECK_WARNING_TIME (30*1000) // warning text messages are sent to ground no more than every 30 seconds #endif