AP_NavEKF2: update tuning defaults

This commit is contained in:
Paul Riseborough 2016-05-08 23:53:49 +10:00 committed by Andrew Tridgell
parent 65f63341d7
commit a3b78e6231
2 changed files with 38 additions and 38 deletions

View File

@ -18,23 +18,23 @@
#define VELNE_NOISE_DEFAULT 0.5f #define VELNE_NOISE_DEFAULT 0.5f
#define VELD_NOISE_DEFAULT 0.7f #define VELD_NOISE_DEFAULT 0.7f
#define POSNE_NOISE_DEFAULT 1.0f #define POSNE_NOISE_DEFAULT 1.0f
#define ALT_NOISE_DEFAULT 5.0f #define ALT_NOISE_DEFAULT 3.0f
#define MAG_NOISE_DEFAULT 0.05f #define MAG_NOISE_DEFAULT 0.05f
#define GYRO_PNOISE_DEFAULT 0.001f #define GYRO_PNOISE_DEFAULT 3.0E-02f
#define ACC_PNOISE_DEFAULT 0.25f #define ACC_PNOISE_DEFAULT 6.0E-01f
#define GBIAS_PNOISE_DEFAULT 7.0E-05f #define GBIAS_PNOISE_DEFAULT 1.0E-04f
#define ABIAS_PNOISE_DEFAULT 1.0E-04f #define GSCALE_PNOISE_DEFAULT 1.0E-05f
#define ABIAS_PNOISE_DEFAULT 1.0E-03f
#define MAG_PNOISE_DEFAULT 2.5E-02f #define MAG_PNOISE_DEFAULT 2.5E-02f
#define VEL_GATE_DEFAULT 200 #define VEL_GATE_DEFAULT 500
#define POS_GATE_DEFAULT 300 #define POS_GATE_DEFAULT 500
#define HGT_GATE_DEFAULT 300 #define HGT_GATE_DEFAULT 500
#define MAG_GATE_DEFAULT 300 #define MAG_GATE_DEFAULT 300
#define MAG_CAL_DEFAULT 3 #define MAG_CAL_DEFAULT 3
#define GLITCH_RADIUS_DEFAULT 25 #define GLITCH_RADIUS_DEFAULT 25
#define FLOW_MEAS_DELAY 10 #define FLOW_MEAS_DELAY 10
#define FLOW_NOISE_DEFAULT 0.25f #define FLOW_NOISE_DEFAULT 0.25f
#define FLOW_GATE_DEFAULT 300 #define FLOW_GATE_DEFAULT 300
#define GSCALE_PNOISE_DEFAULT 3.0E-03f
#define CHECK_SCALER_DEFAULT 100 #define CHECK_SCALER_DEFAULT 100
#elif APM_BUILD_TYPE(APM_BUILD_APMrover2) #elif APM_BUILD_TYPE(APM_BUILD_APMrover2)
@ -42,23 +42,23 @@
#define VELNE_NOISE_DEFAULT 0.5f #define VELNE_NOISE_DEFAULT 0.5f
#define VELD_NOISE_DEFAULT 0.7f #define VELD_NOISE_DEFAULT 0.7f
#define POSNE_NOISE_DEFAULT 1.0f #define POSNE_NOISE_DEFAULT 1.0f
#define ALT_NOISE_DEFAULT 2.0f #define ALT_NOISE_DEFAULT 3.0f
#define MAG_NOISE_DEFAULT 0.05f #define MAG_NOISE_DEFAULT 0.05f
#define GYRO_PNOISE_DEFAULT 0.001f #define GYRO_PNOISE_DEFAULT 3.0E-02f
#define ACC_PNOISE_DEFAULT 0.25f #define ACC_PNOISE_DEFAULT 6.0E-01f
#define GBIAS_PNOISE_DEFAULT 7.0E-05f #define GBIAS_PNOISE_DEFAULT 1.0E-04f
#define ABIAS_PNOISE_DEFAULT 1.0E-04f #define GSCALE_PNOISE_DEFAULT 1.0E-05f
#define ABIAS_PNOISE_DEFAULT 1.0E-03f
#define MAG_PNOISE_DEFAULT 2.5E-02f #define MAG_PNOISE_DEFAULT 2.5E-02f
#define VEL_GATE_DEFAULT 200 #define VEL_GATE_DEFAULT 500
#define POS_GATE_DEFAULT 300 #define POS_GATE_DEFAULT 500
#define HGT_GATE_DEFAULT 300 #define HGT_GATE_DEFAULT 500
#define MAG_GATE_DEFAULT 300 #define MAG_GATE_DEFAULT 300
#define MAG_CAL_DEFAULT 2 #define MAG_CAL_DEFAULT 2
#define GLITCH_RADIUS_DEFAULT 25 #define GLITCH_RADIUS_DEFAULT 25
#define FLOW_MEAS_DELAY 10 #define FLOW_MEAS_DELAY 10
#define FLOW_NOISE_DEFAULT 0.25f #define FLOW_NOISE_DEFAULT 0.25f
#define FLOW_GATE_DEFAULT 300 #define FLOW_GATE_DEFAULT 300
#define GSCALE_PNOISE_DEFAULT 3.0E-03f
#define CHECK_SCALER_DEFAULT 100 #define CHECK_SCALER_DEFAULT 100
#elif APM_BUILD_TYPE(APM_BUILD_ArduPlane) #elif APM_BUILD_TYPE(APM_BUILD_ArduPlane)
@ -66,23 +66,23 @@
#define VELNE_NOISE_DEFAULT 0.5f #define VELNE_NOISE_DEFAULT 0.5f
#define VELD_NOISE_DEFAULT 0.7f #define VELD_NOISE_DEFAULT 0.7f
#define POSNE_NOISE_DEFAULT 1.0f #define POSNE_NOISE_DEFAULT 1.0f
#define ALT_NOISE_DEFAULT 5.0f #define ALT_NOISE_DEFAULT 3.0f
#define MAG_NOISE_DEFAULT 0.05f #define MAG_NOISE_DEFAULT 0.05f
#define GYRO_PNOISE_DEFAULT 0.001f #define GYRO_PNOISE_DEFAULT 3.0E-02f
#define ACC_PNOISE_DEFAULT 0.25f #define ACC_PNOISE_DEFAULT 6.0E-01f
#define GBIAS_PNOISE_DEFAULT 7.0E-05f #define GBIAS_PNOISE_DEFAULT 1.0E-04f
#define ABIAS_PNOISE_DEFAULT 1.0E-04f #define GSCALE_PNOISE_DEFAULT 1.0E-05f
#define ABIAS_PNOISE_DEFAULT 1.0E-03f
#define MAG_PNOISE_DEFAULT 2.5E-02f #define MAG_PNOISE_DEFAULT 2.5E-02f
#define VEL_GATE_DEFAULT 200 #define VEL_GATE_DEFAULT 500
#define POS_GATE_DEFAULT 300 #define POS_GATE_DEFAULT 500
#define HGT_GATE_DEFAULT 400 #define HGT_GATE_DEFAULT 500
#define MAG_GATE_DEFAULT 200 #define MAG_GATE_DEFAULT 300
#define MAG_CAL_DEFAULT 0 #define MAG_CAL_DEFAULT 0
#define GLITCH_RADIUS_DEFAULT 25 #define GLITCH_RADIUS_DEFAULT 25
#define FLOW_MEAS_DELAY 10 #define FLOW_MEAS_DELAY 10
#define FLOW_NOISE_DEFAULT 0.25f #define FLOW_NOISE_DEFAULT 0.25f
#define FLOW_GATE_DEFAULT 300 #define FLOW_GATE_DEFAULT 300
#define GSCALE_PNOISE_DEFAULT 3.0E-03f
#define CHECK_SCALER_DEFAULT 150 #define CHECK_SCALER_DEFAULT 150
#else #else
@ -90,23 +90,23 @@
#define VELNE_NOISE_DEFAULT 0.5f #define VELNE_NOISE_DEFAULT 0.5f
#define VELD_NOISE_DEFAULT 0.7f #define VELD_NOISE_DEFAULT 0.7f
#define POSNE_NOISE_DEFAULT 1.0f #define POSNE_NOISE_DEFAULT 1.0f
#define ALT_NOISE_DEFAULT 5.0f #define ALT_NOISE_DEFAULT 3.0f
#define MAG_NOISE_DEFAULT 0.05f #define MAG_NOISE_DEFAULT 0.05f
#define GYRO_PNOISE_DEFAULT 0.001f #define GYRO_PNOISE_DEFAULT 3.0E-02f
#define ACC_PNOISE_DEFAULT 0.25f #define ACC_PNOISE_DEFAULT 6.0E-01f
#define GBIAS_PNOISE_DEFAULT 3.5E-05f #define GBIAS_PNOISE_DEFAULT 1.0E-04f
#define ABIAS_PNOISE_DEFAULT 1.0E-04f #define GSCALE_PNOISE_DEFAULT 1.0E-05f
#define ABIAS_PNOISE_DEFAULT 1.0E-03f
#define MAG_PNOISE_DEFAULT 2.5E-02f #define MAG_PNOISE_DEFAULT 2.5E-02f
#define VEL_GATE_DEFAULT 200 #define VEL_GATE_DEFAULT 500
#define POS_GATE_DEFAULT 300 #define POS_GATE_DEFAULT 500
#define HGT_GATE_DEFAULT 300 #define HGT_GATE_DEFAULT 500
#define MAG_GATE_DEFAULT 300 #define MAG_GATE_DEFAULT 300
#define MAG_CAL_DEFAULT 3 #define MAG_CAL_DEFAULT 3
#define GLITCH_RADIUS_DEFAULT 25 #define GLITCH_RADIUS_DEFAULT 25
#define FLOW_MEAS_DELAY 10 #define FLOW_MEAS_DELAY 10
#define FLOW_NOISE_DEFAULT 0.25f #define FLOW_NOISE_DEFAULT 0.25f
#define FLOW_GATE_DEFAULT 300 #define FLOW_GATE_DEFAULT 300
#define GSCALE_PNOISE_DEFAULT 3.0E-03f
#define CHECK_SCALER_DEFAULT 100 #define CHECK_SCALER_DEFAULT 100
#endif // APM_BUILD_DIRECTORY #endif // APM_BUILD_DIRECTORY

View File

@ -708,7 +708,7 @@ void NavEKF2_core::CovariancePrediction()
dvz_b = stateStruct.accel_zbias; dvz_b = stateStruct.accel_zbias;
float _gyrNoise = constrain_float(frontend->_gyrNoise, 0.0f, 1.0f); float _gyrNoise = constrain_float(frontend->_gyrNoise, 0.0f, 1.0f);
daxNoise = dayNoise = dazNoise = sq(dt*_gyrNoise); daxNoise = dayNoise = dazNoise = sq(dt*_gyrNoise);
float _accNoise = constrain_float(frontend->_accNoise, 0.0f, 1.0f); float _accNoise = constrain_float(frontend->_accNoise, 0.0f, 10.0f);
dvxNoise = dvyNoise = dvzNoise = sq(dt*_accNoise); dvxNoise = dvyNoise = dvzNoise = sq(dt*_accNoise);
// calculate the predicted covariance due to inertial sensor error propagation // calculate the predicted covariance due to inertial sensor error propagation