AP_NavEKF2: Remove un-used data in IMU buffer

Recovers 416 Bytes of memory per EKF2 instance for Copter
This commit is contained in:
Paul Riseborough 2015-11-09 13:38:41 +11:00 committed by Andrew Tridgell
parent 88cc1e2ffe
commit 5d2f78996a
2 changed files with 1 additions and 3 deletions

View File

@ -165,7 +165,6 @@ void NavEKF2_core::InitialiseVariables()
tiltAlignComplete = false;
yawAlignComplete = false;
stateIndexLim = 23;
imuDataNew.frame = 0;
baroStoreIndex = 0;
magStoreIndex = 0;
gpsStoreIndex = 0;

View File

@ -358,8 +358,7 @@ private:
Vector3f delVel; // 3..5
float delAngDT; // 6
float delVelDT; // 7
uint32_t frame; // 8
uint32_t time_ms; // 9
uint32_t time_ms; // 8
};
struct gps_elements {