mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 14:48:28 -04:00
AP_NavEKF2: Group GPS innovation tests when compiling error score
This commit is contained in:
parent
e9ea06bd10
commit
7d48054e6f
@ -45,9 +45,11 @@ float NavEKF2_core::errorScore() const
|
|||||||
{
|
{
|
||||||
float score = 0.0f;
|
float score = 0.0f;
|
||||||
if (tiltAlignComplete && yawAlignComplete) {
|
if (tiltAlignComplete && yawAlignComplete) {
|
||||||
score = MAX(score, velTestRatio);
|
// Check GPS fusion performance
|
||||||
score = MAX(score, posTestRatio);
|
score = MAX(score, 0.5f * (velTestRatio + posTestRatio));
|
||||||
|
// Check altimeter fusion performance
|
||||||
score = MAX(score, hgtTestRatio);
|
score = MAX(score, hgtTestRatio);
|
||||||
|
// Check attitude corrections
|
||||||
const float tiltErrThreshold = 0.05f;
|
const float tiltErrThreshold = 0.05f;
|
||||||
score = MAX(score, tiltErrFilt / tiltErrThreshold);
|
score = MAX(score, tiltErrFilt / tiltErrThreshold);
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user