EKF lane switch and EKF yaw reset leading to instabilities

Hi everyone!

I have a large agricultural quadcopter, capable of carrying a payload of about 30 kg (EFT Z30 frame). It is equipped with a CUAV V6X flight controller, two NEO3 GPS modules, and a downward-facing NRA24 sensor.

I’ve configured the copter and have been flying it for a while. However, occasionally, even in very stable conditions, I experience strange instabilities mid-flight. When reviewing the logs, these issues are always preceded by EKF_YAW_RESET and EKF lane switch messages.

Here is a log of a manual figure-eight flight I conducted yesterday for a magfit. Towards the end of the flight, the same instabilities occurred. I’ve also attached some images to illustrate the issue.

So far, I haven’t been able to identify the cause and would greatly appreciate any ideas on how to resolve it.


EKF_YAW_RESET is informational, indicating compass heading and GPS path had a mismatch and they’ve been aligned. It doesnt cause a crash but could point to something causing the misalignment.
Similar for the lane switch, Arducopter is doing what it should and trying options to maintain stability - but what caused the first EKF lane to be marked as bad? This is not your typical “motor or ESC failed” scenario.
I’ll see what I can find.

1 Like

Looking at innovations and things, I think magnetic variances are the source of the main problem.

Set these to improve the compass calibration and disable the onboard compass:

COMPASS_USE3,0
COMPASS_OFS_X,-67.53898
COMPASS_OFS_Y,29.743444
COMPASS_OFS_Z,39.603195
COMPASS_DIA_X,1
COMPASS_DIA_Y,1
COMPASS_DIA_Z,1
COMPASS_ODI_X,0
COMPASS_ODI_Y,0
COMPASS_ODI_Z,0
COMPASS_MOT_X,0
COMPASS_MOT_Y,0
COMPASS_MOT_Z,0
COMPASS_SCALE,1.1959532
COMPASS_ORIENT,0
COMPASS_OFS2_X,208.11592
COMPASS_OFS2_Y,-63.676373
COMPASS_OFS2_Z,306.06128
COMPASS_DIA2_X,1.1198436
COMPASS_DIA2_Y,1.0249825
COMPASS_DIA2_Z,0.85517395
COMPASS_ODI2_X,0.0061804336
COMPASS_ODI2_Y,0.1527947
COMPASS_ODI2_Z,0.106676556
COMPASS_MOT2_X,0
COMPASS_MOT2_Y,0
COMPASS_MOT2_Z,0
COMPASS_SCALE2,0.97793794
COMPASS_ORIENT2,6
COMPASS_MOTCT,0

Set these to fix up some logging:

INS_LOG_BAT_MASK,1
INS_LOG_BAT_OPT,4
LOG_BITMASK,180222

Consider enabling the Fence too - it will prevent take off in any mode until Home can be set.
Set a suitable altitude and radius.

I’d like to see the log from an ordinary flight after those changes, just do some yaw, circles, ascent, descent and general flying around in AltHold and Loiter.
We’ll be able to further improve the compass calibration, plus I suspect you Harmonic Notch Filter settings are excess to requirements and possibly affecting stability a little bit.

1 Like

Hello Shawn,

First of all, thank you very much for your guidance!

I conducted two flights after making the changes you suggested, and I didn’t encounter any EKF errors this time, so I believe we’re on the right track.

However, I agree with your observation regarding the harmonic notch or something else potentially being off. Even without the errors, I still noticed some strange oscillations.
I don’t exactly know if the notch may have something to do with this but the issue only occurred in Loiter mode—everything seemed fine in Stabilize and AltHold.

I should also mention that it was quite a windy day, and the oscillations appeared to happen primarily on the roll axis, triggered by gusts of wind. As a precaution, I’m planning to retune the roll and pitch axes as well.

I’ve attached some screenshots of the oscillations and the log files are in this folder.


Attitude control is OK but a bit nervous, try ATC_ANG_LIM_TC,2 just to smooth it out a little.
It could probably benefit from an Autotune after we’ve nailed down the filter and whatever else we can find with those oscillations.

Unfortunately the log is so big I cant get it loaded up in any of the filter tools.
I think you should have these settings based on the ESC RPM I see in the log:

INS_HNTCH_FREQ,20
INS_HNTCH_BW,5
INS_HNTCH_ATT,40
INS_HNTCH_HMNCS,3
INS_HNTCH_OPTS,2

Note that the hover frequency is not 20Hz, but the notch filter will increase that 20Hz to match the ESC RPM, and suitably scale the bandwidth too. It needs to start at the minimum.

Just do a short flight next, with some variety so we can confirm the filter settings (and the extra compass settings).
Once it is correct you can disable this extra logging:

INS_LOG_BAT_MASK,0
INS_LOG_BAT_OPT,0

Compass calibration can be further improved:

COMPASS_OFS_X,-82.439674
COMPASS_OFS_Y,28.6108
COMPASS_OFS_Z,41.395184
COMPASS_DIA_X,1.0278705
COMPASS_DIA_Y,0.99461997
COMPASS_DIA_Z,0.9775095
COMPASS_ODI_X,-0.002101466
COMPASS_ODI_Y,-0.0019167982
COMPASS_ODI_Z,-0.014957749
COMPASS_MOT_X,0.26035506
COMPASS_MOT_Y,-0.008036682
COMPASS_MOT_Z,-0.12361763
COMPASS_SCALE,1.1780409
COMPASS_ORIENT,0
COMPASS_OFS2_X,194.35925
COMPASS_OFS2_Y,-60.665848
COMPASS_OFS2_Z,294.58102
COMPASS_DIA2_X,1.1327372
COMPASS_DIA2_Y,1.0539213
COMPASS_DIA2_Z,0.8133415
COMPASS_ODI2_X,0.00088302634
COMPASS_ODI2_Y,0.12925637
COMPASS_ODI2_Z,0.09255216
COMPASS_MOT2_X,0.21520035
COMPASS_MOT2_Y,-0.02241816
COMPASS_MOT2_Z,-0.023231255
COMPASS_SCALE2,0.9521188
COMPASS_ORIENT2,6
COMPASS_MOTCT,2
1 Like

I changed the parameters you suggested and performed two quick flights. The first one (log 00000147) was ok, with some small oscillations but nothing concerning. One thing I noticed was that it manifested mainly when I was conducting a maneuver combining more than one axis (diagonal flight or roll+yaw).

The second flight (log 00000148) on the other hand was scary. Just after takeoff (about 2m) the drone decided to do a hard bank and started a very dangerous oscillation, I then changed to stabilize mode and was able to save it. Not sure about the reason for this one, hope you can help with it as well. The graphs are for this flight.

Today we had much less wind than yesterday, but with an occasional gust.

Thanks again for your help, hope the new files can help us narrow down the problems, this time I was able to open it on the filter review tool.


I’ve looked at both logs, but we will mostly assume we are discussing the second log where there was some loss of control at the start.

This will help the notch filter to affect the attitude control LESS than it has been:
INS_HNTCH_OPTS,0
and the filter still works effectively. You can probably set these too for smaller logs now:

INS_LOG_BAT_MASK,0
INS_LOG_BAT_OPT,0

I’ve got a few more ideas, but in the interests of just changing the minimum number of parameters at one time, I would suggest this D term change next:
ATC_RAT_RLL_D,0.009
and decrease this from 300 to 200
TKOFF_RPM_MIN,200
since it almost looks like the props are nearly producing enough thrust at 300RPM to at least unsettle the copter, so it might as well be fully stabilised and try to take off as the throttle rises.
This may have even contributed to the instability at take off.

GPS positions are far apart at arming too, and after some flight they come back close to each other. I see you’ve already set their X,Y,Z positions, that’s great.
See if this improves the second GPS HDOP
GPS_GNSS_MODE2,5
Big copters are particularly prone to a wandering GPS position at takeoff, since it’s easy to catch the landing gear on grass and tip over, or fly right at the pilot or nearest vehicle.
If the performance difference between the two GPS units is suspect, you can opt to rely on the primary unit, and only switch over if there is an issue. The downside is this can lead to a step-change in position if there is ever a switch-over.
GPS_AUTO_SWITCH,4
I tend to avoid using the “Use Best” setting since that could potentially be a different GPS unit for each flight. Some of this may take testing to see what works best for your GPS units and region.

Do another short test flight when you get a chance.

2 Likes

Thank you! I flew today again and the copter feels much more robust.

The only parameter I didn’t change was the GPS_AUTO_SWITCH, since in the beginning I used the “best” setting and saw the step change in position lead to high oscillations. For the moment I think I will keep with the “blend” option, but if I see any problems I’ll try the GPS_AUTO_SWITCH, 4.

First flight seemed very good (log 00000149) and second flight (log 00000150) as well.

One issue I noticed during some maneuvers—pushing the stick fully forward or sideways and then suddenly letting go—was a slight oscillation during braking, as seen in the video (second flight).
I wonder if this might be related to how AP handles angle changes with a downward-facing rangefinder. The rangefinder is located at the nose of the craft, and whenever I input a high-pitch command, the copter struggles to maintain altitude, leading to some concerning throttle-down moments.


Do you think it’s time to perform another autotune, or should we tweak more parameters first?

Just a quick note, on MP, the ‘set bitmask’ option for INS_HNTCH_OPTS doesn’t match the documentation. I’ll add a couple of screenshots to illustrate the problem. Not sure if here is the right place to discuss it but I prefer to let you know.
My version is the 1.3.81 (build 1.3.8741.25556) running on linux with mono.

While I look into the rest, the 'Set Bitmask" dialog does do the correct thing.
Being a bitmask, bit0 = 1 decimal, bit1 = 2 decimal, bit2 = 4 decimal, and so on…
So when you select more than one option the result is the sum of their decimal values.