mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-14 10:07:39 +08:00
Better defaults for filter noise params
This commit is contained in:
parent
aceca6b2a9
commit
bab79ece49
@ -218,7 +218,7 @@ PARAM_DEFINE_FLOAT(PE_ACC_PNOISE, 0.25f);
|
||||
* @max 0.00001
|
||||
* @group Position Estimator
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(PE_GBIAS_PNOISE, 1e-07f);
|
||||
PARAM_DEFINE_FLOAT(PE_GBIAS_PNOISE, 1e-06f);
|
||||
|
||||
/**
|
||||
* Accelerometer bias estimate process noise
|
||||
@ -230,7 +230,7 @@ PARAM_DEFINE_FLOAT(PE_GBIAS_PNOISE, 1e-07f);
|
||||
* @max 0.001
|
||||
* @group Position Estimator
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(PE_ABIAS_PNOISE, 0.00005f);
|
||||
PARAM_DEFINE_FLOAT(PE_ABIAS_PNOISE, 0.0002f);
|
||||
|
||||
/**
|
||||
* Magnetometer earth frame offsets process noise
|
||||
|
||||
@ -210,10 +210,10 @@ void AttPosEKF::InitialiseParameters()
|
||||
|
||||
yawVarScale = 1.0f;
|
||||
windVelSigma = 0.1f;
|
||||
dAngBiasSigma = 5.0e-7;
|
||||
dVelBiasSigma = 1e-4f;
|
||||
magEarthSigma = 3.0e-4f;
|
||||
magBodySigma = 3.0e-4f;
|
||||
dAngBiasSigma = 1.0e-6;
|
||||
dVelBiasSigma = 0.0002f;
|
||||
magEarthSigma = 0.0003f;
|
||||
magBodySigma = 0.0003f;
|
||||
|
||||
vneSigma = 0.2f;
|
||||
vdSigma = 0.3f;
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user