Skip to content

Commit

Permalink
AP_HAL: protect against invalid values when calculating Jain's estimator
Browse files Browse the repository at this point in the history
  • Loading branch information
andyp1per authored and tridge committed Dec 9, 2024
1 parent ec215c3 commit 1d6d112
Showing 1 changed file with 5 additions and 0 deletions.
5 changes: 5 additions & 0 deletions libraries/AP_HAL/DSP.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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) {
Expand Down

0 comments on commit 1d6d112

Please sign in to comment.