mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-21 16:18:29 -04:00
AP_NavEKF3: remove unused terrainHgtStableSet_ms
This commit is contained in:
parent
a8c2be26ba
commit
ec5f84c926
@ -470,7 +470,6 @@ void NavEKF3_core::setTouchdownExpected(bool val)
|
||||
// enabled by the combination of EK3_RNG_USE_HGT and EK3_RNG_USE_SPD parameters.
|
||||
void NavEKF3_core::setTerrainHgtStable(bool val)
|
||||
{
|
||||
terrainHgtStableSet_ms = imuSampleTime_ms;
|
||||
terrainHgtStable = val;
|
||||
}
|
||||
|
||||
|
@ -225,7 +225,6 @@ void NavEKF3_core::InitialiseVariables()
|
||||
lastVelReset_ms = 0;
|
||||
lastPosResetD_ms = 0;
|
||||
lastRngMeasTime_ms = 0;
|
||||
terrainHgtStableSet_ms = 0;
|
||||
|
||||
// initialise other variables
|
||||
gpsNoiseScaler = 1.0f;
|
||||
|
@ -1238,7 +1238,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
|
||||
|
||||
// body frame odometry fusion
|
||||
obs_ring_buffer_t<vel_odm_elements> storedBodyOdm; // body velocity data buffer
|
||||
|
Loading…
Reference in New Issue
Block a user