mirror of https://github.com/ArduPilot/ardupilot
AP_NavEKF2: Adjust parameter defaults
This commit is contained in:
parent
8bcedb228b
commit
7230472516
|
@ -17,67 +17,70 @@
|
||||||
// copter defaults
|
// copter defaults
|
||||||
#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 0.5f
|
#define POSNE_NOISE_DEFAULT 1.0f
|
||||||
#define ALT_NOISE_DEFAULT 1.0f
|
#define ALT_NOISE_DEFAULT 1.5f
|
||||||
#define MAG_NOISE_DEFAULT 0.05f
|
#define MAG_NOISE_DEFAULT 0.05f
|
||||||
#define GYRO_PNOISE_DEFAULT 0.01f
|
#define GYRO_PNOISE_DEFAULT 0.005f
|
||||||
#define ACC_PNOISE_DEFAULT 0.25f
|
#define ACC_PNOISE_DEFAULT 0.25f
|
||||||
#define GBIAS_PNOISE_DEFAULT 1E-05f
|
#define GBIAS_PNOISE_DEFAULT 5E-06f
|
||||||
#define ABIAS_PNOISE_DEFAULT 0.00005f
|
#define ABIAS_PNOISE_DEFAULT 0.00005f
|
||||||
#define MAG_PNOISE_DEFAULT 0.0003f
|
#define MAG_PNOISE_DEFAULT 0.0003f
|
||||||
#define VEL_GATE_DEFAULT 5
|
#define VEL_GATE_DEFAULT 5
|
||||||
#define POS_GATE_DEFAULT 5
|
#define POS_GATE_DEFAULT 5
|
||||||
#define HGT_GATE_DEFAULT 10
|
#define HGT_GATE_DEFAULT 5
|
||||||
#define MAG_GATE_DEFAULT 3
|
#define MAG_GATE_DEFAULT 3
|
||||||
#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 3
|
#define FLOW_GATE_DEFAULT 3
|
||||||
|
#define GSCALE_PNOISE_DEFAULT 1e-6f
|
||||||
|
|
||||||
#elif APM_BUILD_TYPE(APM_BUILD_APMrover2)
|
#elif APM_BUILD_TYPE(APM_BUILD_APMrover2)
|
||||||
// rover defaults
|
// rover defaults
|
||||||
#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 0.5f
|
#define POSNE_NOISE_DEFAULT 1.0f
|
||||||
#define ALT_NOISE_DEFAULT 1.0f
|
#define ALT_NOISE_DEFAULT 1.5f
|
||||||
#define MAG_NOISE_DEFAULT 0.05f
|
#define MAG_NOISE_DEFAULT 0.05f
|
||||||
#define GYRO_PNOISE_DEFAULT 0.01f
|
#define GYRO_PNOISE_DEFAULT 0.005f
|
||||||
#define ACC_PNOISE_DEFAULT 0.25f
|
#define ACC_PNOISE_DEFAULT 0.25f
|
||||||
#define GBIAS_PNOISE_DEFAULT 8E-06f
|
#define GBIAS_PNOISE_DEFAULT 5E-06f
|
||||||
#define ABIAS_PNOISE_DEFAULT 0.00005f
|
#define ABIAS_PNOISE_DEFAULT 0.00005f
|
||||||
#define MAG_PNOISE_DEFAULT 0.0003f
|
#define MAG_PNOISE_DEFAULT 0.0003f
|
||||||
#define VEL_GATE_DEFAULT 5
|
#define VEL_GATE_DEFAULT 5
|
||||||
#define POS_GATE_DEFAULT 5
|
#define POS_GATE_DEFAULT 5
|
||||||
#define HGT_GATE_DEFAULT 10
|
#define HGT_GATE_DEFAULT 5
|
||||||
#define MAG_GATE_DEFAULT 3
|
#define MAG_GATE_DEFAULT 3
|
||||||
#define MAG_CAL_DEFAULT 2
|
#define MAG_CAL_DEFAULT 3
|
||||||
#define GLITCH_RADIUS_DEFAULT 25
|
#define GLITCH_RADIUS_DEFAULT 25
|
||||||
#define FLOW_MEAS_DELAY 25
|
#define FLOW_MEAS_DELAY 10
|
||||||
#define FLOW_NOISE_DEFAULT 0.15f
|
#define FLOW_NOISE_DEFAULT 0.25f
|
||||||
#define FLOW_GATE_DEFAULT 5
|
#define FLOW_GATE_DEFAULT 3
|
||||||
|
#define GSCALE_PNOISE_DEFAULT 1e-6f
|
||||||
|
|
||||||
#else
|
#else
|
||||||
// generic defaults (and for plane)
|
// generic defaults (and for plane)
|
||||||
#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 0.5f
|
#define POSNE_NOISE_DEFAULT 1.0f
|
||||||
#define ALT_NOISE_DEFAULT 0.5f
|
#define ALT_NOISE_DEFAULT 1.5f
|
||||||
#define MAG_NOISE_DEFAULT 0.05f
|
#define MAG_NOISE_DEFAULT 0.05f
|
||||||
#define GYRO_PNOISE_DEFAULT 0.015f
|
#define GYRO_PNOISE_DEFAULT 0.005f
|
||||||
#define ACC_PNOISE_DEFAULT 0.5f
|
#define ACC_PNOISE_DEFAULT 0.25f
|
||||||
#define GBIAS_PNOISE_DEFAULT 8E-06f
|
#define GBIAS_PNOISE_DEFAULT 5E-06f
|
||||||
#define ABIAS_PNOISE_DEFAULT 0.00005f
|
#define ABIAS_PNOISE_DEFAULT 0.00005f
|
||||||
#define MAG_PNOISE_DEFAULT 0.0003f
|
#define MAG_PNOISE_DEFAULT 0.0003f
|
||||||
#define VEL_GATE_DEFAULT 6
|
#define VEL_GATE_DEFAULT 5
|
||||||
#define POS_GATE_DEFAULT 30
|
#define POS_GATE_DEFAULT 5
|
||||||
#define HGT_GATE_DEFAULT 20
|
#define HGT_GATE_DEFAULT 5
|
||||||
#define MAG_GATE_DEFAULT 3
|
#define MAG_GATE_DEFAULT 3
|
||||||
#define MAG_CAL_DEFAULT 0
|
#define MAG_CAL_DEFAULT 3
|
||||||
#define GLITCH_RADIUS_DEFAULT 25
|
#define GLITCH_RADIUS_DEFAULT 25
|
||||||
#define FLOW_MEAS_DELAY 25
|
#define FLOW_MEAS_DELAY 10
|
||||||
#define FLOW_NOISE_DEFAULT 0.3f
|
#define FLOW_NOISE_DEFAULT 0.25f
|
||||||
#define FLOW_GATE_DEFAULT 3
|
#define FLOW_GATE_DEFAULT 3
|
||||||
|
#define GSCALE_PNOISE_DEFAULT 1e-6f
|
||||||
|
|
||||||
#endif // APM_BUILD_DIRECTORY
|
#endif // APM_BUILD_DIRECTORY
|
||||||
|
|
||||||
|
@ -327,7 +330,7 @@ const AP_Param::GroupInfo NavEKF2::var_info[] PROGMEM = {
|
||||||
// @Range: 0.0000001 0.00001
|
// @Range: 0.0000001 0.00001
|
||||||
// @User: Advanced
|
// @User: Advanced
|
||||||
// @Units: 1/s
|
// @Units: 1/s
|
||||||
AP_GROUPINFO("GSCL_PNOISE", 27, NavEKF2, _gyroScaleProcessNoise, 1e-6f),
|
AP_GROUPINFO("GSCL_PNOISE", 27, NavEKF2, _gyroScaleProcessNoise, GSCALE_PNOISE_DEFAULT),
|
||||||
|
|
||||||
// @Param: ABIAS_PNOISE
|
// @Param: ABIAS_PNOISE
|
||||||
// @DisplayName: Accelerometer bias process noise (m/s^2)
|
// @DisplayName: Accelerometer bias process noise (m/s^2)
|
||||||
|
|
Loading…
Reference in New Issue