AP_NavEKF: disable EKF1 by default

use EKF2 instead
This commit is contained in:
Andrew Tridgell 2016-01-05 16:41:48 +11:00
parent c34626ec4e
commit a0a4b698f6

View File

@ -123,7 +123,7 @@ const AP_Param::GroupInfo NavEKF::var_info[] = {
// @Description: This enables EKF1 to be disabled when using alternative algorithms. When disabling it, the alternate EKF2 estimator must be enabled by setting EK2_ENABLED = 1 and flight control algorithms must be set to use the alternative estimator by setting AHRS_EKF_TYPE = 2.
// @Values: 0:Disabled, 1:Enabled
// @User: Advanced
AP_GROUPINFO_FLAGS("ENABLE", 34, NavEKF, _enable, 1, AP_PARAM_FLAG_ENABLE),
AP_GROUPINFO_FLAGS("ENABLE", 34, NavEKF, _enable, 0, AP_PARAM_FLAG_ENABLE),
// @Param: VELNE_NOISE
// @DisplayName: GPS horizontal velocity measurement noise scaler