diff --git a/libraries/AP_NavEKF2/AP_NavEKF2.cpp b/libraries/AP_NavEKF2/AP_NavEKF2.cpp index ad30bee0b1..2219d6a911 100644 --- a/libraries/AP_NavEKF2/AP_NavEKF2.cpp +++ b/libraries/AP_NavEKF2/AP_NavEKF2.cpp @@ -368,7 +368,7 @@ const AP_Param::GroupInfo NavEKF2::var_info[] = { // @Param: ABIAS_P_NSE // @DisplayName: Accelerometer bias stability (m/s^3) // @Description: This noise controls the growth of the vertical accelerometer delta velocity bias state error estimate. Increasing it makes accelerometer bias estimation faster and noisier. - // @Range: 0.00001 0.001 + // @Range: 0.00001 0.005 // @User: Advanced // @Units: m/s/s/s AP_GROUPINFO("ABIAS_P_NSE", 28, NavEKF2, _accelBiasProcessNoise, ABIAS_P_NSE_DEFAULT), diff --git a/libraries/AP_NavEKF3/AP_NavEKF3.cpp b/libraries/AP_NavEKF3/AP_NavEKF3.cpp index 095c6346d4..24b356cfa9 100644 --- a/libraries/AP_NavEKF3/AP_NavEKF3.cpp +++ b/libraries/AP_NavEKF3/AP_NavEKF3.cpp @@ -363,7 +363,7 @@ const AP_Param::GroupInfo NavEKF3::var_info[] = { // @Param: ABIAS_P_NSE // @DisplayName: Accelerometer bias stability (m/s^3) // @Description: This noise controls the growth of the vertical accelerometer delta velocity bias state error estimate. Increasing it makes accelerometer bias estimation faster and noisier. - // @Range: 0.00001 0.001 + // @Range: 0.00001 0.005 // @User: Advanced // @Units: m/s/s/s AP_GROUPINFO("ABIAS_P_NSE", 28, NavEKF3, _accelBiasProcessNoise, ABIAS_P_NSE_DEFAULT),