Just in case the Min and Max functions are not playing nice with AP_Var

This commit is contained in:
jasonshort 2011-10-26 16:48:50 +00:00
parent 3ea6a4d287
commit 8ec0eec5a2
1 changed files with 6 additions and 2 deletions

View File

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