Filter: add harmonic notch dynamic tracking mode

update harmonic notch REF docs
This commit is contained in:
Andy Piper 2019-10-10 18:36:09 +01:00 committed by Randy Mackay
parent a8913d0df5
commit 22111f59e8
2 changed files with 14 additions and 2 deletions

View File

@ -63,12 +63,20 @@ const AP_Param::GroupInfo HarmonicNotchFilterParams::var_info[] = {
// @Param: REF
// @DisplayName: Harmonic Notch Filter reference value
// @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.
// @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 throttle-based scaling, this parameter is the reference value associated with the specified frequency to facilitate frequency scaling of the Harmonic Notch Filter. For RPM and ESC telemetry based tracking, this parameter is set to 1 to enable the Harmonic Notch Filter using the RPM sensor or ESC telemetry set to measure rotor speed. The sensor data is converted to Hz automatically for use in the Harmonic Notch Filter. This reference value may also be used to scale the sensor data, if required. For example, rpm sensor data is required to measure heli motor RPM. Therefore the reference value can be used to scale the RPM sensor to the rotor RPM.
// @User: Advanced
// @Range: 0.0 0.9
// @Range: 0.0 1.0
// @RebootRequired: True
AP_GROUPINFO("REF", 6, HarmonicNotchFilterParams, _reference, 0),
// @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 or ESC telemetry based. Throttle-based updates should only be used with multicopters.
// @Range: 0 3
// @Values: 0:Disabled,1:Throttle,2:RPM Sensor,3:ESC Telemetry
// @User: Advanced
AP_GROUPINFO("MODE", 7, HarmonicNotchFilterParams, _tracking_mode, 1),
AP_GROUPEND
};

View File

@ -68,6 +68,8 @@ public:
uint8_t harmonics(void) const { return _harmonics; }
// reference value of the harmonic notch
float reference(void) const { return _reference; }
// notch dynamic tracking mode
uint8_t tracking_mode(void) const { return _tracking_mode; }
static const struct AP_Param::GroupInfo var_info[];
private:
@ -75,6 +77,8 @@ private:
AP_Int8 _harmonics;
// notch reference value
AP_Float _reference;
// notch dynamic tracking mode
AP_Int8 _tracking_mode;
};
typedef HarmonicNotchFilter<Vector3f> HarmonicNotchFilterVector3f;