Browse Source

Filter: ensure the derivative filter never returns an invalid number

master
Andrew Tridgell 13 years ago
parent
commit
81cd4b6c13
  1. 5
      libraries/Filter/DerivativeFilter.cpp

5
libraries/Filter/DerivativeFilter.cpp

@ -92,6 +92,11 @@ float DerivativeFilter<T,FILTER_SIZE>::slope(void) @@ -92,6 +92,11 @@ float DerivativeFilter<T,FILTER_SIZE>::slope(void)
break;
}
// cope with numerical errors
if (isnan(result) || isinf(result)) {
result = 0;
}
_new_data = false;
_last_slope = result;

Loading…
Cancel
Save