mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 14:08:45 -04:00
parent
0c8f0377ca
commit
6c09b268d8
@ -35,6 +35,10 @@ template <class T>
|
||||
void DigitalBiquadFilter<T>::compute_params(float sample_freq, float cutoff_freq, biquad_params &ret) {
|
||||
ret.cutoff_freq = cutoff_freq;
|
||||
ret.sample_freq = sample_freq;
|
||||
if (!is_positive(ret.cutoff_freq)) {
|
||||
// zero cutoff means pass-thru
|
||||
return;
|
||||
}
|
||||
|
||||
float fr = sample_freq/cutoff_freq;
|
||||
float ohm = tanf(M_PI/fr);
|
||||
@ -83,6 +87,10 @@ float LowPassFilter2p<T>::get_sample_freq(void) const {
|
||||
|
||||
template <class T>
|
||||
T LowPassFilter2p<T>::apply(const T &sample) {
|
||||
if (!is_positive(_params.cutoff_freq)) {
|
||||
// zero cutoff means pass-thru
|
||||
return sample;
|
||||
}
|
||||
return _filter.apply(sample, _params);
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user