Filter: removed parameters from the old notch filter

saves some flash space
This commit is contained in:
Andrew Tridgell 2022-04-13 20:48:18 +10:00 committed by Randy Mackay
parent 6c61ea970d
commit d48e048403
2 changed files with 0 additions and 50 deletions

View File

@ -100,54 +100,7 @@ void NotchFilter<T>::reset()
signal2 = signal1 = T();
}
// table of user settable parameters
const AP_Param::GroupInfo NotchFilterParams::var_info[] = {
// @Param: ENABLE
// @DisplayName: Enable
// @Description: Enable notch filter
// @Values: 0:Disabled,1:Enabled
// @User: Advanced
AP_GROUPINFO_FLAGS("ENABLE", 1, NotchFilterParams, _enable, 0, AP_PARAM_FLAG_ENABLE),
// Slots 2 and 3 are reserved - they were integer versions of FREQ and BW which have since been converted to float
// @Param: ATT
// @DisplayName: Attenuation
// @Description: Notch attenuation in dB
// @Range: 5 30
// @Units: dB
// @User: Advanced
AP_GROUPINFO("ATT", 4, NotchFilterParams, _attenuation_dB, 15),
// @Param: FREQ
// @DisplayName: Frequency
// @Description: Notch center frequency in Hz
// @Range: 10 400
// @Units: Hz
// @User: Advanced
AP_GROUPINFO("FREQ", 5, NotchFilterParams, _center_freq_hz, 80),
// @Param: BW
// @DisplayName: Bandwidth
// @Description: Notch bandwidth in Hz
// @Range: 5 100
// @Units: Hz
// @User: Advanced
AP_GROUPINFO("BW", 6, NotchFilterParams, _bandwidth_hz, 20),
AP_GROUPEND
};
/*
a notch filter with enable and filter parameters - constructor
*/
NotchFilterParams::NotchFilterParams(void)
{
AP_Param::setup_object_defaults(this, var_info);
}
/*
instantiate template classes
*/
template class NotchFilter<float>;

View File

@ -50,9 +50,6 @@ private:
*/
class NotchFilterParams {
public:
NotchFilterParams(void);
static const struct AP_Param::GroupInfo var_info[];
float center_freq_hz(void) const { return _center_freq_hz; }
float bandwidth_hz(void) const { return _bandwidth_hz; }
float attenuation_dB(void) const { return _attenuation_dB; }