AP_NavEKF2: remove unused terrainHgtStableSet_ms

This commit is contained in:
Randy Mackay 2020-06-22 14:14:42 +09:00
parent dccc3e22d9
commit a8c2be26ba
3 changed files with 0 additions and 3 deletions

View File

@ -473,7 +473,6 @@ void NavEKF2_core::setTouchdownExpected(bool val)
// enabled by the combination of EK2_RNG_AID_HGT and EK2_RNG_USE_SPD parameters.
void NavEKF2_core::setTerrainHgtStable(bool val)
{
terrainHgtStableSet_ms = imuSampleTime_ms;
terrainHgtStable = val;
}

View File

@ -174,7 +174,6 @@ void NavEKF2_core::InitialiseVariables()
lastVelReset_ms = 0;
lastPosResetD_ms = 0;
lastRngMeasTime_ms = 0;
terrainHgtStableSet_ms = 0;
// initialise other variables
gpsNoiseScaler = 1.0f;

View File

@ -1105,7 +1105,6 @@ private:
uint32_t lastRngMeasTime_ms; // Timestamp of last range measurement
uint8_t rngMeasIndex[2]; // Current range measurement ringbuffer index for dual range sensors
bool terrainHgtStable; // true when the terrain height is stable enough to be used as a height reference
uint32_t terrainHgtStableSet_ms; // system time at which terrainHgtStable was set
// Range Beacon Sensor Fusion
obs_ring_buffer_t<rng_bcn_elements> storedRangeBeacon; // Beacon range buffer