mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
AP_NavEKF2: remove unused terrainHgtStableSet_ms
This commit is contained in:
parent
dccc3e22d9
commit
a8c2be26ba
@ -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;
|
||||
}
|
||||
|
||||
|
@ -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;
|
||||
|
@ -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
|
||||
|
Loading…
Reference in New Issue
Block a user