AP_HAL_SITL: remove redundant harmonics from DSP

This commit is contained in:
Andy Piper 2021-11-22 20:26:35 +00:00 committed by Andrew Tridgell
parent 2fab99d647
commit fa91e74fde
2 changed files with 6 additions and 6 deletions

View File

@ -35,9 +35,9 @@ extern const AP_HAL::HAL& hal;
// important as frequency resolution. Referred to as [Heinz] throughout the code.
// initialize the FFT state machine
AP_HAL::DSP::FFTWindowState* DSP::fft_init(uint16_t window_size, uint16_t sample_rate, uint8_t harmonics)
AP_HAL::DSP::FFTWindowState* DSP::fft_init(uint16_t window_size, uint16_t sample_rate)
{
DSP::FFTWindowStateSITL* fft = new DSP::FFTWindowStateSITL(window_size, sample_rate, harmonics);
DSP::FFTWindowStateSITL* fft = new DSP::FFTWindowStateSITL(window_size, sample_rate);
if (fft == nullptr || fft->_hanning_window == nullptr || fft->_rfft_data == nullptr || fft->_freq_bins == nullptr || fft->_derivative_freq_bins == nullptr) {
delete fft;
return nullptr;
@ -61,8 +61,8 @@ uint16_t DSP::fft_analyse(AP_HAL::DSP::FFTWindowState* state, uint16_t start_bin
}
// create an instance of the FFT state machine
DSP::FFTWindowStateSITL::FFTWindowStateSITL(uint16_t window_size, uint16_t sample_rate, uint8_t harmonics)
: AP_HAL::DSP::FFTWindowState::FFTWindowState(window_size, sample_rate, harmonics)
DSP::FFTWindowStateSITL::FFTWindowStateSITL(uint16_t window_size, uint16_t sample_rate)
: AP_HAL::DSP::FFTWindowState::FFTWindowState(window_size, sample_rate)
{
if (_freq_bins == nullptr || _hanning_window == nullptr || _rfft_data == nullptr || _derivative_freq_bins == nullptr) {
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "Failed to allocate window for DSP");

View File

@ -27,7 +27,7 @@ typedef std::complex<float> complexf;
class HALSITL::DSP : public AP_HAL::DSP {
public:
// initialise an FFT instance
virtual FFTWindowState* fft_init(uint16_t window_size, uint16_t sample_rate, uint8_t harmonics) override;
virtual FFTWindowState* fft_init(uint16_t window_size, uint16_t sample_rate) override;
// start an FFT analysis with an ObjectBuffer
virtual void fft_start(FFTWindowState* state, FloatBuffer& samples, uint16_t advance) override;
// perform remaining steps of an FFT analysis
@ -38,7 +38,7 @@ public:
friend class HALSITL::DSP;
public:
FFTWindowStateSITL(uint16_t window_size, uint16_t sample_rate, uint8_t harmonics);
FFTWindowStateSITL(uint16_t window_size, uint16_t sample_rate);
virtual ~FFTWindowStateSITL();
private: