From db043744a47a339c51e05772a565bd2b7b114559 Mon Sep 17 00:00:00 2001 From: priseborough Date: Mon, 7 Apr 2014 21:01:08 +1000 Subject: [PATCH] AP_NavEKF : Reduce Z accel bias process noise to provide a more stable estimate --- libraries/AP_NavEKF/AP_NavEKF.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/libraries/AP_NavEKF/AP_NavEKF.cpp b/libraries/AP_NavEKF/AP_NavEKF.cpp index b2ec385a67..18b0b6cd33 100644 --- a/libraries/AP_NavEKF/AP_NavEKF.cpp +++ b/libraries/AP_NavEKF/AP_NavEKF.cpp @@ -35,7 +35,7 @@ #define GYRO_PNOISE_DEFAULT 0.015f #define ACC_PNOISE_DEFAULT 0.25f #define GBIAS_PNOISE_DEFAULT 1E-07f -#define ABIAS_PNOISE_DEFAULT 0.00015f +#define ABIAS_PNOISE_DEFAULT 0.0001f #define MAGE_PNOISE_DEFAULT 0.0003f #define MAGB_PNOISE_DEFAULT 0.0003f #define VEL_GATE_DEFAULT 2 @@ -56,7 +56,7 @@ #define GYRO_PNOISE_DEFAULT 0.015f #define ACC_PNOISE_DEFAULT 0.25f #define GBIAS_PNOISE_DEFAULT 1E-07f -#define ABIAS_PNOISE_DEFAULT 0.00015f +#define ABIAS_PNOISE_DEFAULT 0.0001f #define MAGE_PNOISE_DEFAULT 0.0003f #define MAGB_PNOISE_DEFAULT 0.0003f #define VEL_GATE_DEFAULT 2 @@ -77,7 +77,7 @@ #define GYRO_PNOISE_DEFAULT 0.015f #define ACC_PNOISE_DEFAULT 0.25f #define GBIAS_PNOISE_DEFAULT 1E-07f -#define ABIAS_PNOISE_DEFAULT 0.00015f +#define ABIAS_PNOISE_DEFAULT 0.0001f #define MAGE_PNOISE_DEFAULT 0.0003f #define MAGB_PNOISE_DEFAULT 0.0003f #define VEL_GATE_DEFAULT 3