8000 GitHub - cwl0127/QuickPID: A fast PID controller with Integral anti-windup, timer mode and multiple options for Proportional, Derivative and anti-windup modes of operation. Also includes analogWrite compatibility for ESP32 and ESP32-S2.
[go: up one dir, main page]

Skip to content
forked from Dlloydev/QuickPID

A fast PID controller with Integral anti-windup, timer mode and multiple options for Proportional, Derivative and anti-windup modes of operation. Also includes analogWrite compatibility for ESP32 and ESP32-S2.

License

Notifications You must be signed in to change notification settings

cwl0127/QuickPID

 
 

Folders and files

NameName
Last commit message
Last commit date

Latest commit

 
 
 
 
 
 
 
 
 
 
 
 
 
 
 

Repository files navigation

QuickPID arduino-library-badge

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 except for using a more advanced anti-windup mode. Integral anti-windup 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.

Features

Development began with a fork of the Arduino PID Library. Modifications and new features have been added as described in the releases.

New feature Summary

  • New functions added: SetProportionalMode, SetDerivativeMode and SetAntiWindupMode
  • timer mode for calling PID compute by an external timer function or ISR
  • analogWrite() support for ESP32 and ESP32-S2
  • Proportional on error pOnError, measurement pOnMeas or both pOnErrorMeas options
  • Derivative on error dOnError and measurement dOnMeas options
  • New PID Query Functions GetPterm, GetIterm, GetDterm, GetPmode, GetDmode and GetAwMode
  • New integral anti-windup options iAwCondition, iAwClamp and iAwOff
  • New reverse mode only changes sign of error and dInput
  • Uses float instead of double

Direct and Reverse Controller Action

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).

Functions

QuickPID_Constructor

QuickPID::QuickPID(float* Input, float* Output, float* Setpoint, float Kp, float Ki, float Kd,
                   pMode pMode = pMode::pOnError, dMode dMode = dMode::dOnMeas,
                   iAwMode iAwMode = iAwMode::iAwCondition, Action action = Action::direct)
  • Input, Output, and Setpoint are pointers to the variables holding these values.
  • Kp, Ki, and Kd are the PID proportional, integral, and derivative gains.
  • pMode is the proportional mode parameter with options for pOnError proportional on error (default), pOnMeas proportional on measurement and pOnErrorMeas which is 0.5 pOnError + 0.5 pOnMeas.
  • dMode is the derivative mode parameter with options for dOnError derivative on error, dOnMeas derivative on measurement (default).
  • awMode is the integral anti-windup parameter with an option for iAwCondition (default) that is based on PI terms to provide some integral correction, prevent deep saturation and reduce overshoot. TheiAwClamp option clamps the summation of the pmTerm and iTerm. The iAwOff option turns off all anti-windup.
  • Action is the controller action parameter which has direct (default) and reverse options. These options set how the controller responds to a change in input. direct action is used if the input moves in the same direction as the controller output (i.e. heating process). reverse action 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, Action action)

This allows you to use Proportional on Error without explicitly saying so.

QuickPID::QuickPID(float *Input, float *Output, float *Setpoint)

This simplified version allows you to define the remaining parameters later via specific setter functions. By default, Kp, Ki, and Kd will be initialized to zero and should be later set via SetTunings to relevant values.

Compute

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.

Initialize

void QuickPID::Initialize();

Does all the things that need to happen to ensure a bump-less transfer from manual to automatic mode.

PID Query Functions

These functions query the internal state of the PID.

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();       // pOnError (0), pOnMeas (1), pOnErrorMeas (2)
uint8_t GetDmode();       // dOnError (0), dOnMeas (1)
uint8_t GetAwMode();      // iAwCondition (0, iAwClamp (1), iAwOff (2)

PID Set Functions

These functions set the internal state of the PID.

void SetMode(Control mode);                     // Set PID mode to manual, automatic or timer
void SetOutputLimits(float Min, float Max);     // Set and clamps the output to (0-255 by default)
void SetTunings(float Kp, float Ki, float Kd,   // set pid tunings and all computational modes
     pMode pMode, dMode dMode, iAwMode iAwMode);
void SetTunings(float Kp, float Ki, float Kd);  // only set pid tunings, other pid modes are unchanged
void SetControllerDirection(Action Action);     // Set controller action to direct (default) or reverse
void SetSampleTimeUs(uint32_t NewSampleTimeUs); // Set PID compute sample time, default = 100000 µs
void SetProportionalMode(pMode pMode);          // Set pTerm based on error (default), measurement, or both
void SetDerivativeMode(dMode dMode);            // Set the dTerm, based error or measurement (default).
void SetAntiWindupMode(iAwMode iAwMode);        // Set iTerm anti-windup to iAwCondition, iAwClamp or iAwOff

SetMode

void QuickPID::SetMode(Control Mode);

Allows the controller Mode to be set to manual (0) (default) 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: PID_AVR_Basic_Interrupt_TIMER.ino and PID_AVR_Basic_Software_TIMER.ino

SetOutputLimits

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.

SetTunings

void QuickPID::SetTunings(float Kp, float Ki, float Kd, pMode pMode = pMode::pOnError,
                          dMode dMode = dMode::dOnMeas, iAwMode iAwMode = iAwMode::iAwCondition)

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 iAwMode settings. See example PID_AdaptiveTunings.ino

SetControllerDirection

void QuickPID::SetControllerDirection(Action 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.

SetSampleTime

void QuickPID::SetSampleTimeUs(uint32_t NewSampleTimeUs);

Sets the period, in microseconds, at which the calculation is performed. The default is 100000µs (100ms).

SetProportionalMode

void QuickPID::SetProportionalMode(pMode pMode);

Sets the computation method for the proportional term, to compute based either on error (default), on measurement, or the average of both.

SetDerivativeMode

void QuickPID::SetDerivativeMode(dMode dMode);

Sets the computation method for the derivative term, to compute based either on error or on measurement (default).

SetAntiWindupMode

void QuickPID::SetAntiWindupMode(iAwMode iAwMode);

Sets the integral anti-windup mode to one of iAwClamp, which clamps the output after adding integral and proportional (on measurement) terms, or iAwCondition (default), which provides some integral correction, prevents deep saturation and reduces overshoot. Option iAwOff disables anti-windup altogether.

AnalogWrite (PWM and DAC) for ESP32

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. AnalogWrite documentation

Original README (Arduino PID)

***************************************************************
* Arduino PID Library - Version 1.2.1
* by Brett Beauregard <br3ttb@gmail.com> brettbeauregard.com
*
* This Library is licensed under the MIT License
***************************************************************

About

A fast PID controller with Integral anti-windup, timer mode and multiple options for Proportional, Derivative and anti-windup modes of operation. Also includes analogWrite compatibility for ESP32 and ESP32-S2.

Resources

License

Stars

Watchers

Forks

Packages

No packages published

Languages

  • C++ 100.0%
0