AP_NavEKF2: Explicitly define plane build type for default parameters

Use Copter parameters if build type is unknown
This commit is contained in:
Paul Riseborough 2015-10-30 21:57:30 +11:00 committed by Andrew Tridgell
parent 7ed36d8e65
commit 2ebce110b7
1 changed files with 25 additions and 2 deletions

View File

@ -59,8 +59,8 @@
#define FLOW_GATE_DEFAULT 3 #define FLOW_GATE_DEFAULT 3
#define GSCALE_PNOISE_DEFAULT 3.0E-03f #define GSCALE_PNOISE_DEFAULT 3.0E-03f
#else #elif APM_BUILD_TYPE(APM_BUILD_ArduPlane)
// generic defaults (and for plane) // plane 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 1.0f #define POSNE_NOISE_DEFAULT 1.0f
@ -82,6 +82,29 @@
#define FLOW_GATE_DEFAULT 3 #define FLOW_GATE_DEFAULT 3
#define GSCALE_PNOISE_DEFAULT 3.0E-03f #define GSCALE_PNOISE_DEFAULT 3.0E-03f
#else
// build type not specified, use copter defaults
#define VELNE_NOISE_DEFAULT 0.5f
#define VELD_NOISE_DEFAULT 0.7f
#define POSNE_NOISE_DEFAULT 1.0f
#define ALT_NOISE_DEFAULT 5.0f
#define MAG_NOISE_DEFAULT 0.05f
#define GYRO_PNOISE_DEFAULT 0.005f
#define ACC_PNOISE_DEFAULT 0.25f
#define GBIAS_PNOISE_DEFAULT 7.0E-05f
#define ABIAS_PNOISE_DEFAULT 1.0E-04f
#define MAG_PNOISE_DEFAULT 2.5E-02f
#define VEL_GATE_DEFAULT 3
#define POS_GATE_DEFAULT 3
#define HGT_GATE_DEFAULT 3
#define MAG_GATE_DEFAULT 3
#define MAG_CAL_DEFAULT 3
#define GLITCH_RADIUS_DEFAULT 25
#define FLOW_MEAS_DELAY 10
#define FLOW_NOISE_DEFAULT 0.25f
#define FLOW_GATE_DEFAULT 3
#define GSCALE_PNOISE_DEFAULT 3.0E-03f
#endif // APM_BUILD_DIRECTORY #endif // APM_BUILD_DIRECTORY
// Define tuning parameters // Define tuning parameters