mirror of https://github.com/ArduPilot/ardupilot
AP_NavEKF3: correctly use wheel odometry speed for pitched rovers
This commit is contained in:
parent
68828511cd
commit
c96bc54254
|
@ -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;
|
||||
|
|
Loading…
Reference in New Issue