mirror of https://github.com/ArduPilot/ardupilot
Filter: added RPM2 harmonic notch type
This commit is contained in:
parent
2a9899629b
commit
7150dde40a
|
@ -78,7 +78,7 @@ const AP_Param::GroupInfo HarmonicNotchFilterParams::var_info[] = {
|
||||||
// @DisplayName: Harmonic Notch Filter dynamic frequency tracking 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 updates should only be used with multicopters.
|
||||||
// @Range: 0 4
|
// @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
|
// @User: Advanced
|
||||||
AP_GROUPINFO("MODE", 7, HarmonicNotchFilterParams, _tracking_mode, 1),
|
AP_GROUPINFO("MODE", 7, HarmonicNotchFilterParams, _tracking_mode, 1),
|
||||||
|
|
||||||
|
|
|
@ -73,6 +73,7 @@ enum class HarmonicNotchDynamicMode {
|
||||||
UpdateRPM = 2,
|
UpdateRPM = 2,
|
||||||
UpdateBLHeli = 3,
|
UpdateBLHeli = 3,
|
||||||
UpdateGyroFFT = 4,
|
UpdateGyroFFT = 4,
|
||||||
|
UpdateRPM2 = 5,
|
||||||
};
|
};
|
||||||
|
|
||||||
/*
|
/*
|
||||||
|
|
Loading…
Reference in New Issue