mirror of https://github.com/ArduPilot/ardupilot
Just in case the Min and Max functions are not playing nice with AP_Var
This commit is contained in:
parent
18e8bb3d6a
commit
d8a0ce6933
|
@ -11,8 +11,12 @@ long
|
||||||
APM_PI::get_pi(int32_t error, float dt)
|
APM_PI::get_pi(int32_t error, float dt)
|
||||||
{
|
{
|
||||||
_integrator += ((float)error * _ki) * 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;
|
return (float)error * _kp + _integrator;
|
||||||
}
|
}
|
||||||
|
|
Loading…
Reference in New Issue