When flying in loiter, I then activated FFT Tune using the AUX switch. But I got the following logs/errors:
FFT: calbrated 3.2KHz/12.6Hz/333.3Hz
FFT: Found peaks at 110.1/215.0/316.4Hz
FFT: Selected 110.1Hz
FFT: Unable to set throttle notch with 110.1Hz/0.1
I have a few questions:
Why did the In-Flight FFT-Based Harmonic Notch Setup keep failing? (I tried it multiple times rebooting the autopilot each time)
I’m getting constant EKF lane changes, the GPS puck (CANBUS) is 10CM away from the Cubepilot, Herelink etc on a GPS stand. Why is this happening?
All components on the latest firmware. (Autopilot, Here4 etc)
The drone in loiter mode randomly will ascend, again not sure why this is happening?
When working with dataflash logs is it possible to extract the logs that would be displayed in the “Messages” tab in mission planner? Or is that data only present in TLOGS? (I do not have the tlogs for these flights)
Thanks for trying this feature! I think you are the first person to try it since I developed it. The FFT selection looks sane, the error means that no notch was configured for throttle-based notching. We are basically trying to avoid overwriting your existing configuration. To get around this enable the notch - INS_HNTCH_ENABLE = 1 - then setup for throttle - INS_HNTCH_MODE = 1 - then disable the notch again - INS_HNTCH_ENABLE = 0. It should then work. Note that we try and setup the defaults to make this work out of the box, but there are some idiosyncrasies that I’m not terrible hapy about.
The tool I was using was ArduPilot Filter Review but I was trying to diagnose why the auto selection wasn’t working.
I have a few questions:
Why would the throttle notch be preferable? What I read in the docs led me to believe it was the inferior choice given the hardware. Could you elaborate please?
I used the Advanced→Anon Log functionality in MP on the dataflash binary. As a result it has been converted from binary→ASCII/Unicode. Is there a tool to convert it back into binary so the tools work? I was a bit confused why the MP tool didn’t offer that as a feature/option.
You are very welcome! (happy to be the Guinea pig) Reading the docs actually led me to do some additional research leading to your Youtube channel!
I have a few questions, would it be possible to address the answers in-line:
I was following the instructions here In-Flight FFT-Based Harmonic Notch Setup — Copter documentation . Am I understanding correctly I should just follow your steps above and use the AUX switch and ignore the manual parameter changes stated on that page?
The FFT above detected 3 noise peaks “Found peaks at 110.1/215.0/316.4Hz” is there a reason why it is only setting up one filter and not three? Should I be looking to notch out all three?
Given that I have no ESC telem/RPM sensor was my choice of using In-Flight FFT correct?
So I understand the feature in general better, my understanding is that the In-Flight FFT is basically to replace the manual analysis to identify the centre freq and bandwidth/width of frequencies to notch out. It does this by setting Throttle based notch filters that we would otherwise have to do by hand is this correct? My confusion arises from the fact that the docs make it sound like In-Flight FFT is a type of dynamic notch that would run constantly whenever you fly, constantly finding/eliminating noise, but after doing my flight and seeing the GCS logs and from your response above it seems like it’s actually an automated process run once that automatically sets Throttle based notch filters (and only Throttle based) for you?
You are very welcome! (happy to be the Guinea pig) Reading the docs actually led me to do some additional research leading to your Youtube channel!
I have a few questions, would it be possible to address the answers in-line:
I was following the instructions here In-Flight FFT-Based Harmonic Notch Setup — Copter documentation . Am I understanding correctly I should just follow your steps above and use the AUX switch and ignore the manual parameter changes stated on that page?
The FFT above detected 3 noise peaks “Found peaks at 110.1/215.0/316.4Hz” is there a reason why it is only setting up one filter and not three? Should I be looking to notch out all three?
If you set the options to “multi-source” it will track all three
Given that I have no ESC telem/RPM sensor was my choice of using In-Flight FFT correct?
Yes that or throttle based notch (see below)
So I understand the feature in general better, my understanding is that the In-Flight FFT is basically to replace the manual analysis to identify the centre freq and bandwidth/width of frequencies to notch out. It does this by setting Throttle based notch filters that we would otherwise have to do by hand is this correct? My confusion arises from the fact that the docs make it sound like In-Flight FFT is a type of dynamic notch that would run constantly whenever you fly, constantly finding/eliminating noise, but after doing my flight and seeing the GCS logs and from your response above it seems like it’s actually an automated process run once that automatically sets Throttle based notch filters (and only Throttle based) for you?
The feature you are using is to set the throttle based notch from the in-flight FFT, so you would be using the throttle based notch rather than the the FFT based notch
1. I was following the instructions here In-Flight FFT-Based Harmonic Notch Setup — Copter documentation . Am I understanding correctly I should just follow your steps above and use the AUX switch and ignore the manual parameter changes stated on that page?
1.1 Should I be disabling the FFT Engine after doing this process to save CPU cycles? As the engine was used to find the centre freq and isn’t going be used after the notches are set or does your feature do this?
2.1 So I’d be looking to set Bit 0 on INS_HNTCH_HMNCS?
3.1 I’ll set bit 1 of INS_HNTCH_OPTS. So I do not need to enable the second notch filter as setting this option will use the first peak as a base and then apply a calculated multiple to roughly hit the other 3 peaks? I can use one filter INS_HNTCH_ENABLE and do not need to enable INS_HNTC2_ENABLE?
Also, looking at my graph above would you recommend I enable “multi-source”?
5.1 Understood, thought bit confused here if INS_HNTCH_MODE = 4. In-Flight FFT based which is the feature described above to set throttle based notch filter from In-Flight FFT (analysis) what mode would be the FFT Based Notch?
I’m also assuming that an FFT Based Notch would be one that has no explicit frequencies set and the autopilot just responds to what it detects real-time? (though I’m not seeing any docs that describe that)
Also, do you have any insight on the following:
6. I’m getting constant EKF lane changes, the GPS puck (CANBUS) is 10CM away from the Cubepilot, Herelink etc on a GPS stand. Why is this happening?
All components on the latest firmware. (Autopilot, Here4 etc)
7. The drone in loiter mode randomly will ascend, again not sure why this is happening?
The anon log above still works for analysis using the “Review Log” functionality in MP but not on the web tools. All the params are present in the log also.
1.1 - does not matter much, its not that CPU intensive.
2.1 - yes, but sorry if you are running the throttle notch ultimately you probably want 2 or 3 harmonics.
3.1. - just set INS_HNTCH_HMNCS to 7 that will give you 3 notches. Multi-source works in 4.6.x now with the throttle notch so yes.
5.1 - mode 4 is FFT actively driving the notch, mode 1 is throttle
Triple notch is narrower overall than the regular notch but wider at the base. This means its great for suppressing heavier noise that is not super clean - but it does require the notch frequency be set accurately, so just beware - if you are using the throttle notch the fit may not be quite so good.
The first two parameters should have been set. What did you end up with?
I’ve done some flights today. The notch filter setting was successful, but the flights afterward performed quite poorly—worse than when the notch filter was disabled. I’ve attached the DATAFLASH BIN here:
It also set INS_HNTCH_HMNC=13 automatically. (It was originally set to 7/1,2,3 harmonics before disabling the notch and running the FFT)
After running the FFT when trying to fly I got a tonne of oscillations.
Here is the BIN straight after the FFT Tune (rebooted autopilot):
I wasn’t sure what option to take here so I disabled multi-source and set INS_HNTCH_OPTS = 0 and the oscillations went away. But I’m still receiving a tonne of EKF lane switch messages and the drone would randomly ascend and descend in loiter. (Though I suspect I’ve got a potential baro issue too as I’m getting some fluctuation on Position/vert EKF) I also got some GPS issues later on despite the Here4 seeing 16 satellites.
This is often a problem with the FFT analysis - it misses the first peak due to lack of energy. Try dividing the FREQ by 2, changing the HMNCS to 7 and dividing the bandwidth by 8 (if you are using notch-per-motor you typically need a lower bandwidth).