AP_NavEKF : Add time based noise to terrain offset state
This commit is contained in:
parent
b1d3d5d9a3
commit
117bd2a998
@ -2535,7 +2535,9 @@ void NavEKF::RunAuxiliaryEKF()
|
||||
return;
|
||||
}
|
||||
distanceTravelledSq = min(distanceTravelledSq, 100.0f);
|
||||
Popt[1][1] += (distanceTravelledSq * sq(0.01f*float(_gndGradientSigma)));
|
||||
float timeLapsed = min(0.001f * (imuSampleTime_ms - timeAtLastAuxEKF_ms), 1.0f);
|
||||
Popt[1][1] += (distanceTravelledSq * sq(0.01f*float(_gndGradientSigma))) + sq(1.0f * timeLapsed);
|
||||
timeAtLastAuxEKF_ms = imuSampleTime_ms;
|
||||
}
|
||||
|
||||
// fuse range finder data
|
||||
@ -4202,7 +4204,7 @@ void NavEKF::ZeroVariables()
|
||||
lastFixTime_ms = imuSampleTime_ms;
|
||||
secondLastFixTime_ms = imuSampleTime_ms;
|
||||
lastDecayTime_ms = imuSampleTime_ms;
|
||||
airborneDetectTime_ms = imuSampleTime_ms;
|
||||
timeAtLastAuxEKF_ms = imuSampleTime_ms;
|
||||
|
||||
gpsNoiseScaler = 1.0f;
|
||||
velTimeout = false;
|
||||
|
@ -503,6 +503,7 @@ private:
|
||||
uint8_t storeIndex; // State vector storage index
|
||||
uint32_t lastStateStoreTime_ms; // time of last state vector storage
|
||||
uint32_t lastFixTime_ms; // time of last GPS fix used to determine if new data has arrived
|
||||
uint32_t timeAtLastAuxEKF_ms; // last time the auxilliary filter was run to fuse range or optical flow measurements
|
||||
uint32_t secondLastFixTime_ms; // time of second last GPS fix used to determine how long since last update
|
||||
uint32_t lastHealthyMagTime_ms; // time the magnetometer was last declared healthy
|
||||
Vector3f lastAngRate; // angular rate from previous IMU sample used for trapezoidal integrator
|
||||
|
Loading…
Reference in New Issue
Block a user