AP_NavEKF2: Fix calculation of predicted LOS rate in terrain estimator

This commit is contained in:
priseborough 2017-06-20 14:21:54 +10:00 committed by Francisco Ferreira
parent a83457ab07
commit c69c5440a0
1 changed files with 2 additions and 2 deletions

View File

@ -184,10 +184,10 @@ void NavEKF2_core::EstimateTerrainOffset()
// divide velocity by range, subtract body rates and apply scale factor to
// get predicted sensed angular optical rates relative to X and Y sensor axes
losPred = relVelSensor.length()/flowRngPred;
losPred = norm(relVelSensor.x, relVelSensor.y)/flowRngPred;
// calculate innovations
auxFlowObsInnov = losPred - sqrtf(sq(ofDataDelayed.flowRadXYcomp[0]) + sq(ofDataDelayed.flowRadXYcomp[1]));
auxFlowObsInnov = losPred - norm(ofDataDelayed.flowRadXYcomp.x, ofDataDelayed.flowRadXYcomp.y);
// calculate observation jacobian
float t3 = sq(q0);