mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 08:38:36 -04:00
Filter: ensure the derivative filter never returns an invalid number
This commit is contained in:
parent
2e77691ca1
commit
81cd4b6c13
@ -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…
Reference in New Issue
Block a user