AP_AHRS: use ekf3 by default

This commit is contained in:
Randy Mackay 2018-01-05 10:43:45 +09:00
parent 60633f5a7f
commit 1b3ad9cd8d
1 changed files with 1 additions and 1 deletions

View File

@ -129,7 +129,7 @@ const AP_Param::GroupInfo AP_AHRS::var_info[] = {
// @Description: This controls which NavEKF Kalman filter version is used for attitude and position estimation
// @Values: 0:Disabled,2:Enable EKF2,3:Enable EKF3
// @User: Advanced
AP_GROUPINFO("EKF_TYPE", 14, AP_AHRS, _ekf_type, 2),
AP_GROUPINFO("EKF_TYPE", 14, AP_AHRS, _ekf_type, 3),
#endif
// @Param: CUSTOM_ROLL