mirror of https://github.com/ArduPilot/ardupilot
AP_NavEKF3: Remove unused class variable rngBcnTimeout
This commit is contained in:
parent
9d85a4292e
commit
1281033931
|
@ -328,14 +328,12 @@ void NavEKF3_core::setAidingMode()
|
|||
PV_AidingMode = AID_NONE;
|
||||
posTimeout = true;
|
||||
velTimeout = true;
|
||||
rngBcnTimeout = true;
|
||||
tasTimeout = true;
|
||||
gpsNotAvailable = true;
|
||||
} else if (posAidLossCritical) {
|
||||
// if the loss of position is critical, declare all sources of position aiding as being timed out
|
||||
posTimeout = true;
|
||||
velTimeout = !optFlowUsed && !gpsVelUsed && !bodyOdmUsed;
|
||||
rngBcnTimeout = true;
|
||||
gpsNotAvailable = true;
|
||||
|
||||
}
|
||||
|
|
|
@ -342,7 +342,6 @@ void NavEKF3_core::InitialiseVariables()
|
|||
lastRngBcnPassTime_ms = 0;
|
||||
rngBcnTestRatio = 0.0f;
|
||||
rngBcnHealth = false;
|
||||
rngBcnTimeout = true;
|
||||
varInnovRngBcn = 0.0f;
|
||||
innovRngBcn = 0.0f;
|
||||
memset(&lastTimeRngBcn_ms, 0, sizeof(lastTimeRngBcn_ms));
|
||||
|
|
|
@ -1216,7 +1216,6 @@ private:
|
|||
uint32_t lastRngBcnPassTime_ms; // time stamp when the range beacon measurement last passed innovation consistency checks (msec)
|
||||
float rngBcnTestRatio; // Innovation test ratio for range beacon measurements
|
||||
bool rngBcnHealth; // boolean true if range beacon measurements have passed innovation consistency check
|
||||
bool rngBcnTimeout; // boolean true if range beacon measurements have failed innovation consistency checks for too long
|
||||
float varInnovRngBcn; // range beacon observation innovation variance (m^2)
|
||||
float innovRngBcn; // range beacon observation innovation (m)
|
||||
uint32_t lastTimeRngBcn_ms[4]; // last time we received a range beacon measurement (msec)
|
||||
|
|
Loading…
Reference in New Issue