mirror of https://github.com/ArduPilot/ardupilot
Copter: increase EKF_CHECK_THRESH default to 0.8
Also remove unused #define related to inertial nav check (now removed)
This commit is contained in:
parent
3e1bd04c94
commit
21d56735ca
|
@ -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
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
|
|
|
@ -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
|
||||
|
|
Loading…
Reference in New Issue