From a129b9c50ecc43eccd8d05abd78baba04fcb5775 Mon Sep 17 00:00:00 2001 From: Henry Wurzburg Date: Sun, 7 Apr 2024 11:46:39 -0500 Subject: [PATCH] Filter:correct vehicles which can use throttle based notches --- libraries/Filter/HarmonicNotchFilter.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/Filter/HarmonicNotchFilter.cpp b/libraries/Filter/HarmonicNotchFilter.cpp index ed12108c2cd438..a710de35daa7c3 100644 --- a/libraries/Filter/HarmonicNotchFilter.cpp +++ b/libraries/Filter/HarmonicNotchFilter.cpp @@ -116,7 +116,7 @@ const AP_Param::GroupInfo HarmonicNotchFilterParams::var_info[] = { // @Param: MODE // @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. + // @Description: Harmonic Notch Filter dynamic frequency tracking mode. Dynamic updates can be throttle, RPM sensor, ESC telemetry or dynamic FFT based. Throttle-based harmonic notch cannot be used on fixed wing only planes. It can for Copters, QuaadPlane(while in VTOL modes), and Rovers. // @Range: 0 5 // @Values: 0:Fixed,1:Throttle,2:RPM Sensor,3:ESC Telemetry,4:Dynamic FFT,5:Second RPM Sensor // @User: Advanced