Browse Source

AP_NavEKF2: Delay use of magnetic field states until off-ground

Magnetic interference whilst on the ground can adversely affect filter states. This patch ensures that the simpler and more robust magnetic heading observation method is used until the vehicle has cleared the ground.
mission-4.1.18
Paul Riseborough 9 years ago committed by Andrew Tridgell
parent
commit
71c399674a
  1. 4
      libraries/AP_NavEKF2/AP_NavEKF2_Control.cpp

4
libraries/AP_NavEKF2/AP_NavEKF2_Control.cpp

@ -66,8 +66,8 @@ void NavEKF2_core::setWindMagStateLearningMode() @@ -66,8 +66,8 @@ void NavEKF2_core::setWindMagStateLearningMode()
// Determine if learning of magnetic field states has been requested by the user
bool magCalRequested = ((frontend._magCal == 0) && !onGround) || ((frontend._magCal == 1) && manoeuvring) || (frontend._magCal == 3);
// Deny mag calibration request if we aren't using the compass, are in the pre-arm constant position mode or it has been inhibited by the user
bool magCalDenied = !use_compass() || (PV_AidingMode == AID_NONE) || (frontend._magCal == 2);
// Deny mag calibration request if we aren't using the compass, have not perfomred the first in-air calibration are on the ground or it has been inhibited by the user
bool magCalDenied = !use_compass() || !firstMagYawInit || (frontend._magCal == 2) || onGround;
// Inhibit the magnetic field calibration if not requested or denied
inhibitMagStates = (!magCalRequested || magCalDenied);

Loading…
Cancel
Save