Tuning the Harmonic Notch

Yes, so if you want the notch to go all the way down to 70Hz say you set INS_HNTCH_FREQ to 70 and INS_HNTCH_REF to 0.2554156 * SQUAREROOT( 70 / 90 )

Andy any idea why CTUN.N would not be logged? This is on the Firmware that you gave me earlier.

It’s moved to FTN.DnF. This is a build of master.

1 Like

Hi Andy @andyp1per Is the Double notch in Master now? I have been flying with your PR but for updating purposes can I just use Latest -dev now?

Yes, both FFT and Double-Notch are in master

Can you remind me how the double notch is configured? I see to set INS_HNTCH_OPTS = 1. But then does that open up more parameters to set the frequency, or offset between the notches, or does it detect it automatically?

And, is ESC RPM still preferred if it’s available, or might the FFT be better for detecting the noise?

It’s configured like you have there. The regular notch parameters are used to configure two notches with a higher Q that should overall have the same Q and attenuation of the single notch, but with a wider spread. So for example if your notch freq is 100, you will actually have two notches one at 97Hz and one at 103Hz whose combined bandwidth should reflect the bandwidth you have set for the notch.

But, beware - I don’t think the double-notch buys anything on smaller copters because their peak is so spikey and for F4’s its quite CPU-heavy because you are doubling the number of notches (so 6 if you use defaults). In tuning my 4" the double-notch made the tune worse and could not be used with 2k backend rate because of CPU load. On larger copters with much more smushy noise, you should get much more benefit.

ESC RPM will always be better for small copters - there’s very little latency or CPU load and the noise is very much a function of RPM (not quite true at the top end but true enough). For large copters its a different story - very complex noise patterns, but FFT currently struggles there also. I have just created https://github.com/ArduPilot/ardupilot/pull/14470 which might help with this.

1 Like

Copter appear smoother after tuning but keep wondering why is the y axis spike much bigger than the others

David Ardis

Andy, not sure how to configure parameters for the triple.

INS_HNTCH_OPTS = 2

PR here for those who are interested: https://github.com/ArduPilot/ardupilot/pull/14470

@andyp1per

I have been flying a spray drone and want to tune the harmonic notch and notches. Regular flights I will start with a 30 lb. payload and will disperse it over roughly 10 minutes.

Do you recommend tuning the harmonic notch with no, half or full payload?

Thank you.

When tuning the notch it really doesn’t matter as long as the thrust linearization is set up correctly. What matters is whether you then try and tighten autotune by running it again with the notch enabled - in that case you should follow autotune procedure which I think requires zero payload IIRC.

Ok, thank you.

I am not sure I am completely understanding. When you say the thrust linearization are you meaning mot_thst_expo? I have that setup as .75 with using 30 inch props.

Yes. The default setting for the harmonic notch is to use throttle as a proxy for motor RPM to calculate where to put the notch, but that requires that your throttle is linear with rpm.

Ok, thank you. I will try this today or tomorrow and post results for expert analysis.

@andyp1per Could you please take a look and give me your analysis?

I flew my drone today and tuned the harmonic notch with no payload. I think it went well, but I am not quite sure what to put for the notch frequency scaling as I am not sure what my min_freq is?

Looking at my dynamic flight it looks like my min would be about 20 so my new ins_hntch_ref would be:
20/90 = .222222
Square root of .22222 is .471404
Take .47140 x .1954755 (mot_thst_hover) = .09214715

New ins_hntch_ref would be .09214715?

All three flights in order of pre-filter, post-filter to dynamic flight.



Pre-Filter


Post-Filter

Dynamic Flight

Thoughts? Thank you so much!!!

Your hover frequency is 64 (that’s what you’ve set and looks right), so it would be 20/64 - but I wouldn’t recommend you go that low, maybe 40Hz, so 40/64. You can alos raise HNTCH_ATT to 40 - that will squash the peak more effectively.

@andyp1per I am tuning a new 6 inch Copter with a Pixracer and I see somethings I don’t understand well.

One thing is that as already said also by others the FFT analysis done by MP differ from FFT analysis done by mavfft_isb.py. I post some images, in all images above is pre-filter and below is post-filter.

Mission Planner FFT analysis:

mavfft_isb.py analysis (lin scale):

mavfft_isb.py analysis (log scale):

From the plot of FTN1 PkAvg and BwAvg it seems that the right analysis is from mavfft_isb.py. From this same plot I see zone in which BwAvg becomes greater then PkAvg, this seems strange to me, but maybe the cause could be that even without filter the peak is not so high and pronounced.

I attach the two log:
https://drive.google.com/file/d/1uzsB1Paai5x37MF5jarLx1Q2kBeeV8MG/view?usp=sharing
https://drive.google.com/file/d/1fd-WS9G-n3GjHAVh1PMasnWVfPWGiMsR/view?usp=sharing

Ok. Thank you @andyp1per!

I will try a dynamic flight today with the new settings and a full payload.

So mavfft_isb does the same analysis as the in-flight FFT as I wrote both :wink: Mission planner does something different - it simply averages the FFT passes. It doesn’t do any windowing, doesn’t convert to power spectral density and doesn’t do a NEBW calculation, so I would say its results are more approximate, although not inaccurate.

The bandwidth will increase when you yaw, because the motors will be running at different frequencies spreading the width of the peak

1 Like