mirror of https://github.com/ArduPilot/ardupilot
AC_PID: update pid_info with integrator reset for logging purposes
This commit is contained in:
parent
13b03f79db
commit
9d8bf5004e
|
@ -272,6 +272,7 @@ float AC_PID::get_ff()
|
|||
void AC_PID::reset_I()
|
||||
{
|
||||
_integrator = 0.0;
|
||||
_pid_info.I = 0.0;
|
||||
}
|
||||
|
||||
void AC_PID::load_gains()
|
||||
|
|
|
@ -166,6 +166,13 @@ Vector2f AC_PID_2D::get_ff()
|
|||
return _target * _kff;
|
||||
}
|
||||
|
||||
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
|
||||
void AC_PID_2D::save_gains()
|
||||
{
|
||||
|
|
|
@ -41,7 +41,7 @@ public:
|
|||
const Vector2f& get_error() const { return _error; }
|
||||
|
||||
// reset the integrator
|
||||
void reset_I() { _integrator.zero(); };
|
||||
void reset_I();
|
||||
|
||||
// reset_filter - input and D term filter will be reset to the next value provided to set_input()
|
||||
void reset_filter() { _reset_filter = true; }
|
||||
|
|
|
@ -139,6 +139,12 @@ void AC_PID_Basic::update_i(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
|
||||
void AC_PID_Basic::save_gains()
|
||||
{
|
||||
|
@ -176,4 +182,5 @@ 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;
|
||||
}
|
||||
|
|
|
@ -37,7 +37,7 @@ public:
|
|||
float get_error() const WARN_IF_UNUSED { return _error; }
|
||||
|
||||
// reset the integrator
|
||||
void reset_I() { _integrator = 0.0f; }
|
||||
void reset_I();
|
||||
|
||||
// input and D term filter will be reset to the next value provided to set_input()
|
||||
void reset_filter() { _reset_filter = true; }
|
||||
|
|
Loading…
Reference in New Issue