mirror of https://github.com/ArduPilot/ardupilot
Filter: use CLASS_NO_COPY
This commit is contained in:
parent
6c0c6a1f48
commit
cd1f5ca494
|
@ -56,6 +56,8 @@ public:
|
|||
T apply(const T &sample, float cutoff_freq, float dt);
|
||||
T apply(const T &sample);
|
||||
|
||||
CLASS_NO_COPY(DigitalLPF);
|
||||
|
||||
void compute_alpha(float sample_freq, float cutoff_freq);
|
||||
|
||||
// get latest filtered value from filter (equal to the value returned by latest call to apply method)
|
||||
|
@ -79,6 +81,8 @@ public:
|
|||
LowPassFilter(float cutoff_freq);
|
||||
LowPassFilter(float sample_freq, float cutoff_freq);
|
||||
|
||||
CLASS_NO_COPY(LowPassFilter);
|
||||
|
||||
// change parameters
|
||||
void set_cutoff_frequency(float cutoff_freq);
|
||||
void set_cutoff_frequency(float sample_freq, float cutoff_freq);
|
||||
|
|
|
@ -34,7 +34,9 @@ public:
|
|||
float b1;
|
||||
float b2;
|
||||
};
|
||||
|
||||
|
||||
CLASS_NO_COPY(DigitalBiquadFilter);
|
||||
|
||||
DigitalBiquadFilter();
|
||||
|
||||
T apply(const T &sample, const struct biquad_params ¶ms);
|
||||
|
@ -63,6 +65,8 @@ public:
|
|||
void reset(void);
|
||||
void reset(const T &value);
|
||||
|
||||
CLASS_NO_COPY(LowPassFilter2p);
|
||||
|
||||
protected:
|
||||
struct DigitalBiquadFilter<T>::biquad_params _params;
|
||||
|
||||
|
|
|
@ -17,6 +17,8 @@ class SlewLimiter {
|
|||
public:
|
||||
SlewLimiter(const float &slew_rate_max, const float &slew_rate_tau);
|
||||
|
||||
CLASS_NO_COPY(SlewLimiter);
|
||||
|
||||
/*
|
||||
apply filter to sample, returning multiplier between 0 and 1 to keep
|
||||
output within slew rate
|
||||
|
|
Loading…
Reference in New Issue