AP_NavEKF3: Re-tune tilt alignment check

New tilt error variance estimate is more accurate and larger than before.
This commit is contained in:
Paul Riseborough 2020-09-17 08:23:02 +10:00 committed by Andrew Tridgell
parent 16ae75a681
commit 90e928c32a
1 changed files with 1 additions and 1 deletions

View File

@ -411,7 +411,7 @@ void NavEKF3_core::checkAttitudeAlignmentStatus()
// Once the tilt variances have reduced to equivalent of 3deg uncertainty, re-set the yaw and magnetic field states
// and declare the tilt alignment complete
if (!tiltAlignComplete) {
if (tiltErrorVariance < sq(radians(3.0f))) {
if (tiltErrorVariance < sq(radians(5.0f))) {
tiltAlignComplete = true;
gcs().send_text(MAV_SEVERITY_INFO, "EKF3 IMU%u tilt alignment complete",(unsigned)imu_index);
}