mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
AP_NavEKF2: change order of variable initialisation
No functional change, this modifies the init order to match the declaration order.
This commit is contained in:
parent
82854953e7
commit
fbecda7eeb
@ -294,19 +294,17 @@ void NavEKF2_core::InitialiseVariables()
|
||||
rngBcnLast3DmeasTime_ms = 0;
|
||||
rngBcnGoodToAlign = false;
|
||||
lastRngBcnChecked = 0;
|
||||
memset(&receiverPosCov, 0, sizeof(receiverPosCov));
|
||||
receiverPos.zero();
|
||||
memset(&receiverPosCov, 0, sizeof(receiverPosCov));
|
||||
rngBcnAlignmentStarted = false;
|
||||
rngBcnAlignmentCompleted = false;
|
||||
lastBeaconIndex = 0;
|
||||
rngBcnPosSum.zero();
|
||||
numBcnMeas = 0;
|
||||
rngSum = 0.0f;
|
||||
memset(&rngBcnFusionReport, 0, sizeof(rngBcnFusionReport));
|
||||
rngBcnFuseDataReportIndex = 0;
|
||||
N_beacons = 0;
|
||||
minBcnPosD = 0.0f;
|
||||
maxBcnPosD = 0.0f;
|
||||
minBcnPosD = 0.0f;
|
||||
bcnPosOffset = 0.0f;
|
||||
bcnPosOffsetMax = 0.0f;
|
||||
bcnPosOffsetMaxVar = 0.0f;
|
||||
@ -314,6 +312,8 @@ void NavEKF2_core::InitialiseVariables()
|
||||
bcnPosOffsetMin = 0.0f;
|
||||
bcnPosOffsetMinVar = 0.0f;
|
||||
OffsetMinInnovFilt = 0.0f;
|
||||
rngBcnFuseDataReportIndex = 0;
|
||||
memset(&rngBcnFusionReport, 0, sizeof(rngBcnFusionReport));
|
||||
|
||||
// zero data buffers
|
||||
storedIMU.reset();
|
||||
|
Loading…
Reference in New Issue
Block a user