QuickPID is an updated implementation of the Arduino PID library with additional features for PID control. By default, this implementation closely follows the method of processing the p,i,d terms as in the PID_v1 library. One of the additional features includes integral anti-windup which can be based on conditionally using PI terms to provide some integral correction, prevent deep saturation and reduce overshoot. Anti-windup can also be based on clamping only, or it can be turned completely off. Also, the proportional term can be based on error, measurement, or both. The derivative term can be based on error or measurement. PID controller modes include TIMER, which allows external timer or ISR timing control.
Development began with a fork of the Arduino PID Library. Modifications and new features have been added as described in the releases.
-
TIMERmode for calling PID compute by an external timer function or ISR -
analogWrite()support for ESP32 and ESP32-S2 - Proportional on error
PE, measurementPMor bothPEMoptions - Derivative on error
DEand measurementDMoptions - New PID Query Functions
GetPterm,GetIterm,GetDterm,GetPmode,GetDmodeandGetAwMode - New integral anti-windup options
CONDITION,CLAMPandOFF - New
REVERSEmode only changes sign oferroranddInput - Uses
floatinstead ofdouble
Direct controller action leads the output to increase when the input is larger than the setpoint (i.e. heating process). Reverse controller leads the output to decrease when the input is larger than the setpoint (i.e. cooling process).
When the controller is set to REVERSE acting, the sign of the error and dInput (derivative of Input) is internally changed. All operating ranges and limits remain the same. To simulate a REVERSE acting process from a process that's DIRECT acting, the Input value needs to be "flipped". That is, if your reading from a 10-bit ADC with 0-1023 range, the input value used is (1023 - reading).
QuickPID::QuickPID(float* Input, float* Output, float* Setpoint,
float Kp, float Ki, float Kd, uint8_t pMode = PE, uint8_t dMode = DM,
uint8_t awMode = CLAMP, uint8_t Action = DIRECT)Input,Output, andSetpointare pointers to the variables holding these values.Kp,Ki, andKdare the PID proportional, integral, and derivative gains.pModeis the proportional mode parameter with options forPEproportional on error (default),PMproportional on measurement andPEMwhich is 0.5PE+ 0.5PM.dModeis the derivative mode parameter with options forDEderivative on error (default),DMderivative on measurement (default).awModeis the integral anti-windup parameter with an option forCONDITIONwhich is based on PI terms to provide some integral correction, prevent deep saturation and reduce overshoot. TheCLAMPoption (default), clamps the summation of the pmTerm and iTerm. TheOFFoption turns off all anti-windup.Actionis the controller action parameter which hasDIRECT(default) andREVERSEoptions. These options set how the controller responds to a change in input.DIRECTaction is used if the input moves in the same direction as the controller output (i.e. heating process).REVERSEaction is used if the input moves in the opposite direction as the controller output (i.e. cooling process).
QuickPID::QuickPID(float* Input, float* Output, float* Setpoint,
float Kp, float Ki, float Kd, uint8_t Action = DIRECT)This allows you to use Proportional on Error without explicitly saying so.
bool QuickPID::Compute();This function contains the PID algorithm and it should be called once every loop(). Most of the time it will just return false without doing anything. However, at a frequency specified by SetSampleTime it will calculate a new Output and return true.
void QuickPID::SetTunings(float Kp, float Ki, float Kd, uint8_t pMode = PE, uint8_t dMode = DM, uint8_t awMode = CLAMP)This function allows the controller's dynamic performance to be adjusted. It's called automatically from the constructor, but tunings can also be adjusted on the fly during normal operation. The parameters are as described in the constructor.
void QuickPID::SetTunings(float Kp, float Ki, float Kd);Set Tunings using the last remembered pMode, dMode and awMode settings. See example PID_AdaptiveTunings.ino
void QuickPID::SetSampleTimeUs(uint32_t NewSampleTimeUs);Sets the period, in microseconds, at which the calculation is performed. The default is 100000µs (100ms).
void QuickPID::SetOutputLimits(float Min, float Max);The PID controller is designed to vary its output within a given range. By default this range is 0-255, the Arduino PWM range.
void QuickPID::SetMode(uint8_t Mode)Allows the controller Mode to be set to MANUAL (0) or AUTOMATIC (1) or TIMER (2). when the transition from manual to automatic or timer occurs, the controller is automatically initialized.
TIMER mode is used when the PID compute is called by an external timer function or ISR. In this mode, the timer function and SetSampleTimeUs use the same time period value. The PID compute and timer will always remain in sync because the sample time variable and calculations remain constant. See examples:
void QuickPID::Initialize();Does all the things that need to happen to ensure a bump-less transfer from manual to automatic mode.
void QuickPID::SetControllerDirection(uint8_t Action)The PID will either be connected to a DIRECT acting process (+Output leads to +Input) or a REVERSE acting process (+Output leads to -Input.) We need to know which one, because otherwise we may increase the output when we should be decreasing. This is called from the constructor.
float GetKp(); // proportional gain
float GetKi(); // integral gain
float GetKd(); // derivative gain
float GetPterm(); // proportional component of output
float GetIterm(); // integral component of output
float GetDterm(); // derivative component of output
uint8_t GetMode(); // MANUAL (0), AUTOMATIC (1) or TIMER (2)
uint8_t GetDirection(); // DIRECT (0), REVERSE (1)
uint8_t GetPmode(); // PE (0), PM (1), PEM (2)
uint8_t GetDmode(); // DE (0), DM (1)
uint8_t GetAwMode(); // CONDITION (0), CLAMP (1), OFF (2)These functions query the internal state of the PID.
If you're using QuickPID with an ESP32 and need analogWrite compatibility, there's no need to install a library as this feature is already included.
***************************************************************
* Arduino PID Library - Version 1.2.1
* by Brett Beauregard <br3ttb@gmail.com> brettbeauregard.com
*
* This Library is licensed under the MIT License
***************************************************************
-
For an ultra-detailed explanation of the original code, please visit: http://brettbeauregard.com/blog/2011/04/improving-the-beginners-pid-introduction/
-
For function documentation see: http://playground.arduino.cc/Code/PIDLibrary