From 1d6d11283e13a6fe98fd893f797e2d03acca8cbd Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Sat, 7 Dec 2024 16:20:40 +0000 Subject: [PATCH] AP_HAL: protect against invalid values when calculating Jain's estimator --- libraries/AP_HAL/DSP.cpp | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/libraries/AP_HAL/DSP.cpp b/libraries/AP_HAL/DSP.cpp index 10b33e38d0..932149d972 100644 --- a/libraries/AP_HAL/DSP.cpp +++ b/libraries/AP_HAL/DSP.cpp @@ -286,6 +286,11 @@ float DSP::calculate_jains_estimator(const FFTWindowState* fft, const float* rea float y1 = real_fft[k_max-1]; float y2 = real_fft[k_max]; float y3 = real_fft[k_max+1]; + + if (is_zero(y2) || is_zero(y1)) { + return 0.0f; + } + float d = 0.0f; if (y1 > y3) {