Browse Source

AP_NavEKF2: remove unused innovationIncrement and lastInnovation

zr-v5.1
Peter Barker 4 years ago committed by Andrew Tridgell
parent
commit
80f9ef7ed1
  1. 2
      libraries/AP_NavEKF2/AP_NavEKF2_core.cpp
  2. 4
      libraries/AP_NavEKF2/AP_NavEKF2_core.h

2
libraries/AP_NavEKF2/AP_NavEKF2_core.cpp

@ -239,8 +239,6 @@ void NavEKF2_core::InitialiseVariables() @@ -239,8 +239,6 @@ void NavEKF2_core::InitialiseVariables()
gpsNotAvailable = true;
motorsArmed = false;
prevMotorsArmed = false;
innovationIncrement = 0;
lastInnovation = 0;
memset(&gpsCheckStatus, 0, sizeof(gpsCheckStatus));
gpsSpdAccPass = false;
ekfInnovationsPass = false;

4
libraries/AP_NavEKF2/AP_NavEKF2_core.h

@ -1061,10 +1061,6 @@ private: @@ -1061,10 +1061,6 @@ private:
uint32_t lastInnovFailTime_ms; // last time in msec the GPS innovations failed
bool gpsAccuracyGood; // true when the GPS accuracy is considered to be good enough for safe flight.
// States used for unwrapping of compass yaw error
float innovationIncrement;
float lastInnovation;
// variables added for optical flow fusion
obs_ring_buffer_t<of_elements> storedOF; // OF data buffer
of_elements ofDataNew; // OF data at the current time horizon

Loading…
Cancel
Save