Skip to content

Commit

Permalink
Merge pull request #9 from Dlloydev/work-in-progress
Browse files Browse the repository at this point in the history
Major update
  • Loading branch information
Dlloydev authored May 20, 2021
2 parents c688c8d + 323d52e commit 7f8e049
Show file tree
Hide file tree
Showing 5 changed files with 202 additions and 147 deletions.
10 changes: 9 additions & 1 deletion README.md
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
# QuickPID [![arduino-library-badge](https://www.ardu-badge.com/badge/QuickPID.svg?)](https://www.ardu-badge.com/QuickPID)

QuickPID is a fast fixed/floating point implementation of the Arduino PID library with built-in [AutoTune](https://github.com/Dlloydev/QuickPID/wiki/AutoTune) class as a dynamic object to reduce memory if not used. This controller can automatically determine and set parameters `Kp, Ki, Kd`. Additionally the Ultimate Gain `Ku`, Ultimate Period `Tu`, Dead Time `td` and determine how easy the process is to control. There are 10 tuning rules available to choose from. Also available is a POn setting that controls the mix of Proportional on Error to Proportional on Measurement.
QuickPID is a fast fixed/floating point implementation of the Arduino PID library with built-in [AutoTune](https://github.com/Dlloydev/QuickPID/wiki/AutoTune) class as a dynamic object to reduce memory if not used, thanks to contributions by [gnalbandian (Gonzalo)](https://github.com/gnalbandian). This controller can automatically determine and set parameters `Kp, Ki, Kd`. Additionally the Ultimate Gain `Ku`, Ultimate Period `Tu`, Dead Time `td` and determine how easy the process is to control. There are 10 tuning rules available to choose from. Also available is a POn setting that controls the mix of Proportional on Error to Proportional on Measurement.

### About

Expand Down Expand Up @@ -164,6 +164,14 @@ Use this link for reference. Note that if you're using QuickPID, there's no need
#### Change Log
#### Version 2.3.0
- New AutoTune class added as a dynamic object to reduce memory if not used, thanks to contributions by [gnalbandian (Gonzalo)](https://github.com/gnalbandian).
- AutoTune now works for a reverse acting controller.
- AutoTune configuration parameters include outputStep, hysteresis, setpoint, output, direction and printOrPlotter.
- Defined tuningMethod as an enum.
- Updated AnalogWrite methods for ESP32/ESP32-S2.
#### Version 2.2.8
- AutoTune is now independent of the QuickPID library and can be run from a sketch. AutoTune is now non-blocking, no timeouts are required and it uses Input and Output variables directly.
Expand Down
68 changes: 35 additions & 33 deletions examples/AutoTune_Filter_DIRECT/AutoTune_Filter_DIRECT.ino
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,7 @@ int output = 85; // 1/3 of 8-bit PWM range for symetrical waveform

float Input, Output, Setpoint;
float Kp = 0, Ki = 0, Kd = 0;
bool pidLoop = false;

QuickPID _myPID = QuickPID(&Input, &Output, &Setpoint, Kp, Ki, Kd, POn, QuickPID::DIRECT);

Expand All @@ -33,46 +34,47 @@ void setup() {
Serial.println(F("AutoTune test exceeds outMax limit. Check output, hysteresis and outputStep values"));
while (1);
}
_myPID.AutoTune(tuningRule);
_myPID.AutoTune(tuningMethod::ZIEGLER_NICHOLS_PID);
_myPID.autoTune->autoTuneConfig(outputStep, hysteresis, setpoint, output, QuickPID::DIRECT, printOrPlotter);
}

void loop() {

if (_myPID.autoTune) // Avoid deferencing nullptr after _myPID.clearAutoTune()
{
uint8_t autoTuningCurrentStage = autoTuneLoop();
if(autoTuningCurrentStage < _myPID.autoTune->RUN_PID)
{
Input = avg(_myPID.analogReadFast(inputPin)); // filtered input
analogWrite(outputPin, Output);
if (autoTuningCurrentStage == _myPID.autoTune->NEW_TUNINGS) // get new tunings
{
_myPID.autoTune->setAutoTuneConstants(&Kp, &Ki, &Kd); // set new tunings
_myPID.SetMode(QuickPID::AUTOMATIC); // setup PID
_myPID.SetTunings(Kp, Ki, Kd, POn); // apply new tunings to PID
Setpoint = 500;
}
}
else // RUN_PID stage
{
if (printOrPlotter == 0) // plotter
{
_myPID.clearAutoTune(); // releases memory used by AutoTune object
Serial.print("Setpoint:"); Serial.print(Setpoint); Serial.print(",");
Serial.print("Input:"); Serial.print(Input); Serial.print(",");
Serial.print("Output:"); Serial.print(Output); Serial.println();
}
}
}
else // Autotune already done (or not created)
{
Input = _myPID.analogReadFast(inputPin);
if (_myPID.autoTune) // Avoid dereferencing nullptr after _myPID.clearAutoTune()
{
switch (_myPID.autoTune->autoTuneLoop()) {
case _myPID.autoTune->AUTOTUNE:
Input = avg(_myPID.analogReadFast(inputPin));
analogWrite(outputPin, Output);
break;

case _myPID.autoTune->TUNINGS:
_myPID.autoTune->setAutoTuneConstants(&Kp, &Ki, &Kd); // set new tunings
_myPID.SetMode(QuickPID::AUTOMATIC); // setup PID
_myPID.SetSampleTimeUs(10000); // 10ms
_myPID.SetTunings(Kp, Ki, Kd, POn); // apply new tunings to PID
Setpoint = 500;
break;

case _myPID.autoTune->CLR:
if (!pidLoop) {
_myPID.clearAutoTune(); // releases memory used by AutoTune object
pidLoop = true;
}
break;
}
}
if (pidLoop) {
if (printOrPlotter == 0) { // plotter
Serial.print("Setpoint:"); Serial.print(Setpoint); Serial.print(",");
Serial.print("Input:"); Serial.print(Input); Serial.print(",");
Serial.print("Output:"); Serial.print(Output); Serial.println();
}
Input = _myPID.analogReadFast(inputPin);
_myPID.Compute();
analogWrite(outputPin, Output);
}
}
//delay(1); // adjust loop speed
}

float avg(int inputVal) {
Expand Down
39 changes: 26 additions & 13 deletions examples/AutoTune_Filter_REVERSE/AutoTune_Filter_REVERSE.ino
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,7 @@ int output = 85; // 1/3 of 8-bit PWM range for symetrical waveform

float Input, Output, Setpoint;
float Kp = 0, Ki = 0, Kd = 0;
bool pidLoop = false;

QuickPID _myPID = QuickPID(&Input, &Output, &Setpoint, Kp, Ki, Kd, POn, QuickPID::REVERSE);

Expand All @@ -34,26 +35,37 @@ void setup() {
Serial.println(F("AutoTune test exceeds outMax limit. Check output, hysteresis and outputStep values"));
while (1);
}
_myPID.AutoTune(tuningRule);
_myPID.AutoTune(tuningMethod::ZIEGLER_NICHOLS_PID);
_myPID.autoTune->autoTuneConfig(outputStep, hysteresis, inputMax - setpoint, output, QuickPID::REVERSE, printOrPlotter);
}

void loop() {

if (_myPID.autoTune->autoTuneLoop() != _myPID.autoTune->RUN_PID) { // running autotune
Input = inputMax - avg(_myPID.analogReadFast(inputPin)); // filtered input (reverse acting)
analogWrite(outputPin, Output);
}
if (_myPID.autoTune) // Avoid dereferencing nullptr after _myPID.clearAutoTune()
{
switch (_myPID.autoTune->autoTuneLoop()) {
case _myPID.autoTune->AUTOTUNE:
Input = inputMax - avg(_myPID.analogReadFast(inputPin)); // filtered, reverse acting
analogWrite(outputPin, Output);
break;

if (_myPID.autoTune->autoTuneLoop() == _myPID.autoTune->NEW_TUNINGS) { // get new tunings
_myPID.autoTune->setAutoTuneConstants(&Kp, &Ki, &Kd); // set new tunings
_myPID.clearAutoTune(); // releases memory used by AutoTune object
_myPID.SetMode(QuickPID::AUTOMATIC); // setup PID
_myPID.SetTunings(Kp, Ki, Kd, POn); // apply new tunings to PID
Setpoint = 500;
}
case _myPID.autoTune->TUNINGS:
_myPID.autoTune->setAutoTuneConstants(&Kp, &Ki, &Kd); // set new tunings
_myPID.SetMode(QuickPID::AUTOMATIC); // setup PID
_myPID.SetSampleTimeUs(10000); // 10ms
_myPID.SetTunings(Kp, Ki, Kd, POn); // apply new tunings to PID
Setpoint = 500;
break;

if (_myPID.autoTune->autoTuneLoop() == _myPID.autoTune->RUN_PID) { // running PID
case _myPID.autoTune->CLR:
if (!pidLoop) {
_myPID.clearAutoTune(); // releases memory used by AutoTune object
pidLoop = true;
}
break;
}
}
if (pidLoop) {
if (printOrPlotter == 0) { // plotter
Serial.print("Setpoint:"); Serial.print(Setpoint); Serial.print(",");
Serial.print("Input:"); Serial.print(Input); Serial.print(",");
Expand All @@ -63,6 +75,7 @@ void loop() {
_myPID.Compute();
analogWrite(outputPin, Output);
}
//delay(1); // adjust loop speed
}

float avg(int inputVal) {
Expand Down
Loading

0 comments on commit 7f8e049

Please sign in to comment.