2010-11-25 21:30:21 -04:00
|
|
|
/// @file PID.cpp
|
2011-02-14 00:45:31 -04:00
|
|
|
/// @brief Generic PID algorithm
|
2010-11-25 21:30:21 -04:00
|
|
|
|
2016-03-31 18:43:36 -03:00
|
|
|
#include <cmath>
|
2010-11-25 21:54:47 -04:00
|
|
|
|
2010-11-25 21:30:21 -04:00
|
|
|
#include "PID.h"
|
2015-08-11 03:28:46 -03:00
|
|
|
#include <AP_HAL/AP_HAL.h>
|
|
|
|
#include <AP_Math/AP_Math.h>
|
2012-11-30 23:35:01 -04:00
|
|
|
|
|
|
|
extern const AP_HAL::HAL& hal;
|
2010-10-28 01:59:24 -03:00
|
|
|
|
2015-10-25 14:03:46 -03:00
|
|
|
const AP_Param::GroupInfo PID::var_info[] = {
|
2016-02-08 07:42:16 -04:00
|
|
|
|
|
|
|
// @Param: P
|
|
|
|
// @DisplayName: PID Proportional Gain
|
|
|
|
// @Description: P Gain which produces an output value that is proportional to the current error value
|
2023-01-03 13:22:48 -04:00
|
|
|
AP_GROUPINFO_FLAGS_DEFAULT_POINTER("P", 0, PID, _kp, default_kp),
|
2016-02-08 07:42:16 -04:00
|
|
|
|
|
|
|
// @Param: I
|
|
|
|
// @DisplayName: PID Integral Gain
|
|
|
|
// @Description: I Gain which produces an output that is proportional to both the magnitude and the duration of the error
|
2023-01-03 13:22:48 -04:00
|
|
|
AP_GROUPINFO_FLAGS_DEFAULT_POINTER("I", 1, PID, _ki, default_ki),
|
2016-02-08 07:42:16 -04:00
|
|
|
|
|
|
|
// @Param: D
|
|
|
|
// @DisplayName: PID Derivative Gain
|
|
|
|
// @Description: D Gain which produces an output that is proportional to the rate of change of the error
|
2023-01-03 13:22:48 -04:00
|
|
|
AP_GROUPINFO_FLAGS_DEFAULT_POINTER("D", 2, PID, _kd, default_kd),
|
2016-02-08 07:42:16 -04:00
|
|
|
|
|
|
|
// @Param: IMAX
|
|
|
|
// @DisplayName: PID Integral Maximum
|
|
|
|
// @Description: The maximum/minimum value that the I term can output
|
2023-01-03 13:22:48 -04:00
|
|
|
AP_GROUPINFO_FLAGS_DEFAULT_POINTER("IMAX", 3, PID, _imax, default_kimax),
|
2016-02-08 07:42:16 -04:00
|
|
|
|
2012-08-17 03:22:43 -03:00
|
|
|
AP_GROUPEND
|
2012-02-11 07:54:10 -04:00
|
|
|
};
|
|
|
|
|
2013-02-09 05:36:13 -04:00
|
|
|
float PID::get_pid(float error, float scaler)
|
2010-10-28 01:59:24 -03:00
|
|
|
{
|
2015-11-19 23:15:45 -04:00
|
|
|
uint32_t tnow = AP_HAL::millis();
|
2012-08-17 03:22:43 -03:00
|
|
|
uint32_t dt = tnow - _last_t;
|
|
|
|
float output = 0;
|
|
|
|
float delta_time;
|
|
|
|
|
|
|
|
if (_last_t == 0 || dt > 1000) {
|
|
|
|
dt = 0;
|
2012-08-27 03:58:40 -03:00
|
|
|
|
|
|
|
// if this PID hasn't been used for a full second then zero
|
|
|
|
// the intergator term. This prevents I buildup from a
|
|
|
|
// previous fight mode from causing a massive return before
|
|
|
|
// the integrator gets a chance to correct itself
|
2012-11-27 03:41:31 -04:00
|
|
|
reset_I();
|
2012-08-17 03:22:43 -03:00
|
|
|
}
|
|
|
|
_last_t = tnow;
|
|
|
|
|
2022-03-11 13:43:16 -04:00
|
|
|
delta_time = (float)dt * 0.001f;
|
2012-08-17 03:22:43 -03:00
|
|
|
|
|
|
|
// Compute proportional component
|
2016-05-30 03:48:40 -03:00
|
|
|
_pid_info.P = error * _kp;
|
|
|
|
output += _pid_info.P;
|
2012-08-17 03:22:43 -03:00
|
|
|
|
|
|
|
// Compute derivative component if time has elapsed
|
2013-01-10 14:42:24 -04:00
|
|
|
if ((fabsf(_kd) > 0) && (dt > 0)) {
|
2012-11-27 03:41:31 -04:00
|
|
|
float derivative;
|
|
|
|
|
|
|
|
if (isnan(_last_derivative)) {
|
|
|
|
// we've just done a reset, suppress the first derivative
|
|
|
|
// term as we don't want a sudden change in input to cause
|
|
|
|
// a large D output change
|
|
|
|
derivative = 0;
|
|
|
|
_last_derivative = 0;
|
|
|
|
} else {
|
|
|
|
derivative = (error - _last_error) / delta_time;
|
|
|
|
}
|
2012-08-17 03:22:43 -03:00
|
|
|
|
|
|
|
// discrete low pass filter, cuts out the
|
|
|
|
// high frequency noise that can drive the controller crazy
|
2016-02-25 13:13:02 -04:00
|
|
|
float RC = 1/(2*M_PI*_fCut);
|
2012-08-17 03:22:43 -03:00
|
|
|
derivative = _last_derivative +
|
2012-11-30 23:35:01 -04:00
|
|
|
((delta_time / (RC + delta_time)) *
|
|
|
|
(derivative - _last_derivative));
|
2012-08-17 03:22:43 -03:00
|
|
|
|
|
|
|
// update state
|
|
|
|
_last_error = error;
|
|
|
|
_last_derivative = derivative;
|
|
|
|
|
|
|
|
// add in derivative component
|
2016-05-30 03:48:40 -03:00
|
|
|
_pid_info.D = _kd * derivative;
|
|
|
|
output += _pid_info.D;
|
2012-08-17 03:22:43 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
// scale the P and D components
|
|
|
|
output *= scaler;
|
2016-05-30 03:48:40 -03:00
|
|
|
_pid_info.D *= scaler;
|
|
|
|
_pid_info.P *= scaler;
|
2012-08-17 03:22:43 -03:00
|
|
|
|
|
|
|
// Compute integral component if time has elapsed
|
2013-01-10 14:42:24 -04:00
|
|
|
if ((fabsf(_ki) > 0) && (dt > 0)) {
|
2012-08-17 03:22:43 -03:00
|
|
|
_integrator += (error * _ki) * scaler * delta_time;
|
|
|
|
if (_integrator < -_imax) {
|
|
|
|
_integrator = -_imax;
|
|
|
|
} else if (_integrator > _imax) {
|
|
|
|
_integrator = _imax;
|
|
|
|
}
|
2016-05-30 03:48:40 -03:00
|
|
|
_pid_info.I = _integrator;
|
2012-08-17 03:22:43 -03:00
|
|
|
output += _integrator;
|
|
|
|
}
|
|
|
|
|
2019-06-27 06:31:52 -03:00
|
|
|
_pid_info.target = output;
|
2012-08-17 03:22:43 -03:00
|
|
|
return output;
|
2010-10-28 01:59:24 -03:00
|
|
|
}
|
|
|
|
|
2011-02-14 00:45:31 -04:00
|
|
|
void
|
|
|
|
PID::reset_I()
|
|
|
|
{
|
2012-08-17 03:22:43 -03:00
|
|
|
_integrator = 0;
|
2012-11-27 03:41:31 -04:00
|
|
|
// we use NAN (Not A Number) to indicate that the last
|
|
|
|
// derivative value is not valid
|
|
|
|
_last_derivative = NAN;
|
2016-05-30 03:48:40 -03:00
|
|
|
_pid_info.I = 0;
|
2011-02-14 00:45:31 -04:00
|
|
|
}
|
2010-10-28 01:59:24 -03:00
|
|
|
|
2017-10-12 19:26:22 -03:00
|
|
|
void PID::reset() {
|
|
|
|
memset(&_pid_info, 0, sizeof(_pid_info));
|
|
|
|
reset_I();
|
|
|
|
}
|
|
|
|
|
2010-11-25 19:26:44 -04:00
|
|
|
void
|
2010-11-25 20:06:06 -04:00
|
|
|
PID::load_gains()
|
2010-11-25 19:26:44 -04:00
|
|
|
{
|
2012-08-17 03:22:43 -03:00
|
|
|
_kp.load();
|
|
|
|
_ki.load();
|
|
|
|
_kd.load();
|
|
|
|
_imax.load();
|
2010-11-25 19:26:44 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
void
|
2010-11-25 20:06:06 -04:00
|
|
|
PID::save_gains()
|
2010-11-25 19:26:44 -04:00
|
|
|
{
|
2012-08-17 03:22:43 -03:00
|
|
|
_kp.save();
|
|
|
|
_ki.save();
|
|
|
|
_kd.save();
|
|
|
|
_imax.save();
|
2010-10-28 01:59:24 -03:00
|
|
|
}
|