mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 09:28:31 -04:00
AP_PI AP_Var change
using the If statement rather than Max to avoid potential AP_Var issues. I don't know if this is a real prob or not. Just being careful.
This commit is contained in:
parent
d551494b94
commit
6fd7c1dcda
@ -11,8 +11,12 @@ long
|
||||
APM_PI::get_pi(int32_t error, float dt)
|
||||
{
|
||||
_integrator += ((float)error * _ki) * dt;
|
||||
_integrator = min(_integrator, (float)_imax);
|
||||
_integrator = max(_integrator, (float)-_imax);
|
||||
|
||||
if (_integrator < -_imax) {
|
||||
_integrator = -_imax;
|
||||
} else if (_integrator > _imax) {
|
||||
_integrator = _imax;
|
||||
}
|
||||
|
||||
return (float)error * _kp + _integrator;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user