From 7d48704f8204db59c9afcdea68afbc52bf702113 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Mon, 27 Oct 2014 22:20:03 +0900 Subject: [PATCH] AP_NavEKF: fix parameter descriptions Errors pointed out by Richard (DK) --- libraries/AP_NavEKF/AP_NavEKF.cpp | 98 +++++++++++++++---------------- 1 file changed, 49 insertions(+), 49 deletions(-) diff --git a/libraries/AP_NavEKF/AP_NavEKF.cpp b/libraries/AP_NavEKF/AP_NavEKF.cpp index de4fb68a3a..87834344a5 100644 --- a/libraries/AP_NavEKF/AP_NavEKF.cpp +++ b/libraries/AP_NavEKF/AP_NavEKF.cpp @@ -108,173 +108,173 @@ const AP_Param::GroupInfo NavEKF::var_info[] PROGMEM = { // @Param: VELNE_NOISE // @DisplayName: GPS horizontal velocity measurement noise (m/s) // @Description: This is the RMS value of noise in the North and East GPS velocity measurements. Increasing it reduces the weighting on these measurements. - // @Range: 0.05 - 5.0 + // @Range: 0.05 5.0 // @Increment: 0.05 - // @User: advanced + // @User: Advanced AP_GROUPINFO("VELNE_NOISE", 0, NavEKF, _gpsHorizVelNoise, VELNE_NOISE_DEFAULT), // @Param: VELD_NOISE // @DisplayName: GPS vertical velocity measurement noise (m/s) // @Description: This is the RMS value of noise in the vertical GPS velocity measurement. Increasing it reduces the weighting on this measurement. - // @Range: 0.05 - 5.0 + // @Range: 0.05 5.0 // @Increment: 0.05 - // @User: advanced + // @User: Advanced AP_GROUPINFO("VELD_NOISE", 1, NavEKF, _gpsVertVelNoise, VELD_NOISE_DEFAULT), // @Param: POSNE_NOISE // @DisplayName: GPS horizontal position measurement noise (m) // @Description: This is the RMS value of noise in the GPS horizontal position measurements. Increasing it reduces the weighting on these measurements. - // @Range: 0.1 - 10.0 + // @Range: 0.1 10.0 // @Increment: 0.1 - // @User: advanced + // @User: Advanced AP_GROUPINFO("POSNE_NOISE", 2, NavEKF, _gpsHorizPosNoise, POSNE_NOISE_DEFAULT), // @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. - // @Range: 0.1 - 10.0 + // @Range: 0.1 10.0 // @Increment: 0.1 - // @User: advanced + // @User: Advanced AP_GROUPINFO("ALT_NOISE", 3, NavEKF, _baroAltNoise, ALT_NOISE_DEFAULT), // @Param: MAG_NOISE // @DisplayName: Magnetometer measurement noise (Gauss) // @Description: This is the RMS value of noise in magnetometer measurements. Increasing it reduces the weighting on these measurements. - // @Range: 0.01 - 0.5 + // @Range: 0.01 0.5 // @Increment: 0.01 - // @User: advanced + // @User: Advanced AP_GROUPINFO("MAG_NOISE", 4, NavEKF, _magNoise, MAG_NOISE_DEFAULT), // @Param: EAS_NOISE // @DisplayName: Equivalent airspeed measurement noise (m/s) // @Description: This is the RMS value of noise in magnetometer measurements. Increasing it reduces the weighting on these measurements. - // @Range: 0.5 - 5.0 + // @Range: 0.5 5.0 // @Increment: 0.1 - // @User: advanced + // @User: Advanced AP_GROUPINFO("EAS_NOISE", 5, NavEKF, _easNoise, 1.4f), // @Param: WIND_PNOISE // @DisplayName: Wind velocity process noise (m/s^2) // @Description: This noise controls the growth of wind state error estimates. Increasing it makes wind estimation faster and noisier. - // @Range: 0.01 - 1.0 + // @Range: 0.01 1.0 // @Increment: 0.1 - // @User: advanced + // @User: Advanced AP_GROUPINFO("WIND_PNOISE", 6, NavEKF, _windVelProcessNoise, 0.1f), // @Param: WIND_PSCALE // @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. - // @Range: 0.0 - 1.0 + // @Range: 0.0 1.0 // @Increment: 0.1 - // @User: advanced + // @User: Advanced AP_GROUPINFO("WIND_PSCALE", 7, NavEKF, _wndVarHgtRateScale, 0.5f), // @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. - // @Range: 0.001 - 0.05 + // @Range: 0.001 0.05 // @Increment: 0.001 - // @User: advanced + // @User: Advanced AP_GROUPINFO("GYRO_PNOISE", 8, NavEKF, _gyrNoise, GYRO_PNOISE_DEFAULT), // @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. - // @Range: 0.05 - 1.0 AP_Float _gpsNEVelVarAccScale; // scale factor applied to NE velocity measurement variance due to Vdot + // @Range: 0.05 1.0 // @Increment: 0.01 - // @User: advanced + // @User: Advanced AP_GROUPINFO("ACC_PNOISE", 9, NavEKF, _accNoise, ACC_PNOISE_DEFAULT), // @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. - // @Range: 0.0000001 - 0.00001 - // @User: advanced + // @Range: 0.0000001 0.00001 + // @User: Advanced AP_GROUPINFO("GBIAS_PNOISE", 10, NavEKF, _gyroBiasProcessNoise, GBIAS_PNOISE_DEFAULT), // @Param: ABIAS_PNOISE // @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. - // @Range: 0.00001 - 0.001 - // @User: advanced + // @Range: 0.00001 0.001 + // @User: Advanced AP_GROUPINFO("ABIAS_PNOISE", 11, NavEKF, _accelBiasProcessNoise, ABIAS_PNOISE_DEFAULT), // @Param: MAGE_PNOISE // @DisplayName: Earth magnetic field process noise (gauss/s) // @Description: This noise controls the growth of earth magnetic field state error estimates. Increasing it makes earth magnetic field bias estimation faster and noisier. - // @Range: 0.0001 - 0.01 - // @User: advanced + // @Range: 0.0001 0.01 + // @User: Advanced AP_GROUPINFO("MAGE_PNOISE", 12, NavEKF, _magEarthProcessNoise, MAGE_PNOISE_DEFAULT), // @Param: MAGB_PNOISE // @DisplayName: Body magnetic field process noise (gauss/s) // @Description: This noise controls the growth of body magnetic field state error estimates. Increasing it makes compass offset estimation faster and noisier. - // @Range: 0.0001 - 0.01 - // @User: advanced + // @Range: 0.0001 0.01 + // @User: Advanced AP_GROUPINFO("MAGB_PNOISE", 13, NavEKF, _magBodyProcessNoise, MAGB_PNOISE_DEFAULT), // @Param: VEL_DELAY // @DisplayName: GPS velocity measurement delay (msec) // @Description: This is the number of msec that the GPS velocity measurements lag behind the inertial measurements. - // @Range: 0 - 500 + // @Range: 0 500 // @Increment: 10 - // @User: advanced + // @User: Advanced AP_GROUPINFO("VEL_DELAY", 14, NavEKF, _msecVelDelay, 220), // @Param: POS_DELAY // @DisplayName: GPS position measurement delay (msec) // @Description: This is the number of msec that the GPS position measurements lag behind the inertial measurements. - // @Range: 0 - 500 + // @Range: 0 500 // @Increment: 10 - // @User: advancedScale factor applied to horizontal position measurement variance due to manoeuvre acceleration + // @User: Advanced AP_GROUPINFO("POS_DELAY", 15, NavEKF, _msecPosDelay, 220), // @Param: GPS_TYPE // @DisplayName: GPS velocity mode control // @Description: This parameter controls use of GPS velocity measurements : 0 = use 3D velocity, 1 = use 2D velocity, 2 = use no velocity - // @Range: 0 - 3 + // @Range: 0 3 // @Increment: 1 - // @User: advanced + // @User: Advanced AP_GROUPINFO("GPS_TYPE", 16, NavEKF, _fusionModeGPS, 0), // @Param: VEL_GATE // @DisplayName: GPS velocity measurement gate size // @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 + // @Range: 1 100 // @Increment: 1 - // @User: advanced + // @User: Advanced AP_GROUPINFO("VEL_GATE", 17, NavEKF, _gpsVelInnovGate, VEL_GATE_DEFAULT), // @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. - // @Range: 1 - 100 + // @Range: 1 100 // @Increment: 1 - // @User: advanced + // @User: Advanced AP_GROUPINFO("POS_GATE", 18, NavEKF, _gpsPosInnovGate, POS_GATE_DEFAULT), // @Param: HGT_GATE // @DisplayName: Height measurement gate size // @Description: This parameter sets the number of standard deviations applied to the height 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 + // @Range: 1 100 // @Increment: 1 - // @User: advanced + // @User: Advanced AP_GROUPINFO("HGT_GATE", 19, NavEKF, _hgtInnovGate, HGT_GATE_DEFAULT), // @Param: MAG_GATE // @DisplayName: Magnetometer measurement gate size // @Description: This parameter sets the number of standard deviations applied to the magnetometer 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 + // @Range: 1 100 // @Increment: 1 - // @User: advanced + // @User: Advanced AP_GROUPINFO("MAG_GATE", 20, NavEKF, _magInnovGate, MAG_GATE_DEFAULT), // @Param: EAS_GATE // @DisplayName: Airspeed measurement gate size // @Description: This parameter sets the number of standard deviations applied to the airspeed 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 + // @Range: 1 100 // @Increment: 1 - // @User: advanced + // @User: Advanced AP_GROUPINFO("EAS_GATE", 21, NavEKF, _tasInnovGate, 10), // @Param: MAG_CAL @@ -282,23 +282,23 @@ const AP_Param::GroupInfo NavEKF::var_info[] PROGMEM = { // @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 // @Increment: 1 - // @User: advanced + // @User: Advanced AP_GROUPINFO("MAG_CAL", 22, NavEKF, _magCal, MAG_CAL_DEFAULT), // @Param: GLITCH_ACCEL // @DisplayName: GPS glitch accel gate size (cm/s^2) // @Description: This parameter controls the maximum amount of difference in horizontal acceleration between the value predicted by the filter and the value measured by the GPS before the GPS position data is rejected. If this value is set too low, then valid GPS data will be regularly discarded, and the position accuracy will degrade. If this parameter is set too high, then large GPS glitches will cause large rapid changes in position. - // @Range: 100 - 500 + // @Range: 100 500 // @Increment: 50 - // @User: advanced + // @User: Advanced AP_GROUPINFO("GLITCH_ACCEL", 23, NavEKF, _gpsGlitchAccelMax, GLITCH_ACCEL_DEFAULT), // @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. - // @Range: 10 - 50 + // @Range: 10 50 // @Increment: 5 - // @User: advanced + // @User: Advanced AP_GROUPINFO("GLITCH_RAD", 24, NavEKF, _gpsGlitchRadiusMax, GLITCH_RADIUS_DEFAULT), AP_GROUPEND