AP_NavEKF3: correctly use wheel odometry speed for pitched rovers

This commit is contained in:
priseborough 2017-10-31 07:18:30 +11:00 committed by Randy Mackay
parent 68828511cd
commit c96bc54254
1 changed files with 1 additions and 1 deletions

View File

@ -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;