mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_Empty: add harmonics to DSP
add DSP vector mean function add ObjectBuffer signature
This commit is contained in:
parent
33c1523905
commit
13e40a3002
|
@ -21,12 +21,12 @@
|
||||||
class Empty::DSP : public AP_HAL::DSP {
|
class Empty::DSP : public AP_HAL::DSP {
|
||||||
#if HAL_WITH_DSP
|
#if HAL_WITH_DSP
|
||||||
public:
|
public:
|
||||||
virtual FFTWindowState* fft_init(uint16_t window_size, uint16_t sample_rate) override { return nullptr; }
|
virtual FFTWindowState* fft_init(uint16_t window_size, uint16_t sample_rate, uint8_t harmonics) override { return nullptr; }
|
||||||
virtual void fft_start(FFTWindowState* state, const float* samples, uint16_t buffer_index, uint16_t buffer_size) override {}
|
virtual void fft_start(FFTWindowState* state, FloatBuffer& samples, uint16_t advance) override {}
|
||||||
virtual uint16_t fft_analyse(FFTWindowState* state, uint16_t start_bin, uint16_t end_bin, uint8_t harmonics, float noise_att_cutoff) override { return 0; }
|
virtual uint16_t fft_analyse(FFTWindowState* state, uint16_t start_bin, uint16_t end_bin, float noise_att_cutoff) override { return 0; }
|
||||||
protected:
|
protected:
|
||||||
virtual void vector_max_float(const float* vin, uint16_t len, float* maxValue, uint16_t* maxIndex) const override {}
|
virtual void vector_max_float(const float* vin, uint16_t len, float* maxValue, uint16_t* maxIndex) const override {}
|
||||||
virtual void vector_scale_float(const float* vin, float scale, float* vout, uint16_t len) const override {}
|
virtual void vector_scale_float(const float* vin, float scale, float* vout, uint16_t len) const override {}
|
||||||
|
virtual float vector_mean_float(const float* vin, uint16_t len) const override { return 0.0f; };
|
||||||
#endif // HAL_WITH_DSP
|
#endif // HAL_WITH_DSP
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue