5
0
mirror of https://github.com/ArduPilot/ardupilot synced 2025-01-05 15:38:29 -04:00

AC_PID: update pid_info when integrator set

This commit is contained in:
Randy Mackay 2019-10-16 17:10:28 +09:00
parent adf4d8fd47
commit 0052dcc8f8
2 changed files with 8 additions and 1 deletions
libraries/AC_PID

View File

@ -327,4 +327,11 @@ void AC_PID::set_integrator(float target, float measurement, float i)
void AC_PID::set_integrator(float error, float i)
{
_integrator = constrain_float(i - error * _kp, -_kimax, _kimax);
_pid_info.I = _integrator;
}
void AC_PID::set_integrator(float i)
{
_integrator = constrain_float(i, -_kimax, _kimax);
_pid_info.I = _integrator;
}

View File

@ -101,7 +101,7 @@ public:
// integrator setting functions
void set_integrator(float target, float measurement, float i);
void set_integrator(float error, float i);
void set_integrator(float i) { _integrator = constrain_float(i, -_kimax, _kimax); }
void set_integrator(float i);
const AP_Logger::PID_Info& get_pid_info(void) const { return _pid_info; }