Err: 24-1 and 24-0 while flying at high speed with RTK GPS

I have been testing with RTK GPS for a while and these are the parameters I tuned to make optimal use from the RTK GPS:

  • EK2_VELNE_M_NSE = 0.01
  • EK2_POSNE_M_NSE = 0.05
  • EK2_GPS_DELAY = 60 msec (RTK GPS is working at 10Hz)

Now I’m testing the RTK GPS at high speeds (25 m/s) and I’m getting a lot of 24-1 and 24-0 errors:
demo_26.zip (3.2 MB)

Is it possible that these errors are related to the SP-ratio from the Kalmanfilter (EKF2)? On the wiki I can find that the Kalmanfilter thinks the GPS measurements are inconsistent if the SP-ratio is bigger than 1. It’s also weird that this ratio is bigger than 1 because I’m using RTK gps during the whole flight.

I think I will also have a problem while switching back from RTK GPS to normal GPS (if correction data is lost during flight for example). The barometer is very inaccurate while flying at high speeds (around 5-10m drift). When the RTK gps switches to standard GPS both the GPS altitude measurement and barometer measurement are inaccurate, while flying at high speed, and there will be a discontinuity in the altitude estimation from the EKF. Anyone an idea how to solve this problem? Maybe I can use a lidar but this is only sufficient untill 30 - 40m.

It does look like NKF4 SP is noisy (not sure why) and driving the lane switch. The NKF9 SP is bad at times, so it’s good that the PI (index) switches back to 0 when it can.

That’s pretty fast. Curious, how high is your thrust/weight ratio?

I don’t understand why the NKF SP is bad while I’m flying with RTK GPS (accuracy of 2cm). My thrust/weight ratio is around 2,7:1.

Ardupilot does not handle GPS switching well at the moment. The ability to handle GPS switching will be improved by this PR https://github.com/ArduPilot/ardupilot/pull/5642.

Your velocity and position measurement noise parameters are too low and don’t take into account errors due to platform dynamics, antenna offset, antenna phase centre changes with signal direction, etc. My experience from reviewing user RTK GPS logs is that values of 10cm and 10 cm/second are more realistic minimums and looking at the quality of your data they may need to be larger. Your logs are showing sensor inconsistencies that make operating which such small GPS error parameters unrealistic. At the moment the GPS data is failing the innovation consistency checks several times in flight, requiring a full reset back to GPS. You can force the EKF to follow the GPS when innovations are large by increasing the value of EK2_POS_I_GATE, EK2_HGT_I_GATE and EK2_VEL_I_GATE.

If you want to get the full benefit from RTK you also need to have good quality IMU and magnetometer data as these become the major source of error and can drag the inertial solution away from the GPS during manoeuvres.

That means having an IMU that is properly isolated from vibration, has a stable temperature environment and has been calibrated recently. It also means having a magnetometer that is mounted away from sources of interference, is accurately aligned and calibrated.

You also need to set the position of the IMU and GPS accurately in the parameters - see INS_POS1_X, GPS_POS_X, etc