mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
AP_NavEKF3: remove unused innovationIncrement and lastInnovation
This commit is contained in:
parent
80f9ef7ed1
commit
3dc67f09fd
@ -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;
|
||||
|
@ -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<of_elements> storedOF; // OF data buffer
|
||||
of_elements ofDataNew; // OF data at the current time horizon
|
||||
|
Loading…
Reference in New Issue
Block a user