Skip to content

Commit 7f8e049

Browse files
authoredMay 20, 2021
Merge pull request br3ttb#9 from Dlloydev/work-in-progress
Major update
2 parents c688c8d + 323d52e commit 7f8e049

File tree

5 files changed

+202
-147
lines changed

5 files changed

+202
-147
lines changed
 

‎README.md

+9-1
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,6 @@
11
# QuickPID [![arduino-library-badge](https://www.ardu-badge.com/badge/QuickPID.svg?)](https://www.ardu-badge.com/QuickPID)
22

3-
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.
3+
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.
44

55
### About
66

@@ -164,6 +164,14 @@ Use this link for reference. Note that if you're using QuickPID, there's no need
164164
165165
#### Change Log
166166
167+
#### Version 2.3.0
168+
169+
- New AutoTune class added as a dynamic object to reduce memory if not used, thanks to contributions by [gnalbandian (Gonzalo)](https://github.com/gnalbandian).
170+
- AutoTune now works for a reverse acting controller.
171+
- AutoTune configuration parameters include outputStep, hysteresis, setpoint, output, direction and printOrPlotter.
172+
- Defined tuningMethod as an enum.
173+
- Updated AnalogWrite methods for ESP32/ESP32-S2.
174+
167175
#### Version 2.2.8
168176
169177
- 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.

‎examples/AutoTune_Filter_DIRECT/AutoTune_Filter_DIRECT.ino

+35-33
Original file line numberDiff line numberDiff line change
@@ -23,6 +23,7 @@ int output = 85; // 1/3 of 8-bit PWM range for symetrical waveform
2323

2424
float Input, Output, Setpoint;
2525
float Kp = 0, Ki = 0, Kd = 0;
26+
bool pidLoop = false;
2627

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

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

4041
void loop() {
4142

42-
if (_myPID.autoTune) // Avoid deferencing nullptr after _myPID.clearAutoTune()
43-
{
44-
uint8_t autoTuningCurrentStage = autoTuneLoop();
45-
if(autoTuningCurrentStage < _myPID.autoTune->RUN_PID)
46-
{
47-
Input = avg(_myPID.analogReadFast(inputPin)); // filtered input
48-
analogWrite(outputPin, Output);
49-
50-
if (autoTuningCurrentStage == _myPID.autoTune->NEW_TUNINGS) // get new tunings
51-
{
52-
_myPID.autoTune->setAutoTuneConstants(&Kp, &Ki, &Kd); // set new tunings
53-
_myPID.SetMode(QuickPID::AUTOMATIC); // setup PID
54-
_myPID.SetTunings(Kp, Ki, Kd, POn); // apply new tunings to PID
55-
Setpoint = 500;
56-
}
57-
}
58-
else // RUN_PID stage
59-
{
60-
if (printOrPlotter == 0) // plotter
61-
{
62-
_myPID.clearAutoTune(); // releases memory used by AutoTune object
63-
Serial.print("Setpoint:"); Serial.print(Setpoint); Serial.print(",");
64-
Serial.print("Input:"); Serial.print(Input); Serial.print(",");
65-
Serial.print("Output:"); Serial.print(Output); Serial.println();
66-
}
67-
}
68-
69-
}
70-
else // Autotune already done (or not created)
71-
{
72-
Input = _myPID.analogReadFast(inputPin);
43+
if (_myPID.autoTune) // Avoid dereferencing nullptr after _myPID.clearAutoTune()
44+
{
45+
switch (_myPID.autoTune->autoTuneLoop()) {
46+
case _myPID.autoTune->AUTOTUNE:
47+
Input = avg(_myPID.analogReadFast(inputPin));
48+
analogWrite(outputPin, Output);
49+
break;
50+
51+
case _myPID.autoTune->TUNINGS:
52+
_myPID.autoTune->setAutoTuneConstants(&Kp, &Ki, &Kd); // set new tunings
53+
_myPID.SetMode(QuickPID::AUTOMATIC); // setup PID
54+
_myPID.SetSampleTimeUs(10000); // 10ms
55+
_myPID.SetTunings(Kp, Ki, Kd, POn); // apply new tunings to PID
56+
Setpoint = 500;
57+
break;
58+
59+
case _myPID.autoTune->CLR:
60+
if (!pidLoop) {
61+
_myPID.clearAutoTune(); // releases memory used by AutoTune object
62+
pidLoop = true;
63+
}
64+
break;
65+
}
66+
}
67+
if (pidLoop) {
68+
if (printOrPlotter == 0) { // plotter
69+
Serial.print("Setpoint:"); Serial.print(Setpoint); Serial.print(",");
70+
Serial.print("Input:"); Serial.print(Input); Serial.print(",");
71+
Serial.print("Output:"); Serial.print(Output); Serial.println();
72+
}
73+
Input = _myPID.analogReadFast(inputPin);
7374
_myPID.Compute();
7475
analogWrite(outputPin, Output);
75-
}
76+
}
77+
//delay(1); // adjust loop speed
7678
}
7779

7880
float avg(int inputVal) {

‎examples/AutoTune_Filter_REVERSE/AutoTune_Filter_REVERSE.ino

+26-13
Original file line numberDiff line numberDiff line change
@@ -24,6 +24,7 @@ int output = 85; // 1/3 of 8-bit PWM range for symetrical waveform
2424

2525
float Input, Output, Setpoint;
2626
float Kp = 0, Ki = 0, Kd = 0;
27+
bool pidLoop = false;
2728

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

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

4142
void loop() {
4243

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

48-
if (_myPID.autoTune->autoTuneLoop() == _myPID.autoTune->NEW_TUNINGS) { // get new tunings
49-
_myPID.autoTune->setAutoTuneConstants(&Kp, &Ki, &Kd); // set new tunings
50-
_myPID.clearAutoTune(); // releases memory used by AutoTune object
51-
_myPID.SetMode(QuickPID::AUTOMATIC); // setup PID
52-
_myPID.SetTunings(Kp, Ki, Kd, POn); // apply new tunings to PID
53-
Setpoint = 500;
54-
}
52+
case _myPID.autoTune->TUNINGS:
53+
_myPID.autoTune->setAutoTuneConstants(&Kp, &Ki, &Kd); // set new tunings
54+
_myPID.SetMode(QuickPID::AUTOMATIC); // setup PID
55+
_myPID.SetSampleTimeUs(10000); // 10ms
56+
_myPID.SetTunings(Kp, Ki, Kd, POn); // apply new tunings to PID
57+
Setpoint = 500;
58+
break;
5559

56-
if (_myPID.autoTune->autoTuneLoop() == _myPID.autoTune->RUN_PID) { // running PID
60+
case _myPID.autoTune->CLR:
61+
if (!pidLoop) {
62+
_myPID.clearAutoTune(); // releases memory used by AutoTune object
63+
pidLoop = true;
64+
}
65+
break;
66+
}
67+
}
68+
if (pidLoop) {
5769
if (printOrPlotter == 0) { // plotter
5870
Serial.print("Setpoint:"); Serial.print(Setpoint); Serial.print(",");
5971
Serial.print("Input:"); Serial.print(Input); Serial.print(",");
@@ -63,6 +75,7 @@ void loop() {
6375
_myPID.Compute();
6476
analogWrite(outputPin, Output);
6577
}
78+
//delay(1); // adjust loop speed
6679
}
6780

6881
float avg(int inputVal) {

0 commit comments

Comments
 (0)
Please sign in to comment.