AP_NavEKF2: move global state to be on the stack

This commit is contained in:
Peter Barker 2020-10-21 16:13:00 +11:00 committed by Peter Barker
parent e241433c89
commit 400ba7a9df
3 changed files with 1 additions and 3 deletions

View File

@ -504,7 +504,7 @@ void NavEKF2_core::readGpsData()
gpsCheckStatus.bad_fix = false;
// store fix time from previous read
secondLastGpsTime_ms = lastTimeGpsReceived_ms;
const uint32_t secondLastGpsTime_ms = lastTimeGpsReceived_ms;
// get current fix time
lastTimeGpsReceived_ms = gps.last_message_time_ms(gps.primary_sensor());

View File

@ -133,7 +133,6 @@ void NavEKF2_core::InitialiseVariables()
lastTasPassTime_ms = 0;
lastYawTime_ms = imuSampleTime_ms;
lastTimeGpsReceived_ms = 0;
secondLastGpsTime_ms = 0;
lastDecayTime_ms = imuSampleTime_ms;
timeAtLastAuxEKF_ms = imuSampleTime_ms;
flowValidMeaTime_ms = imuSampleTime_ms;

View File

@ -872,7 +872,6 @@ private:
uint32_t lastTasPassTime_ms; // time stamp when airspeed measurement last passed innovation consistency check (msec)
uint32_t lastTimeGpsReceived_ms;// last time we received GPS data
uint32_t timeAtLastAuxEKF_ms; // last time the auxiliary filter was run to fuse range or optical flow measurements
uint32_t secondLastGpsTime_ms; // time of second last GPS fix used to determine how long since last update
uint32_t lastHealthyMagTime_ms; // time the magnetometer was last declared healthy
bool allMagSensorsFailed; // true if all magnetometer sensors have timed out on this flight and we are no longer using magnetometer data
uint32_t lastYawTime_ms; // time stamp when yaw observation was last fused (msec)