You signed in with another tab or window. Reload to refresh your session.You signed out in another tab or window. Reload to refresh your session.You switched accounts on another tab or window. Reload to refresh your session.Dismiss alert
Copy file name to clipboardExpand all lines: TUNING_GUIDE_ArduCopter.md
+49-1Lines changed: 49 additions & 1 deletion
Display the source diff
Display the rich diff
Original file line number
Diff line number
Diff line change
@@ -918,7 +918,7 @@ When asked *Update file with values from FC?* select `Close` to close the applic
918
918
# 7. Assemble propellers and perform the first flight
919
919
920
920
Assemble the propellers in the vehicle ensuring that they are [balanced in order to reduce vibrations](https://www.youtube.com/watch?v=zTDkCZ698uA).
921
-
High vibrations will cause your vehicle to behave eradicaly endangering people and property.
921
+
High vibrations will cause your vehicle to behave erratically endangering people and property.
922
922
923
923
Now that all mandatory configuration steps are done and the props are on you can perform the first flight.
924
924
@@ -1422,6 +1422,54 @@ Take a look at the `RATE.*out` values in the `.bin` log file, they all should be
1422
1422
1423
1423
Now the standard tuning is complete you can skip to [Section 13 Productive Configuration](#13-productive-configuration)
1424
1424
1425
+
## 9.7 Suppress frame resonance with PID notch filters (advanced/optional)
1426
+
1427
+
Frame resonance occurs when the frequency components in the vibration caused by the motors/propellers excite the frame causing a highly amplified oscillation around the natural frequency of the frame. It can remain visible in the rate-controller logs even after the normal `INS_HNTCH_` / `INS_HNTC2_` harmonic notch filters have removed motor and propeller gyro noise.
1428
+
PID notch filters suppress this kind of resonance by filtering the rate controller's target or error signal so the controller stops exciting the frame at that frequency. Remember, garbage-in, garbage-out. We are removing the garbage (the frame resonance) feeding into the PIDs and further exciting the frame.
1429
+
1430
+
> [!IMPORTANT]
1431
+
> Use PID notch filters only after the standard harmonic notch setup is correct, vibration levels are acceptable, CPU load is healthy, and output oscillation has been ruled out.
1432
+
> These parameters are available in ArduCopter 4.5 and newer.
1433
+
> If they are not visible in your firmware, do not add them manually.
1434
+
1435
+
First, set `FILTn_TYPE` to '1' to enable these filters. Set to `0` to disable the filter. Reboot after changing the filter type if the parameter documentation requires it.
1436
+
1437
+
| Parameter | How to set it |
1438
+
| :--- | :--- |
1439
+
|`FILTn_NOTCH_FREQ`| Set to the measured frame-resonance frequency in Hz. |
1440
+
|`FILTn_NOTCH_Q`| Q-factor which is given by given by the notch centre frequency divided by its bandwidth. Start around `5`. Use a lower value for a wider notch if the resonance moves, or a higher value for a narrower notch if the peak is stable. |
1441
+
|`FILTn_NOTCH_ATT`| Sets attenuation in dB. Start around `10` to `20` dB and increase only if the follow-up log still shows the resonance. Higher Attenuation add phase lag. |
1442
+
1443
+
The PID notch index parameters select one of the global `FILT1_` to `FILT8_` notch definitions.
1444
+
Use `0` to disable a PID notch on an axis.
1445
+
Set value from `1` to `8` to select the matching `FILTn_` filter number so that the characteristics of the notch as defined above will be applied.
1446
+
1447
+
| Purpose | Roll | Pitch | Yaw |
1448
+
| :--- | :--- | :--- | :--- |
1449
+
| Target notch index |`ATC_RAT_RLL_NTF`|`ATC_RAT_PIT_NTF`|`ATC_RAT_YAW_NTF`|
1450
+
| Error notch index |`ATC_RAT_RLL_NEF`|`ATC_RAT_PIT_NEF`|`ATC_RAT_YAW_NEF`|
Do not use `ATC_RAT_*_D_FF` to suppress frame resonance.
1454
+
Keep `D_FF` at `0` while tuning PID notch filters. This term is for improving the "locked-in" feel of the drone so that the drone reacts with minimal latency.
1455
+
After the resonance is under control, `D_FF` can be tuned separately in very small increments to improve aggressive rate tracking, but each change must be validated with logs because it changes actuator demand and pilot feel. Check the `Des.ATT*` and `ATT*` plots in the log. The below images show how the tune can be made tighter during aggressive maneuvers:
For the selected filter number `n`, configure the matching global notch filter:
1464
+
1465
+
1. Finish the normal harmonic notch calibration and run a short test flight. Follow the same procedure as given in [Section 9.6] but with isolated inputs along roll, pitch and yaw axes, *one axis per log file*. Inspect these .bin log files in the PID Review Tool and check for peaks in the spectrum.
1466
+
1. Choose an unused `FILTn_` slot. If the frame resonance is at 46 Hz on roll, for example, configure `FILT1_TYPE = 1`, `FILT1_NOTCH_FREQ = 46`, `FILT1_NOTCH_Q = 5`, and `FILT1_NOTCH_ATT = 25`.
1467
+
1. Apply the filter to the affected axis. For a roll resonance, start with `ATC_RAT_RLL_NEF = 1` and leave `ATC_RAT_RLL_NTF = 0`.
1468
+
1. Use a target notch only if the command target is exciting the resonance. For example, set `ATC_RAT_RLL_NTF = 1` only when the roll target signal needs filtering.
1469
+
1. If the same resonance affects roll and pitch, the same filter can be assigned to both axes. If the axes resonate at different frequencies, use separate `FILTn_` slots.
1470
+
1. Fly a short test flight again and inspect the logs in the Filter Review Tool before making a change if necessary.
1471
+
1. Disable the PID notch by setting the relevant `ATC_RAT_*_NEF` or `ATC_RAT_*_NTF` parameter back to `0` if the follow-up log does not show a clear improvement.
1472
+
1425
1473
# 10. Improve altitude under windy conditions (optional)
0 commit comments