mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-04 04:33:59 -04:00
AC_PID: Protect against NaN and INF
This commit is contained in:
parent
132cdc4916
commit
ae77c18a19
@ -84,6 +84,8 @@ void AC_PID::filt_hz(float hz)
|
||||
// this should be called before any other calls to get_p, get_i or get_d
|
||||
void AC_PID::set_input_filter_all(float input)
|
||||
{
|
||||
// don't pass in inf or NaN
|
||||
if (isfinite(input)){
|
||||
// reset input filter to value received
|
||||
if (_flags._reset_filter) {
|
||||
_flags._reset_filter = false;
|
||||
@ -98,6 +100,7 @@ void AC_PID::set_input_filter_all(float input)
|
||||
_derivative = input_filt_change / _dt;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// set_input_filter_d - set input to PID controller
|
||||
// only input to the D portion of the controller is filtered
|
||||
|
Loading…
Reference in New Issue
Block a user