@ -35,7 +35,7 @@
@@ -35,7 +35,7 @@
# define GYRO_PNOISE_DEFAULT 0.015f
# define ACC_PNOISE_DEFAULT 0.25f
# define GBIAS_PNOISE_DEFAULT 1E-07f
# define ABIAS_PNOISE_DEFAULT 0.0002 f
# define ABIAS_PNOISE_DEFAULT 0.00015 f
# define MAGE_PNOISE_DEFAULT 0.0003f
# define MAGB_PNOISE_DEFAULT 0.0003f
# define VEL_GATE_DEFAULT 2
@ -56,7 +56,7 @@
@@ -56,7 +56,7 @@
# define GYRO_PNOISE_DEFAULT 0.015f
# define ACC_PNOISE_DEFAULT 0.25f
# define GBIAS_PNOISE_DEFAULT 1E-07f
# define ABIAS_PNOISE_DEFAULT 0.0002 f
# define ABIAS_PNOISE_DEFAULT 0.00015 f
# define MAGE_PNOISE_DEFAULT 0.0003f
# define MAGB_PNOISE_DEFAULT 0.0003f
# define VEL_GATE_DEFAULT 2
@ -77,7 +77,7 @@
@@ -77,7 +77,7 @@
# define GYRO_PNOISE_DEFAULT 0.015f
# define ACC_PNOISE_DEFAULT 0.25f
# define GBIAS_PNOISE_DEFAULT 1E-07f
# define ABIAS_PNOISE_DEFAULT 0.0002 f
# define ABIAS_PNOISE_DEFAULT 0.00015 f
# define MAGE_PNOISE_DEFAULT 0.0003f
# define MAGB_PNOISE_DEFAULT 0.0003f
# define VEL_GATE_DEFAULT 5
@ -188,7 +188,7 @@ const AP_Param::GroupInfo NavEKF::var_info[] PROGMEM = {
@@ -188,7 +188,7 @@ const AP_Param::GroupInfo NavEKF::var_info[] PROGMEM = {
// @Param: ABIAS_PNOISE
// @DisplayName: Accelerometer bias state process noise (m/s^2)
// @Description: This noise controls the growth of the vertical acelerometer bias state error estimate. Increasing it makes accelerometer bias estimation faster and noisier.
// @Range: 0.0002 - 0.001
// @Range: 0.0001 - 0.001
// @User: advanced
AP_GROUPINFO ( " ABIAS_PNOISE " , 11 , NavEKF , _accelBiasProcessNoise , ABIAS_PNOISE_DEFAULT ) ,
@ -912,7 +912,7 @@ void NavEKF::CovariancePrediction()
@@ -912,7 +912,7 @@ void NavEKF::CovariancePrediction()
// this allows for wind gradient effects.
windVelSigma = dt * constrain_float ( _windVelProcessNoise , 0.01f , 1.0f ) * ( 1.0f + constrain_float ( _wndVarHgtRateScale , 0.0f , 1.0f ) * fabsf ( hgtRate ) ) ;
dAngBiasSigma = dt * constrain_float ( _gyroBiasProcessNoise , 1e-7 f , 1e-5 f ) ;
dVelBiasSigma = dt * constrain_float ( _accelBiasProcessNoise , 2 e-4f , 1e-3 f ) ;
dVelBiasSigma = dt * constrain_float ( _accelBiasProcessNoise , 1 e-4f , 1e-3 f ) ;
magEarthSigma = dt * constrain_float ( _magEarthProcessNoise , 1e-4 f , 1e-2 f ) ;
magBodySigma = dt * constrain_float ( _magBodyProcessNoise , 1e-4 f , 1e-2 f ) ;
for ( uint8_t i = 0 ; i < = 9 ; i + + ) processNoise [ i ] = 1.0e-9 f ;