mirror of https://github.com/ArduPilot/ardupilot
Filter: Allow all filter frequencies to be 16bit.
This commit is contained in:
parent
36878e9b3c
commit
52e4676564
|
@ -75,7 +75,7 @@ const AP_Param::GroupInfo NotchFilterParams::var_info[] = {
|
|||
// @Param: FREQ
|
||||
// @DisplayName: Frequency
|
||||
// @Description: Notch center frequency in Hz
|
||||
// @Range: 10 200
|
||||
// @Range: 10 400
|
||||
// @Units: Hz
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("FREQ", 2, NotchFilterParams, _center_freq_hz, 80),
|
||||
|
@ -83,7 +83,7 @@ const AP_Param::GroupInfo NotchFilterParams::var_info[] = {
|
|||
// @Param: BW
|
||||
// @DisplayName: Bandwidth
|
||||
// @Description: Notch bandwidth in Hz
|
||||
// @Range: 5 50
|
||||
// @Range: 5 100
|
||||
// @Units: Hz
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("BW", 3, NotchFilterParams, _bandwidth_hz, 20),
|
||||
|
|
|
@ -49,14 +49,14 @@ public:
|
|||
static const struct AP_Param::GroupInfo var_info[];
|
||||
|
||||
uint16_t center_freq_hz(void) const { return _center_freq_hz; }
|
||||
uint8_t bandwidth_hz(void) const { return _bandwidth_hz; }
|
||||
uint16_t bandwidth_hz(void) const { return _bandwidth_hz; }
|
||||
float attenuation_dB(void) const { return _attenuation_dB; }
|
||||
uint8_t enabled(void) const { return _enable; }
|
||||
|
||||
private:
|
||||
AP_Int8 _enable;
|
||||
AP_Int16 _center_freq_hz;
|
||||
AP_Int8 _bandwidth_hz;
|
||||
AP_Int16 _bandwidth_hz;
|
||||
AP_Float _attenuation_dB;
|
||||
};
|
||||
|
||||
|
|
Loading…
Reference in New Issue