diff --git a/libraries/AP_NavEKF3/AP_NavEKF3_RngBcnFusion.cpp b/libraries/AP_NavEKF3/AP_NavEKF3_RngBcnFusion.cpp index c8df1a5c07..9708b60f16 100644 --- a/libraries/AP_NavEKF3/AP_NavEKF3_RngBcnFusion.cpp +++ b/libraries/AP_NavEKF3/AP_NavEKF3_RngBcnFusion.cpp @@ -268,11 +268,12 @@ void NavEKF3_core::FuseRngBcn() // Update the fusion report if (rngBcn.fusionReport && rngBcn.dataDelayed.beacon_ID < dal.beacon()->count()) { - rngBcn.fusionReport[rngBcn.dataDelayed.beacon_ID].beaconPosNED = rngBcn.dataDelayed.beacon_posNED; - rngBcn.fusionReport[rngBcn.dataDelayed.beacon_ID].innov = rngBcn.innov; - rngBcn.fusionReport[rngBcn.dataDelayed.beacon_ID].innovVar = rngBcn.varInnov; - rngBcn.fusionReport[rngBcn.dataDelayed.beacon_ID].rng = rngBcn.dataDelayed.rng; - rngBcn.fusionReport[rngBcn.dataDelayed.beacon_ID].testRatio = rngBcn.testRatio; + auto &report = rngBcn.fusionReport[rngBcn.dataDelayed.beacon_ID]; + report.beaconPosNED = rngBcn.dataDelayed.beacon_posNED; + report.innov = rngBcn.innov; + report.innovVar = rngBcn.varInnov; + report.rng = rngBcn.dataDelayed.rng; + report.testRatio = rngBcn.testRatio; } } } @@ -506,11 +507,12 @@ void NavEKF3_core::FuseRngBcnStatic() } // Update the fusion report if (rngBcn.fusionReport && rngBcn.dataDelayed.beacon_ID < dal.beacon()->count()) { - rngBcn.fusionReport[rngBcn.dataDelayed.beacon_ID].beaconPosNED = rngBcn.dataDelayed.beacon_posNED; - rngBcn.fusionReport[rngBcn.dataDelayed.beacon_ID].innov = rngBcn.innov; - rngBcn.fusionReport[rngBcn.dataDelayed.beacon_ID].innovVar = rngBcn.varInnov; - rngBcn.fusionReport[rngBcn.dataDelayed.beacon_ID].rng = rngBcn.dataDelayed.rng; - rngBcn.fusionReport[rngBcn.dataDelayed.beacon_ID].testRatio = rngBcn.testRatio; + auto &report = rngBcn.fusionReport[rngBcn.dataDelayed.beacon_ID]; + report.beaconPosNED = rngBcn.dataDelayed.beacon_posNED; + report.innov = rngBcn.innov; + report.innovVar = rngBcn.varInnov; + report.rng = rngBcn.dataDelayed.rng; + report.testRatio = rngBcn.testRatio; } } }