mirror of https://github.com/ArduPilot/ardupilot
AP_NAvEKF3: Use a const reference
This commit is contained in:
parent
64a3d8fe4e
commit
43386a8eea
|
@ -1085,7 +1085,7 @@ void NavEKF3_core::CovariancePrediction(Vector3f *rotVarVecPtr)
|
|||
// vector defining the variance of the angular alignment uncertainty. Convert he varaince vector
|
||||
// to a matrix and rotate into body frame. Use the exisiting gyro error propagation mechanism to
|
||||
// propagate the body frame angular uncertainty variances.
|
||||
Vector3f rotVarVec = *rotVarVecPtr;
|
||||
const Vector3f &rotVarVec = *rotVarVecPtr;
|
||||
Matrix3f R_ef = Matrix3f (
|
||||
rotVarVec.x, 0.0f, 0.0f,
|
||||
0.0f, rotVarVec.y, 0.0f,
|
||||
|
|
Loading…
Reference in New Issue