AP_HAL: protect against invalid values when calculating Jain's estimator

This commit is contained in:
Andy Piper 2024-12-07 16:20:40 +00:00 committed by Andrew Tridgell
parent ec215c3a29
commit 1d6d11283e
1 changed files with 5 additions and 0 deletions

View File

@ -286,6 +286,11 @@ float DSP::calculate_jains_estimator(const FFTWindowState* fft, const float* rea
float y1 = real_fft[k_max-1]; float y1 = real_fft[k_max-1];
float y2 = real_fft[k_max]; float y2 = real_fft[k_max];
float y3 = real_fft[k_max+1]; float y3 = real_fft[k_max+1];
if (is_zero(y2) || is_zero(y1)) {
return 0.0f;
}
float d = 0.0f; float d = 0.0f;
if (y1 > y3) { if (y1 > y3) {