mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 13:38:38 -04:00
Filter: add mutators for notch filter parameters
This commit is contained in:
parent
02e5a7f463
commit
39d928aa49
@ -80,7 +80,7 @@ const AP_Param::GroupInfo HarmonicNotchFilterParams::var_info[] = {
|
||||
// @Range: 0 4
|
||||
// @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),
|
||||
AP_GROUPINFO("MODE", 7, HarmonicNotchFilterParams, _tracking_mode, int8_t(HarmonicNotchDynamicMode::UpdateThrottle)),
|
||||
|
||||
// @Param: OPTS
|
||||
// @DisplayName: Harmonic Notch Filter options
|
||||
@ -287,6 +287,19 @@ HarmonicNotchFilterParams::HarmonicNotchFilterParams(void)
|
||||
AP_Param::setup_object_defaults(this, var_info);
|
||||
}
|
||||
|
||||
/*
|
||||
save changed parameters
|
||||
*/
|
||||
void HarmonicNotchFilterParams::save_params()
|
||||
{
|
||||
_enable.save();
|
||||
_center_freq_hz.save();
|
||||
_bandwidth_hz.save();
|
||||
_attenuation_dB.save();
|
||||
_harmonics.save();
|
||||
_reference.save();
|
||||
}
|
||||
|
||||
/*
|
||||
instantiate template classes
|
||||
*/
|
||||
|
@ -90,18 +90,24 @@ public:
|
||||
HarmonicNotchFilterParams(void);
|
||||
// set the fundamental center frequency of the harmonic notch
|
||||
void set_center_freq_hz(float center_freq) { _center_freq_hz.set(center_freq); }
|
||||
// set the bandwidth of the harmonic notch
|
||||
void set_bandwidth_hz(float bandwidth_hz) { _bandwidth_hz.set(bandwidth_hz); }
|
||||
// harmonics enabled on the harmonic notch
|
||||
uint8_t harmonics(void) const { return _harmonics; }
|
||||
// has the user set the harmonics value
|
||||
void set_default_harmonics(uint8_t hmncs) { _harmonics.set_default(hmncs); }
|
||||
// reference value of the harmonic notch
|
||||
float reference(void) const { return _reference; }
|
||||
void set_reference(float ref) { _reference = ref; }
|
||||
// notch options
|
||||
bool hasOption(Options option) const { return _options & uint16_t(option); }
|
||||
// notch dynamic tracking mode
|
||||
HarmonicNotchDynamicMode tracking_mode(void) const { return HarmonicNotchDynamicMode(_tracking_mode.get()); }
|
||||
static const struct AP_Param::GroupInfo var_info[];
|
||||
|
||||
// save parameters
|
||||
void save_params();
|
||||
|
||||
private:
|
||||
// configured notch harmonics
|
||||
AP_Int8 _harmonics;
|
||||
|
@ -54,6 +54,7 @@ public:
|
||||
float bandwidth_hz(void) const { return _bandwidth_hz; }
|
||||
float attenuation_dB(void) const { return _attenuation_dB; }
|
||||
uint8_t enabled(void) const { return _enable; }
|
||||
void enable() { _enable.set(true); }
|
||||
|
||||
protected:
|
||||
AP_Int8 _enable;
|
||||
|
Loading…
Reference in New Issue
Block a user