Filter: correct harmonic notch docs and provide better defaults.

This commit is contained in:
Andy Piper 2020-11-21 20:36:11 +00:00 committed by Randy Mackay
parent 6557cb83a4
commit c0e033cb14
1 changed files with 8 additions and 8 deletions

View File

@ -31,27 +31,27 @@ const AP_Param::GroupInfo HarmonicNotchFilterParams::var_info[] = {
// @Param: FREQ
// @DisplayName: Harmonic Notch Filter base frequency
// @Description: Harmonic Notch Filter base center frequency in Hz. For helicopters using RPM sensor to dynamically set the notch frequency, use this parameter to provide a lower limit to the dynamic notch filter. Recommend setting it to half the operating rotor speed in Hz.
// @Range: 10 400
// @Description: Harmonic Notch Filter base center frequency in Hz. This should be set at most half the backend gyro rate (which is typically 1Khz). For helicopters using RPM sensor to dynamically set the notch frequency, use this parameter to provide a lower limit to the dynamic notch filter. Recommend setting it to half the operating rotor speed in Hz.
// @Range: 10 495
// @Units: Hz
// @User: Advanced
AP_GROUPINFO("FREQ", 2, HarmonicNotchFilterParams, _center_freq_hz, 80),
// @Param: BW
// @DisplayName: Harmonic Notch Filter bandwidth
// @Description: Harmonic Notch Filter bandwidth in Hz
// @Range: 5 100
// @Description: Harmonic Notch Filter bandwidth in Hz. This is typically set to half the base frequency. The ratio of base frequency to bandwidth determines the notch quality factor and is fixed across harmonics.
// @Range: 5 250
// @Units: Hz
// @User: Advanced
AP_GROUPINFO("BW", 3, HarmonicNotchFilterParams, _bandwidth_hz, 20),
AP_GROUPINFO("BW", 3, HarmonicNotchFilterParams, _bandwidth_hz, 40),
// @Param: ATT
// @DisplayName: Harmonic Notch Filter attenuation
// @Description: Harmonic Notch Filter attenuation in dB
// @Range: 5 30
// @Description: Harmonic Notch Filter attenuation in dB. Values greater than 40dB will typically produce a hard notch rather than a modest attenuation of motor noise.
// @Range: 5 50
// @Units: dB
// @User: Advanced
AP_GROUPINFO("ATT", 4, HarmonicNotchFilterParams, _attenuation_dB, 15),
AP_GROUPINFO("ATT", 4, HarmonicNotchFilterParams, _attenuation_dB, 40),
// @Param: HMNCS
// @DisplayName: Harmonic Notch Filter harmonics