Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
50 changes: 49 additions & 1 deletion TUNING_GUIDE_ArduCopter.md
Original file line number Diff line number Diff line change
Expand Up @@ -918,7 +918,7 @@ When asked *Update file with values from FC?* select `Close` to close the applic
# 7. Assemble propellers and perform the first flight

Assemble the propellers in the vehicle ensuring that they are [balanced in order to reduce vibrations](https://www.youtube.com/watch?v=zTDkCZ698uA).
High vibrations will cause your vehicle to behave eradicaly endangering people and property.
High vibrations will cause your vehicle to behave erratically endangering people and property.

Now that all mandatory configuration steps are done and the props are on you can perform the first flight.

Expand Down Expand Up @@ -1422,6 +1422,54 @@ Take a look at the `RATE.*out` values in the `.bin` log file, they all should be

Now the standard tuning is complete you can skip to [Section 13 Productive Configuration](#13-productive-configuration)

## 9.7 Suppress frame resonance with PID notch filters (advanced/optional)

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.
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.

> [!IMPORTANT]
> 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.
> These parameters are available in ArduCopter 4.5 and newer.
> If they are not visible in your firmware, do not add them manually.

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.

| Parameter | How to set it |
| :--- | :--- |
| `FILTn_NOTCH_FREQ` | Set to the measured frame-resonance frequency in Hz. |
| `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. |
| `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. |

The PID notch index parameters select one of the global `FILT1_` to `FILT8_` notch definitions.
Use `0` to disable a PID notch on an axis.
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.

| Purpose | Roll | Pitch | Yaw |
| :--- | :--- | :--- | :--- |
| Target notch index | `ATC_RAT_RLL_NTF` | `ATC_RAT_PIT_NTF` | `ATC_RAT_YAW_NTF` |
| Error notch index | `ATC_RAT_RLL_NEF` | `ATC_RAT_PIT_NEF` | `ATC_RAT_YAW_NEF` |
| Derivative feed-forward | `ATC_RAT_RLL_D_FF` | `ATC_RAT_PIT_D_FF` | `ATC_RAT_YAW_D_FF` |

Do not use `ATC_RAT_*_D_FF` to suppress frame resonance.
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.
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:

| | |
| :---: | :---: |
| ![Without D_FF](images/Without_D_FF.png) | ![With D_FF](images/With_D_FF.png) |
| Without D_FF | With D_FF |

ArduPilot actually has 10 notch filters!
For the selected filter number `n`, configure the matching global notch filter:

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.
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`.
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`.
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.
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.
1. Fly a short test flight again and inspect the logs in the Filter Review Tool before making a change if necessary.
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.

# 10. Improve altitude under windy conditions (optional)

## 10.1 [Windspeed Estimation flight(s)](https://ardupilot.org/copter/docs/airspeed-estimation.html)
Expand Down
Binary file added images/With_D_FF.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Binary file added images/Without_D_FF.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.