AP_NavEKF3: tidy population of fusion reports

simply take a refefence and use it
This commit is contained in:
Peter Barker 2024-02-26 14:58:10 +11:00 committed by Peter Barker
parent df3267c9ba
commit e9d065c1cc
1 changed files with 12 additions and 10 deletions

View File

@ -268,11 +268,12 @@ void NavEKF3_core::FuseRngBcn()
// Update the fusion report // Update the fusion report
if (rngBcn.fusionReport && rngBcn.dataDelayed.beacon_ID < dal.beacon()->count()) { if (rngBcn.fusionReport && rngBcn.dataDelayed.beacon_ID < dal.beacon()->count()) {
rngBcn.fusionReport[rngBcn.dataDelayed.beacon_ID].beaconPosNED = rngBcn.dataDelayed.beacon_posNED; auto &report = rngBcn.fusionReport[rngBcn.dataDelayed.beacon_ID];
rngBcn.fusionReport[rngBcn.dataDelayed.beacon_ID].innov = rngBcn.innov; report.beaconPosNED = rngBcn.dataDelayed.beacon_posNED;
rngBcn.fusionReport[rngBcn.dataDelayed.beacon_ID].innovVar = rngBcn.varInnov; report.innov = rngBcn.innov;
rngBcn.fusionReport[rngBcn.dataDelayed.beacon_ID].rng = rngBcn.dataDelayed.rng; report.innovVar = rngBcn.varInnov;
rngBcn.fusionReport[rngBcn.dataDelayed.beacon_ID].testRatio = rngBcn.testRatio; report.rng = rngBcn.dataDelayed.rng;
report.testRatio = rngBcn.testRatio;
} }
} }
} }
@ -506,11 +507,12 @@ void NavEKF3_core::FuseRngBcnStatic()
} }
// Update the fusion report // Update the fusion report
if (rngBcn.fusionReport && rngBcn.dataDelayed.beacon_ID < dal.beacon()->count()) { if (rngBcn.fusionReport && rngBcn.dataDelayed.beacon_ID < dal.beacon()->count()) {
rngBcn.fusionReport[rngBcn.dataDelayed.beacon_ID].beaconPosNED = rngBcn.dataDelayed.beacon_posNED; auto &report = rngBcn.fusionReport[rngBcn.dataDelayed.beacon_ID];
rngBcn.fusionReport[rngBcn.dataDelayed.beacon_ID].innov = rngBcn.innov; report.beaconPosNED = rngBcn.dataDelayed.beacon_posNED;
rngBcn.fusionReport[rngBcn.dataDelayed.beacon_ID].innovVar = rngBcn.varInnov; report.innov = rngBcn.innov;
rngBcn.fusionReport[rngBcn.dataDelayed.beacon_ID].rng = rngBcn.dataDelayed.rng; report.innovVar = rngBcn.varInnov;
rngBcn.fusionReport[rngBcn.dataDelayed.beacon_ID].testRatio = rngBcn.testRatio; report.rng = rngBcn.dataDelayed.rng;
report.testRatio = rngBcn.testRatio;
} }
} }
} }