mirror of https://github.com/ArduPilot/ardupilot
AP_AHRS: enable EKF by default on plane
now we have arming checks enabled by default I think this is the best choice
This commit is contained in:
parent
efd958f0b0
commit
b61f7fa2f6
|
@ -40,7 +40,11 @@
|
||||||
# define AHRS_EKF_USE_ALWAYS 0
|
# define AHRS_EKF_USE_ALWAYS 0
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#if APM_BUILD_TYPE(APM_BUILD_ArduPlane)
|
||||||
|
#define AHRS_EKF_USE_DEFAULT 1
|
||||||
|
#else
|
||||||
#define AHRS_EKF_USE_DEFAULT 0
|
#define AHRS_EKF_USE_DEFAULT 0
|
||||||
|
#endif
|
||||||
|
|
||||||
#define AP_AHRS_TRIM_LIMIT 10.0f // maximum trim angle in degrees
|
#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_RP_P_MIN 0.05f // minimum value for AHRS_RP_P parameter
|
||||||
|
|
Loading…
Reference in New Issue