Filter: added RPM2 harmonic notch type

This commit is contained in:
Andrew Tridgell 2022-04-13 13:51:56 +10:00 committed by Randy Mackay
parent 9741a0b8cd
commit 2cfce1e3e7
2 changed files with 2 additions and 1 deletions

View File

@ -78,7 +78,7 @@ const AP_Param::GroupInfo HarmonicNotchFilterParams::var_info[] = {
// @DisplayName: Harmonic Notch Filter dynamic frequency tracking mode
// @Description: Harmonic Notch Filter dynamic frequency tracking mode. Dynamic updates can be throttle, RPM sensor, ESC telemetry or dynamic FFT based. Throttle-based updates should only be used with multicopters.
// @Range: 0 4
// @Values: 0:Disabled,1:Throttle,2:RPM Sensor,3:ESC Telemetry,4:Dynamic FFT
// @Values: 0:Disabled,1:Throttle,2:RPM Sensor,3:ESC Telemetry,4:Dynamic FFT,5:Second RPM Sensor
// @User: Advanced
AP_GROUPINFO("MODE", 7, HarmonicNotchFilterParams, _tracking_mode, 1),

View File

@ -73,6 +73,7 @@ enum class HarmonicNotchDynamicMode {
UpdateRPM = 2,
UpdateBLHeli = 3,
UpdateGyroFFT = 4,
UpdateRPM2 = 5,
};
/*