AC_PID: support PD boosting

This commit is contained in:
Andy Piper 2022-05-28 16:58:25 +01:00 committed by Andrew Tridgell
parent d1b272fab7
commit f3ecb4ee6c
2 changed files with 6 additions and 2 deletions

View File

@ -123,7 +123,7 @@ void AC_PID::slew_limit(float smax)
// target and error are filtered
// the derivative is then calculated and filtered
// the integral is then updated based on the setting of the limit flag
float AC_PID::update_all(float target, float measurement, float dt, bool limit)
float AC_PID::update_all(float target, float measurement, float dt, bool limit, float boost)
{
// don't process inf or NaN
if (!isfinite(target) || !isfinite(measurement)) {
@ -161,6 +161,10 @@ float AC_PID::update_all(float target, float measurement, float dt, bool limit)
P_out *= _pid_info.Dmod;
D_out *= _pid_info.Dmod;
// boost output if required
P_out *= boost;
D_out *= boost;
_pid_info.target = _target;
_pid_info.actual = measurement;
_pid_info.error = _error;

View File

@ -31,7 +31,7 @@ public:
// target and error are filtered
// the derivative is then calculated and filtered
// the integral is then updated based on the setting of the limit flag
float update_all(float target, float measurement, float dt, bool limit = false);
float update_all(float target, float measurement, float dt, bool limit = false, float boost = 1.0f);
// update_error - set error input to PID controller and calculate outputs
// target is set to zero and error is set and filtered