// @Description: This enables EKF2. Enabling EKF2 only makes the maths run, it does not mean it will be used for flight control. To use it for flight control set AHRS_EKF_USE=3
// @Values: 0:Disabled, 1:Enabled
// @User: Advanced
AP_GROUPINFO("ENABLE",0,NavEKF2,_enable,0),
AP_GROUPINFO("ENABLE",0,NavEKF2,_enable,0),
// GPS measurement parameters
// @Param: GPS_TYPE
// @DisplayName: GPS mode control
// @Description: This parameter controls use of GPS measurements : 0 = use 3D velocity & 2D position, 1 = use 2D velocity and 2D position, 2 = use 2D position, 3 = use no GPS (optical flow will be used if available)
// @Values: 0:GPS 3D Vel and 2D Pos, 1:GPS 2D vel and 2D pos, 2:GPS 2D pos, 3:No GPS use optical flow
// @Description: This parameter sets the number of standard deviations applied to the GPS velocity measurement innovation consistency check. Decreasing it makes it more likely that good measurements willbe rejected. Increasing it makes it more likely that bad measurements will be accepted.
// @DisplayName: Height rate to wind procss noise scaler
// @Description: Increasing this parameter increases how rapidly the wind states adapt when changing altitude, but does make wind speed estimation noiser.
// @Description: This noise controls the growth of estimated error due to gyro measurement errors excluding bias. Increasing it makes the flter trust the gyro measurements less and other measurements more.
// @Description: This noise controls the growth of estimated error due to accelerometer measurement errors excluding bias. Increasing it makes the flter trust the accelerometer measurements less and other measurements more.
// @DisplayName: Accelerometer bias 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.
// @DisplayName: Magnetic field process noise (gauss/s)
// @Description: This noise controls the growth of magnetic field state error estimates. Increasing it makes magnetic field bias estimation faster and noisier.
// @Range: 0.0001 0.01
// @Param: POS_GATE
// @DisplayName: GPS position measurement gate size
// @Description: This parameter sets the number of standard deviations applied to the GPS position measurement innovation consistency check. Decreasing it makes it more likely that good measurements will be rejected. Increasing it makes it more likely that bad measurements will be accepted.
// @DisplayName: Rate gyro scale factor process noise (1/s)
// @Description: This noise controls the rate of gyro scale factor learning. Increasing it makes rate gyro scale factor estimation faster and noisier.
// @Range: 0.0000001 0.00001
// @Param: GLITCH_RAD
// @DisplayName: GPS glitch radius gate size (m)
// @Description: This parameter controls the maximum amount of difference in horizontal position (in m) between the value predicted by the filter and the value measured by the GPS before the long term glitch protection logic is activated and an offset is applied to the GPS measurement to compensate. Position steps smaller than this value will be temporarily ignored, but will then be accepted and the filter will move to the new position. Position steps larger than this value will be ignored initially, but the filter will then apply an offset to the GPS position measurement.
// @Description: This parameter controls use of GPS measurements : 0 = use 3D velocity & 2D position, 1 = use 2D velocity and 2D position, 2 = use 2D position, 3 = use no GPS (optical flow will be used if available)
// @Values: 0:GPS 3D Vel and 2D Pos, 1:GPS 2D vel and 2D pos, 2:GPS 2D pos, 3:No GPS use optical flow
// @Description: This parameter sets the number of standard deviations applied to the GPS velocity measurement innovation consistency check. Decreasing it makes it more likely that good measurements willbe rejected. Increasing it makes it more likely that bad measurements will be accepted.
// @Range: 1 100
// @Increment: 1
// @Param: ALT_SOURCE
// @DisplayName: Primary height source
// @Description: This parameter controls which height sensor is used by the EKF during optical flow navigation (when EKF_GPS_TYPE = 3). A value of will 0 cause it to always use baro altitude. A value of 1 will casue it to use range finder if available.
// @DisplayName: GPS position measurement gate size
// @Description: This parameter sets the number of standard deviations applied to the GPS position measurement innovation consistency check. Decreasing it makes it more likely that good measurements will be rejected. Increasing it makes it more likely that bad measurements will be accepted.
// @Range: 1 100
// @Increment: 1
// @Param: ALT_NOISE
// @DisplayName: Altitude measurement noise (m)
// @Description: This is the RMS value of noise in the altitude measurement. Increasing it reduces the weighting on this measurement.
// @Description: EKF_MAG_CAL = 0 enables calibration based on flying speed and altitude and is the default setting for Plane users. EKF_MAG_CAL = 1 enables calibration based on manoeuvre level and is the default setting for Copter and Rover users. EKF_MAG_CAL = 2 prevents magnetometer calibration regardless of flight condition and is recommended if in-flight magnetometer calibration is unreliable.
// @Values: 0:Speed and Height,1:Acceleration,2:Never,3:Always
// @Description: EKF_MAG_CAL = 0 enables calibration based on flying speed and altitude and is the default setting for Plane users. EKF_MAG_CAL = 1 enables calibration based on manoeuvre level and is the default setting for Copter and Rover users. EKF_MAG_CAL = 2 prevents magnetometer calibration regardless of flight condition and is recommended if in-flight magnetometer calibration is unreliable.
// @Values: 0:Speed and Height,1:Acceleration,2:Never,3:Always
// @Description: This parameter controls the maximum amount of difference in horizontal position (in m) between the value predicted by the filter and the value measured by the GPS before the long term glitch protection logic is activated and an offset is applied to the GPS measurement to compensate. Position steps smaller than this value will be temporarily ignored, but will then be accepted and the filter will move to the new position. Position steps larger than this value will be ignored initially, but the filter will then apply an offset to the GPS position measurement.
// @Range: 10 50
// @Increment: 5
// @Param: RNG_NOISE
// @DisplayName: Range finder measurement noise (m)
// @Description: This is the RMS value of noise in the range finder measurement. Increasing it reduces the weighting on this measurement.
// @Description: This parameter sets the RMS terrain gradient percentage assumed by the terrain height estimation. Terrain height can be estimated using optical flow and/or range finder sensor data if fitted. Smaller values cause the terrain height estimate to be slower to respond to changes in measurement. Larger values casue the terrain height estimate to be faster to respond, but also more noisy. Generally this value can be reduced if operating over very flat terrain and increased if operating over uneven terrain.
// @Range: 1 - 50
// @Param: RNG_GATE
// @DisplayName: Range finder measurement gate size
// @Description: This parameter sets the number of standard deviations applied to the range finder innovation consistency check. Decreasing it makes it more likely that good measurements will be rejected. Increasing it makes it more likely that bad measurements will be accepted.
// @DisplayName: Range finder measurement gate size
// @Description: This parameter sets the number of standard deviations applied to the range finder innovation consistency check. Decreasing it makes it more likely that good measurements will be rejected. Increasing it makes it more likely that bad measurements will be accepted.
// @Range: 1 - 100
// @Increment: 1
// State and Covariance Predition Parameters
// @Param: GYRO_PNOISE
// @DisplayName: Rate gyro noise (rad/s)
// @Description: This noise controls the growth of estimated error due to gyro measurement errors excluding bias. Increasing it makes the flter trust the gyro measurements less and other measurements more.
// @Description: This parameter sets the magnitude maximum optical flow rate in rad/sec that will be accepted by the filter
// @Range: 1.0 - 4.0
// @Increment: 0.1
// @Param: ACC_PNOISE
// @DisplayName: Accelerometer noise (m/s^2)
// @Description: This noise controls the growth of estimated error due to accelerometer measurement errors excluding bias. Increasing it makes the flter trust the accelerometer measurements less and other measurements more.
// @Description: This parameter controls the conditions necessary to trigger a fallback to DCM and INAV. A value of 1 will cause fallbacks to occur on loss of GPS and other conditions. A value of 0 will trust the EKF more.
// @Values: 0:Trust EKF more, 1:Trust DCM more
// @Param: GBIAS_PNOISE
// @DisplayName: Rate gyro bias process noise (rad/s)
// @Description: This noise controls the growth of gyro bias state error estimates. Increasing it makes rate gyro bias estimation faster and noisier.
// @Description: This parameter controls which height sensor is used by the EKF during optical flow navigation (when EKF_GPS_TYPE = 3). A value of will 0 cause it to always use baro altitude. A value of 1 will casue it to use range finder if available.
// @Values: 0:Use Baro, 1:Use Range Finder
// @Param: GSCL_PNOISE
// @DisplayName: Rate gyro scale factor process noise (1/s)
// @Description: This noise controls the rate of gyro scale factor learning. Increasing it makes rate gyro scale factor estimation faster and noisier.
// @DisplayName: Accelerometer bias 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.
// @DisplayName: Magnetic field process noise (gauss/s)
// @Description: This noise controls the growth of magnetic field state error estimates. Increasing it makes magnetic field bias estimation faster and noisier.
// @DisplayName: Height rate to wind procss noise scaler
// @Description: Increasing this parameter increases how rapidly the wind states adapt when changing altitude, but does make wind speed estimation noiser.
gpsNEVelVarAccScale(0.05f),// Scale factor applied to horizontal velocity measurement variance due to manoeuvre acceleration - used when GPS doesn't report speed error
gpsDVelVarAccScale(0.07f),// Scale factor applied to vertical velocity measurement variance due to manoeuvre acceleration - used when GPS doesn't report speed error
gpsPosVarAccScale(0.05f),// Scale factor applied to horizontal position measurement variance due to manoeuvre acceleration
gpsRetryTimeUseTAS_ms(10000),// GPS retry time with airspeed measurements (msec)
gpsRetryTimeNoTAS_ms(7000),// GPS retry time without airspeed measurements (msec)
gpsFailTimeWithFlow_ms(1000),// If we have no GPS for longer than this and we have optical flow, then we will switch across to using optical flow (msec)
hgtRetryTimeMode0_ms(10000),// Height retry time with vertical velocity measurement (msec)
hgtRetryTimeMode12_ms(5000),// Height retry time without vertical velocity measurement (msec)
tasRetryTime_ms(5000),// True airspeed timeout and retry interval (msec)
gpsRetryTimeUseTAS_ms(10000),// GPS retry time with airspeed measurements (msec)
gpsRetryTimeNoTAS_ms(7000),// GPS retry time without airspeed measurements (msec)
gpsFailTimeWithFlow_ms(1000),// If we have no GPS for longer than this and we have optical flow, then we will switch across to using optical flow (msec)
hgtRetryTimeMode0_ms(10000),// Height retry time with vertical velocity measurement (msec)
hgtRetryTimeMode12_ms(5000),// Height retry time without vertical velocity measurement (msec)
tasRetryTime_ms(5000),// True airspeed timeout and retry interval (msec)
magFailTimeLimit_ms(10000),// number of msec before a magnetometer failing innovation consistency checks is declared failed (msec)
magVarRateScale(0.05f),// scale factor applied to magnetometer variance due to angular rate
gyroBiasNoiseScaler(2.0f),// scale factor applied to imu gyro bias learning before the vehicle is armed
accelBiasNoiseScaler(1.0f),// scale factor applied to imu accel bias learning before the vehicle is armed
hgtAvg_ms(100),// average number of msec between height measurements
betaAvg_ms(100),// average number of msec between synthetic sideslip measurements
hgtAvg_ms(100),// average number of msec between height measurements
betaAvg_ms(100),// average number of msec between synthetic sideslip measurements
covTimeStepMax(0.07f),// maximum time (sec) between covariance prediction updates
covDelAngMax(0.05f),// maximum delta angle between covariance prediction updates
DCM33FlowMin(0.71f),// If Tbn(3,3) is less than this number, optical flow measurements will not be fused as tilt is too high.