From 3dc67f09fd85a948fe33a5a4eef3aa395f902279 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Sat, 17 Oct 2020 11:30:16 +1100 Subject: [PATCH] AP_NavEKF3: remove unused innovationIncrement and lastInnovation --- libraries/AP_NavEKF3/AP_NavEKF3_core.cpp | 2 -- libraries/AP_NavEKF3/AP_NavEKF3_core.h | 4 ---- 2 files changed, 6 deletions(-) diff --git a/libraries/AP_NavEKF3/AP_NavEKF3_core.cpp b/libraries/AP_NavEKF3/AP_NavEKF3_core.cpp index 665227e3f0..1e1d15017c 100644 --- a/libraries/AP_NavEKF3/AP_NavEKF3_core.cpp +++ b/libraries/AP_NavEKF3/AP_NavEKF3_core.cpp @@ -303,8 +303,6 @@ void NavEKF3_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_NavEKF3/AP_NavEKF3_core.h b/libraries/AP_NavEKF3/AP_NavEKF3_core.h index 98f56bdb3d..874ff4f8ee 100644 --- a/libraries/AP_NavEKF3/AP_NavEKF3_core.h +++ b/libraries/AP_NavEKF3/AP_NavEKF3_core.h @@ -1204,10 +1204,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