There’s some good documentation on the EKF log fields here and here.
I’m going to answer your questions out of order.
4 - The error happened in flight because Stabilize flight mode does not require the EKF, since everything is controlled by the pilot except for stabilization. Any flight mode which relies on the flight controller to control position such as Loiter or PosHold requires the EKF to be initialized. This is why I suggested trying to arm the copter in PosHold, as it will refuse to arm if it’s not ready. As for the annoyingly cryptic error messages, they are defined here. The error message FLIGHT_MODE-16 can be read as “Flight mode change failed due to error code 16,” which is defined as EKFCHECK. You can find EKFCHECK error 2 as “bad variance” and error code 0 as “variance cleared.”
2 - Innovations are contained in the NKF3 field. An innovation is how far off a sensor reading is from what the EKF expects it to be based on its current state estimate. They are recorded in the relevant units for that measurements (e.g., m/s for velocity). The EKF uses a coordinate system of North, East, Down for position and velocity. Here, you can see that the velocity innovations don’t exist for the first half of the flight, which I guess means that the EKF had not settled on a velocity solution yet.
I also show the position innovations. You can see that they are large at the beginning of the flight, but suddenly jump to near 0 once the EKF initializes. The large innovations are caused by the EKF’s inertial measurements not agreeing with the GPS position, I guess because the EKF hadn’t started its inertial estimation yet. The innovations stay near 0 afterwards, which indicates that your EKF may be fine once it’s working.
1 - The consistency checks are contained in the NKF4 field. They are ratios of innovation/threshold, where the threshold is some value that can be configured with parameters (defaults are usually fine). If the ratio ever exceeds 1, the EKF rejects the measurement. If the ratio stays above 1 for a while, the EKF will instead throw out its estimate and re-initialize, and switch to the secondary EKF, if you have it running (you do). This EKF switching means something is wrong, but fortunately this was not the case for you.
Here are the consistency checks. Again, velocity does not appear until after the EKF initializes. They stay in a healthy range of generally <0.10, the spike at the end is probably the copter touching down.
3 - The gyro biases are in NKF1.Gx. The only reason I mentioned this is because it was the only thing I could find that may explain why the EKF took longer than usual to start.
Here, you can see the EKF learning the gyro bias over time (I inverted the Z bias to make the graph more readable). It initializes after they settle. It might be worth checking your other flight logs to see what the biases usually are for a good flight.
So I think your copter is okay, you just had one instance where EKF took longer than usual and caused something you didn’t expect. My disclaimer is that I am not an expert, so I definitely could have missed or misunderstood something.