diff --git a/libraries/AP_NavEKF3/AP_NavEKF3_PosVelFusion.cpp b/libraries/AP_NavEKF3/AP_NavEKF3_PosVelFusion.cpp index cc35d43614..2a0c07c815 100644 --- a/libraries/AP_NavEKF3/AP_NavEKF3_PosVelFusion.cpp +++ b/libraries/AP_NavEKF3/AP_NavEKF3_PosVelFusion.cpp @@ -1589,7 +1589,7 @@ void NavEKF3_core::SelectBodyOdomFusion() unitVec.x = prevTnb.a.x; unitVec.y = prevTnb.a.y; unitVec.z = 0.0f; - unitVec.normalized(); + unitVec.normalize(); // multiply by forward speed to get velocity vector measured by wheel encoders Vector3f velNED = unitVec * fwdSpd;