Filter: ensure the derivative filter never returns an invalid number

This commit is contained in:
Andrew Tridgell 2012-08-18 13:53:22 +10:00
parent 2e77691ca1
commit 81cd4b6c13

View File

@ -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;