From 80f9ef7ed144e0cb5462ea70a4a35b8d024dd524 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Sat, 17 Oct 2020 11:30:16 +1100 Subject: [PATCH] AP_NavEKF2: remove unused innovationIncrement and lastInnovation --- libraries/AP_NavEKF2/AP_NavEKF2_core.cpp | 2 -- libraries/AP_NavEKF2/AP_NavEKF2_core.h | 4 ---- 2 files changed, 6 deletions(-) diff --git a/libraries/AP_NavEKF2/AP_NavEKF2_core.cpp b/libraries/AP_NavEKF2/AP_NavEKF2_core.cpp index 65937d9538..5c7af492b5 100644 --- a/libraries/AP_NavEKF2/AP_NavEKF2_core.cpp +++ b/libraries/AP_NavEKF2/AP_NavEKF2_core.cpp @@ -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; diff --git a/libraries/AP_NavEKF2/AP_NavEKF2_core.h b/libraries/AP_NavEKF2/AP_NavEKF2_core.h index 7c16386557..e646c6b5dd 100644 --- a/libraries/AP_NavEKF2/AP_NavEKF2_core.h +++ b/libraries/AP_NavEKF2/AP_NavEKF2_core.h @@ -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 storedOF; // OF data buffer of_elements ofDataNew; // OF data at the current time horizon