mirror of https://github.com/ArduPilot/ardupilot
Filter: set the harmonic notch filter ref default to zero (disabled)
Modify parameter descriptions for tradheli
This commit is contained in:
parent
6f6bc904a1
commit
3d289d105b
|
@ -31,7 +31,7 @@ const AP_Param::GroupInfo HarmonicNotchFilterParams::var_info[] = {
|
|||
|
||||
// @Param: FREQ
|
||||
// @DisplayName: Harmonic Notch Filter base frequency
|
||||
// @Description: Harmonic Notch Filter base center frequency in Hz
|
||||
// @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
|
||||
// @Units: Hz
|
||||
// @User: Advanced
|
||||
|
@ -55,7 +55,7 @@ const AP_Param::GroupInfo HarmonicNotchFilterParams::var_info[] = {
|
|||
|
||||
// @Param: HMNCS
|
||||
// @DisplayName: Harmonic Notch Filter harmonics
|
||||
// @Description: Bitmask of harmonic frequencies to apply Harmonic Notch Filter to. This option takes effect on the next reboot. A maximum of 3 harmonics can be used at any one time
|
||||
// @Description: Bitmask of harmonic frequencies to apply Harmonic Notch Filter to. This option takes effect on the next reboot. A maximum of 3 harmonics can be used at any one time.
|
||||
// @Bitmask: 0:1st harmonic,1:2nd harmonic,2:3rd harmonic,3:4th hamronic,4:5th harmonic,5:6th harmonic,6:7th harmonic,7:8th harmonic
|
||||
// @User: Advanced
|
||||
// @RebootRequired: True
|
||||
|
@ -63,11 +63,11 @@ const AP_Param::GroupInfo HarmonicNotchFilterParams::var_info[] = {
|
|||
|
||||
// @Param: REF
|
||||
// @DisplayName: Harmonic Notch Filter reference value
|
||||
// @Description: Reference value associated with the specified frequency to facilitate frequency scaling of the Harmonic Notch Filter
|
||||
// @Description: A reference value of zero disables dynamic updates on the Harmonic Notch Filter and a positive value enables dynamic updates on the Harmonic Notch Filter. For multicopters, this parameter is the reference value associated with the specified frequency to facilitate frequency scaling of the Harmonic Notch Filter. For helicopters, this parameter is set to 1 to enable the Harmonic Notch Filter using the RPM sensor set to measure rotor speed. The RPM sensor data is converted to Hz automatically for use in the dynamic notch filter. This reference value may also be used to scale the rpm sensor data, if required. For example, rpm sensor data is required to measure motor RPM. Therefore the reference value can be used to scale the RPM sensor to the rotor RPM.
|
||||
// @User: Advanced
|
||||
// @Range: 0.1 0.9
|
||||
// @Range: 0.0 0.9
|
||||
// @RebootRequired: True
|
||||
AP_GROUPINFO("REF", 6, HarmonicNotchFilterParams, _reference, 0.1f),
|
||||
AP_GROUPINFO("REF", 6, HarmonicNotchFilterParams, _reference, 0),
|
||||
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
|
Loading…
Reference in New Issue