AC_PID: dont change pid_info.I in set/reset methods

This commit is contained in:
Iampete1 2023-01-13 15:16:32 +00:00 committed by Andrew Tridgell
parent 84d49d5a88
commit 2371d83620
4 changed files with 0 additions and 9 deletions

View File

@ -93,6 +93,5 @@ void AC_HELI_PID::update_leaky_i(float leak_rate)
_integrator -= (float)(_integrator + _leak_min) * leak_rate;
}
_pid_info.I = _integrator;
}
}

View File

@ -268,7 +268,6 @@ float AC_PID::get_ff()
void AC_PID::reset_I()
{
_integrator = 0.0;
_pid_info.I = 0.0;
}
void AC_PID::load_gains()
@ -336,13 +335,11 @@ void AC_PID::set_integrator(float target, float measurement, float integrator)
void AC_PID::set_integrator(float error, float integrator)
{
_integrator = constrain_float(integrator - error * _kp, -_kimax, _kimax);
_pid_info.I = _integrator;
}
void AC_PID::set_integrator(float integrator)
{
_integrator = constrain_float(integrator, -_kimax, _kimax);
_pid_info.I = _integrator;
}
void AC_PID::relax_integrator(float integrator, float dt, float time_constant)
@ -351,5 +348,4 @@ void AC_PID::relax_integrator(float integrator, float dt, float time_constant)
if (is_positive(dt)) {
_integrator = _integrator + (integrator - _integrator) * (dt / (dt + time_constant));
}
_pid_info.I = _integrator;
}

View File

@ -168,8 +168,6 @@ Vector2f AC_PID_2D::get_ff()
void AC_PID_2D::reset_I()
{
_integrator.zero();
_pid_info_x.I = 0.0;
_pid_info_y.I = 0.0;
}
// save_gains - save gains to eeprom

View File

@ -141,7 +141,6 @@ void AC_PID_Basic::update_i(float dt, bool limit_neg, bool limit_pos)
void AC_PID_Basic::reset_I()
{
_integrator = 0.0;
_pid_info.I = 0.0;
}
// save_gains - save gains to eeprom
@ -181,5 +180,4 @@ void AC_PID_Basic::set_integrator(float error, float i)
void AC_PID_Basic::set_integrator(float i)
{
_integrator = constrain_float(i, -_kimax, _kimax);
_pid_info.I = _integrator;
}