mirror of https://github.com/ArduPilot/ardupilot
AP_NavEKF: increase ABIAS_P_NSE param doc range to 0.005
This commit is contained in:
parent
a409567b44
commit
c616587b86
|
@ -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),
|
||||
|
|
|
@ -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),
|
||||
|
|
Loading…
Reference in New Issue