mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 15:53:56 -04:00
Filter: allow freq_min_ratio to be set on harmonic notch filter
allow harmonics to be set
This commit is contained in:
parent
bd05b548a7
commit
500f59d839
@ -101,6 +101,8 @@ public:
|
|||||||
void set_bandwidth_hz(float bandwidth_hz) { _bandwidth_hz.set(bandwidth_hz); }
|
void set_bandwidth_hz(float bandwidth_hz) { _bandwidth_hz.set(bandwidth_hz); }
|
||||||
// harmonics enabled on the harmonic notch
|
// harmonics enabled on the harmonic notch
|
||||||
uint8_t harmonics(void) const { return _harmonics; }
|
uint8_t harmonics(void) const { return _harmonics; }
|
||||||
|
// set the harmonics value
|
||||||
|
void set_harmonics(uint8_t hmncs) { _harmonics.set(hmncs); }
|
||||||
// has the user set the harmonics value
|
// has the user set the harmonics value
|
||||||
void set_default_harmonics(uint8_t hmncs) { _harmonics.set_default(hmncs); }
|
void set_default_harmonics(uint8_t hmncs) { _harmonics.set_default(hmncs); }
|
||||||
// reference value of the harmonic notch
|
// reference value of the harmonic notch
|
||||||
@ -116,6 +118,7 @@ public:
|
|||||||
float freq_min_ratio(void) const {
|
float freq_min_ratio(void) const {
|
||||||
return _freq_min_ratio;
|
return _freq_min_ratio;
|
||||||
}
|
}
|
||||||
|
void set_freq_min_ratio(float ratio) { _freq_min_ratio.set(ratio); }
|
||||||
|
|
||||||
// save parameters
|
// save parameters
|
||||||
void save_params();
|
void save_params();
|
||||||
|
Loading…
Reference in New Issue
Block a user