This limits the use of the reset to situations where it is a last ditch resort before a lane switch and failsafe.
This will limit false positives for general deployment, but still provide protection from fly-aways at the cost of some increase in reaction time.
Separate prediction and correction steps are required to provide an up to date yaw estimate using IMU prediction before it may be required by SelectMagFusion() whilst still doing the velocity update after GPS data haw been pulled from the buffer by SelectVelPosFusion()
Enables the yaw to be reset in flight to a value estimated from a specialised yaw estimator. This allows faster recovery if taking off with a bad magnetometer and also allows yaw alignment and GPS use to commence in-air when operating without any yaw sensing.
AP_NavEKF2: Add missing accesor functions for default airspeed
this prevents the EKF origin on different cores from being initialised
to different values. A common value is stored in the frontend and used
by a core if it doesn't have an origin
Fix rounding error bug preventing state from updating after initial convergence.
Decouple GPS reference height from published EKf origin height.
Add bitmask parameter to control update and publishing of GPS reference height.
Enables simultaneous use of GPS and optical flow data with automatic fallback to relative position mode if GPS is lost and automatic switch-up to absolute position status if GPS gained/re-gained.
If the GPS receiver was disconnected and no data received, then then the gpsGoodToAlign check did not get a chance to run and becasue it was previously true the EKF would switch back into aiding.
This prevents this by ensuring that gpsGoodToAlign defaults to false when the check is not being performed.
An additional check has also been dded to ensure that there is GPS data to fuse before we declare ready to use GPS.
Switching in and out of aiding modes was being performed in more than one place and was using two variables.
The reversion out of GPS mode due to prolonged loss of GPS was not working.
This consolidates the logic and ensures that PV_AidingMode is only changed by the setAidingMode function.
The filter status logic calculations were being repeated every time the get function was called.
The logic is now updated once per filter update step and a separate get function added