Browse Source

AP_NavEKF: clean up unused variable lastDivergeTime_ms

master
Jonathan Challinger 11 years ago committed by Andrew Tridgell
parent
commit
0727ac5c79
  1. 1
      libraries/AP_NavEKF/AP_NavEKF.cpp
  2. 1
      libraries/AP_NavEKF/AP_NavEKF.h

1
libraries/AP_NavEKF/AP_NavEKF.cpp

@ -3349,7 +3349,6 @@ void NavEKF::ZeroVariables() @@ -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;

1
libraries/AP_NavEKF/AP_NavEKF.h

@ -342,7 +342,6 @@ private: @@ -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

Loading…
Cancel
Save