AP_NavEKF: clean up unused variable lastDivergeTime_ms

This commit is contained in:
Jonathan Challinger 2014-10-29 12:42:35 -07:00 committed by Andrew Tridgell
parent 5e51c09978
commit 0727ac5c79
2 changed files with 0 additions and 2 deletions

View File

@ -3349,7 +3349,6 @@ void NavEKF::ZeroVariables()
// initialise time stamps
imuSampleTime_ms = hal.scheduler->millis();
lastHealthyMagTime_ms = imuSampleTime_ms;
lastDivergeTime_ms = imuSampleTime_ms;
TASmsecPrev = imuSampleTime_ms;
BETAmsecPrev = imuSampleTime_ms;
lastMagUpdate = imuSampleTime_ms;

View File

@ -342,7 +342,6 @@ private:
AP_Int16 _hgtRetryTimeMode0; // height measurement retry time following innovation consistency fail if GPS fusion mode is = 0 (msec)
AP_Int16 _hgtRetryTimeMode12; // height measurement retry time following innovation consistency fail if GPS fusion mode is > 0 (msec)
uint32_t _magFailTimeLimit_ms; // number of msec before a magnetometer failing innovation consistency checks is declared failed (msec)
uint32_t lastDivergeTime_ms; // time in msec divergence of filter last detected
float _gyroBiasNoiseScaler; // scale factor applied to gyro bias state process variance when on ground
float _magVarRateScale; // scale factor applied to magnetometer variance due to angular rate
uint16_t _msecGpsAvg; // average number of msec between GPS measurements