mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 09:28:31 -04:00
AP_NavEKF3: Update documentation
This commit is contained in:
parent
6c7820dd8d
commit
64a3d8fe4e
@ -408,7 +408,7 @@ void NavEKF3_core::setAidingMode()
|
||||
void NavEKF3_core::checkAttitudeAlignmentStatus()
|
||||
{
|
||||
// Check for tilt convergence - used during initial alignment
|
||||
// Once the tilt variances have reduced to equivalent of 3deg uncertainty, re-set the yaw and magnetic field states
|
||||
// Once the tilt variances have reduced, re-set the yaw and magnetic field states
|
||||
// and declare the tilt alignment complete
|
||||
if (!tiltAlignComplete) {
|
||||
if (tiltErrorVariance < sq(radians(5.0f))) {
|
||||
|
@ -1043,7 +1043,9 @@ void NavEKF3_core::CovariancePrediction(Vector3f *rotVarVecPtr)
|
||||
P[16][16] = sq(frontend->_magNoise);
|
||||
P[17][17] = P[16][16];
|
||||
P[18][18] = P[16][16];
|
||||
FuseDeclination(0.34f);
|
||||
// Fusing the declinaton angle as an observaton with a 20 deg uncertainty helps
|
||||
// to stabilise the earth field.
|
||||
FuseDeclination(radians(20.0f));
|
||||
}
|
||||
|
||||
if (!inhibitMagStates) {
|
||||
|
Loading…
Reference in New Issue
Block a user