Estimator failure?

https://logs.px4.io/plot_app?log=fd8981a9-cb94-44d6-be07-687b53cfb37a

7:47.940 β€” impossible change in X position at 36 m per 0.1 s, though velocity never goes above 15 m/s.

7:43 β€” jump of yaw by 140 deg and at 7:48 back, though there were no sharp maneuveres really.

What happens and how to avoid it?

Look at the logged messages at the bottom of the Flight Review page:

Thank you. Do you mean the reason is a compass failure?

I think no: in case of bad calibration estimator limits compass influence and doesn’t change direction faster than about 10-15 deg/s (if gyro shows no motion). And in the log at 7:43 we see yaw changed by 140 deg per less than 0.1 s.

It looks like the compass failure is a result of estimator failure, not a reason.

The vehicle takes off and the EKF velocity states immediately diverge. This is unlikely due to a bad yaw angle because at the time of divergence, GPS horizontal velocity magnitude is low. The root cause of this is unknown and will be hard to determine given the lack or pre-arm log data.

It is recommended that the ratio of measured horizontal velocity to innovation be checked before declaring nav failure as due to bad yaw. The following figure shows these quantities for this log:

The EKF interprets this as a loss of navigation due to possible yaw failure which results a reset to the EKF-GSF yaw estimate at 4.7 seconds. The second fault was that the EKF-GSF yaw estimators weights had collapsed to zero which resulted in the published variance and yaw angle going to zero.

The root cause of this second failure is not known, but inspection of the log and code have revealed the following which will be investigated further:

a) The EKF-GSF was slow to be started and some horizontal velocity had already built up when it started. It is recommended that it be started just prior to the vehicle becoming airborne.

b) Inspection of the code shows that other than /0 protection, there is no additional protection for the case where weights have collapsed to zero which can happen if the gaussianDensity function returns a very small value and the normalisation of the weights fails. It is recommended that failure of the normalisation calculation trigger a reset of the EKF’s and GSF. Also additional prevention of weighting collapse can be added.

1 Like

A branch with the suggested fixes has been created - https://github.com/PX4/ecl/tree/pr-gsfBugFix

The root cause of the initial loss of inertial navigation failure after takeoff appears to have been excessive vibration levels that were high enough to cause clipping:

This would also make the EKF-GSF yaw estimate invalid regardless of the zero GSF weight condition that was generated.

Edit: The large innovations on all yaw hypothesis EKF’s caused by the clipping would make an underflow condition in the calculation of the Gaussian Density function more likely. The proposed changes https://github.com/PX4/ecl/tree/pr-gsfBugFix add protection against that.

Paul, thank you for detailed analysis and explanation!

The vehicle takes off and the EKF velocity states immediately diverge.

Can this happen due to bad airspeed sensor?

The EKF-GSF was slow to be started and some horizontal velocity had already built up when it started. It is recommended that it be started just prior to the vehicle becoming airborne.

Why was it slow to start and what can we do to make it work properly?

Airspeed sensing errors cannot cause this.
The EKF-GSF start is currently triggered by the landed status going false. Using a more sophisticated check external to the EKF or another status flag if available is what is required. Could be triggered if armed and vertical velocity exceeds a threshold.

Further analysis of the log reported here: https://github.com/PX4/ecl/pull/914#issuecomment-704154050 indicates that the delay between landed status, GPS movement and EKF-GSF start can be explained with no further action required at this time.

The fix for the EKF-GSF weight collapse issue has been merged. https://github.com/PX4/ecl/pull/914

Thank you https://discuss.px4.io/u/le-chat for sharing your log. Make sure you fix the vibration before flying again. No SW changes can make it safe to fly with that much vibration.