mirror of https://github.com/ArduPilot/ardupilot
AP_HAL: ensure the DSP tracked peaks do not overflow the buffer
This commit is contained in:
parent
a7ccfd6f19
commit
703020be12
|
@ -358,6 +358,8 @@ uint16_t DSP::fft_stop_average(FFTWindowState* fft, uint16_t start_bin, uint16_t
|
|||
scratch_space, peaks, MAX_TRACKED_PEAKS, 0.0f, -1.0f, smoothwidth, 2);
|
||||
hal.util->free_type(scratch_space, sizeof(float) * fft->_num_stored_freqs, DSP_MEM_REGION);
|
||||
|
||||
numpeaks = MIN(numpeaks, uint16_t(MAX_TRACKED_PEAKS));
|
||||
|
||||
// now try and find the lowest harmonic
|
||||
for (uint16_t i = 0; i < numpeaks; i++) {
|
||||
const uint16_t bin = peaks[i] + start_bin;
|
||||
|
|
Loading…
Reference in New Issue