AP_NavEKF2: Group GPS innovation tests when compiling error score

This commit is contained in:
priseborough 2016-11-24 08:55:55 +11:00 committed by Randy Mackay
parent e9ea06bd10
commit 7d48054e6f

View File

@ -45,9 +45,11 @@ float NavEKF2_core::errorScore() const
{
float score = 0.0f;
if (tiltAlignComplete && yawAlignComplete) {
score = MAX(score, velTestRatio);
score = MAX(score, posTestRatio);
// Check GPS fusion performance
score = MAX(score, 0.5f * (velTestRatio + posTestRatio));
// Check altimeter fusion performance
score = MAX(score, hgtTestRatio);
// Check attitude corrections
const float tiltErrThreshold = 0.05f;
score = MAX(score, tiltErrFilt / tiltErrThreshold);
}