ardupilot/libraries/PID/PID.cpp

144 lines
3.6 KiB
C++
Raw Normal View History

/// @file PID.cpp
/// @brief Generic PID algorithm
#include <cmath>
#include "PID.h"
#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;
const AP_Param::GroupInfo PID::var_info[] = {
// @Param: P
// @DisplayName: PID Proportional Gain
// @Description: P Gain which produces an output value that is proportional to the current error value
2012-08-17 03:22:43 -03:00
AP_GROUPINFO("P", 0, PID, _kp, 0),
// @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
2012-08-17 03:22:43 -03:00
AP_GROUPINFO("I", 1, PID, _ki, 0),
// @Param: D
// @DisplayName: PID Derivative Gain
// @Description: D Gain which produces an output that is proportional to the rate of change of the error
2012-08-17 03:22:43 -03:00
AP_GROUPINFO("D", 2, PID, _kd, 0),
// @Param: IMAX
// @DisplayName: PID Integral Maximum
// @Description: The maximum/minimum value that the I term can output
2012-08-17 03:22:43 -03:00
AP_GROUPINFO("IMAX", 3, PID, _imax, 0),
2012-08-17 03:22:43 -03:00
AP_GROUPEND
2012-02-11 07:54:10 -04:00
};
float PID::get_pid(float error, float scaler)
{
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;
// 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
reset_I();
2012-08-17 03:22:43 -03:00
}
_last_t = tnow;
delta_time = (float)dt / 1000.0f;
2012-08-17 03:22:43 -03:00
// Compute proportional component
_pid_info.P = error * _kp;
output += _pid_info.P;
2012-08-17 03:22:43 -03:00
// Compute derivative component if time has elapsed
if ((fabsf(_kd) > 0) && (dt > 0)) {
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
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
_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;
_pid_info.D *= scaler;
_pid_info.P *= scaler;
2012-08-17 03:22:43 -03:00
// Compute integral component if time has elapsed
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;
}
_pid_info.I = _integrator;
2012-08-17 03:22:43 -03:00
output += _integrator;
}
_pid_info.desired = output;
2012-08-17 03:22:43 -03:00
return output;
}
void
PID::reset_I()
{
2012-08-17 03:22:43 -03:00
_integrator = 0;
// we use NAN (Not A Number) to indicate that the last
// derivative value is not valid
_last_derivative = NAN;
_pid_info.I = 0;
}
2017-10-12 19:26:22 -03:00
void PID::reset() {
memset(&_pid_info, 0, sizeof(_pid_info));
reset_I();
}
void
PID::load_gains()
{
2012-08-17 03:22:43 -03:00
_kp.load();
_ki.load();
_kd.load();
_imax.load();
}
void
PID::save_gains()
{
2012-08-17 03:22:43 -03:00
_kp.save();
_ki.save();
_kd.save();
_imax.save();
}