Skip to content

Commit 4d6d76c

Browse files
committed
Update
Major update
1 parent 937f00b commit 4d6d76c

File tree

10 files changed

+393
-185
lines changed

10 files changed

+393
-185
lines changed

README.md

Lines changed: 37 additions & 29 deletions
Original file line numberDiff line numberDiff line change
@@ -4,13 +4,13 @@ This is an open loop PID autotuner using a novel s-curve inflection point test m
44

55
#### Reaction Curve Inflection Point Tuning Method
66

7-
This tuning method determines the process gain, dead time and time constant by doing a shortened step test that ends just after the [inflection point](http://en.wikipedia.org/wiki/Inflection_point) has been reached. From here, the apparent maximum PV (input) is mathematically determined and the controller's tuning parameters are calculated. Test duration is typically only ½Tau.
7+
This tuning method determines the process gain, dead time, time constant and more by doing a shortened step test that ends just after the [inflection point](http://en.wikipedia.org/wiki/Inflection_point) has been reached. From here, the apparent maximum PV (input) is mathematically determined and the controller's tuning parameters are calculated. Test duration is typically only ½Tau.
88

99
- See [**WiKi**](https://github.com/Dlloydev/sTune/wiki) for test results and more.
1010

1111
#### Inflection Point Discovery
1212

13-
Accurate determination of the inflection point was given high priority for this test method. To accomplish this, a circular buffer for the input readings is created that's sized to 10% of samples. The buffer is used as a moving tangent line where the "head" of the tangent is based on the average of all readings in the buffer and the "tail" is based on the oldest instantaneous value in the buffer. The tangent line slides along the reaction curve where where the head (leading point) moves smoothly but with moderate response, and the tail (trailing point) may have some jitter due to being instantaneous and more easily influenced by noise and input resolution.
13+
Accurate determination of the inflection point was given high priority for this test method. To accomplish this, a circular buffer for the input readings is created that's sized to 10% of samples. The buffer is used as a moving tangent line where the "head" of the tangent is based on the average of all readings in the buffer and the "tail" is based on the oldest instantaneous value in the buffer. The tangent line slides along the reaction curve where where the head (leading point) moves smoothly but with moderate response. The tail (trailing point) of the tangent line is represented by instantaneous input readings that have occurred in the past (oldest buffer data point).
1414

1515
The slope of the tangent line is checked at every sample. When the sign of the change in slope changes (i.e. slope goes from increasing to decreasing or from decreasing to increasing), this is the point of inflection ([where the tangent turns red here](https://en.wikipedia.org/wiki/Inflection_point#/media/File:Animated_illustration_of_inflection_point.gif)). After 1⁄16 samples has occurred with the new slope direction, then it's known that the point of inflection has been reached. Final calculations are made and the test ends.
1616

@@ -25,7 +25,7 @@ The slope of the tangent line is checked at every sample. When the sign of the c
2525
- The tuner action is set to `directIP` or `reverseIP`, then configure sTune:
2626

2727
- ```c++
28-
tuner.Configure(outputStart, outputStep, testTimeSec, settleTimeSec, samples);
28+
tuner.Configure(inputSpan, outputSpan, outputStart, outputStep, testTimeSec, settleTimeSec, samples);
2929
```
3030

3131
- Its expected that the user is already familiar with the controller and can make a rough estimation of what the system's time constant would be. Use this estimate for the `testTimeSec` constant.
@@ -34,6 +34,12 @@ The slope of the tangent line is checked at every sample. When the sign of the c
3434

3535
- `settleTimeSec` is used to provide additional settling time prior to starting the test.
3636

37+
- `inputSpan` and `outputSpan` represent the maximum operating range of input and output. Examples:
38+
39+
- If your input works with temp readings of 20C min and 150C max, then `inputSpan = 130;`
40+
If the output uses 8-bit PWM and your using its full range, then `outputSpan = 255;`
41+
If the output is digital relay controlled by millis() with window period of 2000ms, then `outputSpan = 2000;`
42+
3743
- `outputStart` is the initial control output value which is used for the first 12 samples.
3844

3945
- `outputStep` is the stepped output value used for sample 13 to test completion.
@@ -67,18 +73,18 @@ sTune(float *input, float *output, TuningRule tuningRule, Action action, SerialM
6773
- `action` provides choices for controller action (direct or reverse) and whether to perform a fast inflection point test (IP) or a full 5 time constant test (5T). Choices are `directIP`, `direct5T`, `reverseIP` and `reverse5T`.
6874
- `serialMode` provides 6 choices for serial output as described in the table below.
6975

70-
| Tuning Rule | Description |
71-
| ------------------- | -------------------------------------------------------- |
72-
| `zieglerNicholsPI` | Good noise and disturbance rejection |
73-
| `zieglerNicholsPID` | Good noise and disturbance rejection |
74-
| `tyreusLuybenPI` | Time-constant (lag) dominant processes (conservative) |
75-
| `tyreusLuybenPID` | Time-constant (lag) dominant processes (conservative) |
76-
| `cianconeMarlinPI` | Delay (dead-time) dominant processes |
77-
| `cianconeMarlinPID` | Delay (dead-time) dominant processes |
78-
| `amigofPID` | More universal than ZN_PID (uses a dead time dependency) |
79-
| `pessenIntegralPID` | Similar to ZN_PID but with better dynamic response |
80-
| `someOvershootPID` | ZN_PID with lower proportional and integral gain |
81-
| `noOvershootPID` | ZN_PID with much lower P,I,D gain settings |
76+
| Open Loop Tuning Methods | Description |
77+
| ------------------------ | ------------------------------------------------------------ |
78+
| `ZN_PID` | Open loop Ziegler-Nichols method with ¼ decay ratio |
79+
| `ZN_Half_PID` | Same as `ZN_PID` but with all constants cut in half |
80+
| `Damped_PID` | Can solve marginal stability issues |
81+
| `NoOvershoot_PID` | Uses C-H-R method (set point tracking) with 0% overshoot |
82+
| `CohenCoon_PID` | Open loop method approximates closed loop response with a ¼ decay ratio |
83+
| `ZN_PI` | Open loop Ziegler-Nichols method with ¼ decay ratio |
84+
| `ZN_Half_PI` | Same as `ZN_PID` but with all constants cut in half |
85+
| `Damped_PI` | Can solve marginal stability issues |
86+
| `NoOvershoot_PI` | Uses C-H-R method (set point tracking) with 0% overshoot |
87+
| `CohenCoon_PI` | Open loop method approximates closed loop response with a ¼ decay ratio |
8288

8389
| Serial Mode | Description |
8490
| --------------- | ------------------------------------------------------------ |
@@ -92,35 +98,35 @@ sTune(float *input, float *output, TuningRule tuningRule, Action action, SerialM
9298
#### Instantiate sTune
9399

94100
```c++
95-
sTune tuner = sTune(&Input, &Output, tuner.zieglerNicholsPID, tuner.directIP, tuner.printALL);
96-
/* zieglerNicholsPI directIP serialOFF
97-
zieglerNicholsPID direct5T printALL
98-
tyreusLuybenPI reverseIP printSUMMARY
99-
tyreusLuybenPID reverse5T printDEBUG
100-
cianconeMarlinPI printPIDTUNER
101-
cianconeMarlinPID serialPLOTTER
102-
amigofPID
103-
pessenIntegralPID
104-
someOvershootPID
105-
noOvershootPID
101+
sTune tuner = sTune(&Input, &Output, tuner.ZN_PID, tuner.directIP, tuner.printALL);
102+
/* ZN_PID directIP serialOFF
103+
ZN_Half_PID direct5T printALL
104+
Damped_PID reverseIP printSUMMARY
105+
NoOvershoot_PID reverse5T printDEBUG
106+
CohenCoon_PID printPIDTUNER
107+
ZN_PI serialPLOTTER
108+
ZN_Half_PI
109+
Damped_PI
110+
NoOvershoot_PI
111+
CohenCoon_PI
106112
*/
107113
```
108114

109115
#### Configure
110116

111117
```c++
112-
void Configure(const float outputStart, const float outputStep, const uint32_t testTimeSec, const uint32_t settleTimeSec, const uint16_t samples);
118+
void Configure(const float inputSpan, const float outputSpan, float outputStart, float outputStep,
119+
uint32_t testTimeSec, uint32_t settleTimeSec, const uint16_t samples);
113120
```
114121
115122
This function applies the sTune test settings.
116123
117124
#### Set Functions
118125
119126
```c++
120-
void SetAutoTunings(float * kp, float * ki, float * kd);
121127
void SetControllerAction(Action Action);
122128
void SetSerialMode(SerialMode SerialMode);
123-
void SetTuningRule(TuningRule TuningRule);
129+
void SetTuningMethod(TuningMethod TuningMethod);
124130
```
125131

126132
#### Query Functions
@@ -137,6 +143,7 @@ float GetTimeDerivative(); // process time derivative (seconds)
137143
uint8_t GetControllerAction();
138144
uint8_t GetSerialMode();
139145
uint8_t GetTuningRule();
146+
void GetAutoTunings(float * kp, float * ki, float * kd);
140147
```
141148
142149
#### Controllability of the process
@@ -155,6 +162,7 @@ When the test ends, sTune determines [how difficult](https://blog.opticontrols.c
155162

156163
#### References
157164

165+
- [Comparison of PID Controller Tuning Methods](http://www.ie.tec.ac.cr/einteriano/analisis/clase/13.1.Zomorrodi_Shahrokhi_PID_Tunning_Comparison.pdf)
158166
- [Ziegler-Nichols Open-Loop Tuning Rules](https://blog.opticontrols.com/archives/477)
159167
- [Inflection point](https://en.wikipedia.org/wiki/Inflection_point)
160168
- [Time Constant (Re: Step response with arbitrary initial conditions)](https://en.wikipedia.org/wiki/Time_constant)

examples/Autotune_PID_v1/Autotune_PID_v1.ino

Lines changed: 28 additions & 24 deletions
Original file line numberDiff line numberDiff line change
@@ -1,65 +1,69 @@
11
/********************************************************************
2-
PID_v1 Autotune Example (using Temperature Control Lab)
2+
Autotune PID_v1 Example (using Temperature Control Lab)
33
http://apmonitor.com/pdc/index.php/Main/ArduinoTemperatureControl
44
********************************************************************/
55

66
#include <sTune.h>
77
#include <PID_v1.h>
88

9+
// pins
910
const uint8_t inputPin = 0;
1011
const uint8_t outputPin = 3;
1112

12-
//user settings
13-
const uint32_t testTimeSec = 300;
14-
const float outputStart = 0;
15-
const float outputStep = 20;
13+
// test setup
14+
uint32_t testTimeSec = 300;
1615
const uint16_t samples = 500;
17-
const uint32_t settleTimeSec = 10;
16+
uint32_t settleTimeSec = 10;
17+
const float inputSpan = 80;
18+
const float outputSpan = 255;
19+
float outputStart = 0;
20+
float outputStep = 25;
1821

19-
//input constants
22+
// temperature
2023
const float mvResolution = 3300 / 1024.0f;
2124
const float bias = 50;
2225

23-
double Input = 0, Output = 0, Setpoint = 30; //myPID
24-
float input = 0, output = 0, kp = 0, ki = 0, kd = 0; //tuner
26+
// test variables
27+
double Input = 0, Output = 0, Setpoint = 30; // myPID
28+
float input = 0, output = 0, kp = 0, ki = 0, kd = 0; // tuner
2529

2630
PID myPID(&Input, &Output, &Setpoint, 0, 0, 0, DIRECT);
2731

28-
sTune tuner = sTune(&input, &output, tuner.zieglerNicholsPID, tuner.directIP, tuner.printALL);
29-
/* zieglerNicholsPI directIP serialOFF
30-
zieglerNicholsPID direct5T printALL
31-
tyreusLuybenPI reverseIP printSUMMARY
32-
tyreusLuybenPID reverse5T printDEBUG
33-
cianconeMarlinPI printPIDTUNER
34-
cianconeMarlinPID serialPLOTTER
35-
amigofPID
36-
pessenIntegralPID
37-
someOvershootPID
38-
noOvershootPID
32+
sTune tuner = sTune(&input, &output, tuner.ZN_PID, tuner.directIP, tuner.printALL);
33+
/* ZN_PID directIP serialOFF
34+
ZN_Half_PID direct5T printALL
35+
Damped_PID reverseIP printSUMMARY
36+
NoOvershoot_PID reverse5T printDEBUG
37+
CohenCoon_PID printPIDTUNER
38+
ZN_PI serialPLOTTER
39+
ZN_Half_PI
40+
Damped_PI
41+
NoOvershoot_PI
42+
CohenCoon_PI
3943
*/
4044
void setup() {
4145
analogReference(EXTERNAL); // AVR
4246
Serial.begin(115200);
4347
analogWrite(outputPin, outputStart);
44-
tuner.Configure(outputStart, outputStep, testTimeSec, settleTimeSec, samples);
48+
tuner.Configure(inputSpan, outputSpan, outputStart, outputStep, testTimeSec, settleTimeSec, samples);
4549
}
4650

4751
void loop() {
4852

49-
switch (tuner.Run()) { // active while sTune is testing (non-blocking)
53+
switch (tuner.Run()) { // active while sTune is testing
5054
case tuner.inOut:
5155
input = (analogRead(inputPin) / mvResolution) - bias;
5256
analogWrite(outputPin, output);
5357
break;
5458

5559
case tuner.tunings: // active just once when sTune is done
56-
tuner.SetAutoTunings(&kp, &ki, &kd); // sketch variables are updated by sTune
60+
tuner.GetAutoTunings(&kp, &ki, &kd); // sketch variables updated by sTune
5761
myPID.SetMode(AUTOMATIC); // the PID is turned on (automatic)
5862
myPID.SetSampleTime((testTimeSec * 1000) / samples); // PID sample rate
5963
myPID.SetTunings(kp, ki, kd); // update PID with the new tunings
6064
break;
6165

62-
case tuner.runPid:
66+
case tuner.runPid: // this case runs once per sample period after case "tunings"
6367
Input = (analogRead(inputPin) / mvResolution) - bias;
6468
myPID.Compute();
6569
analogWrite(outputPin, Output);
Lines changed: 76 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,76 @@
1+
/********************************************************************
2+
Autotune Plotter Example (using Temperature Control Lab)
3+
http://apmonitor.com/pdc/index.php/Main/ArduinoTemperatureControl
4+
********************************************************************/
5+
6+
#include <sTune.h>
7+
#include <QuickPID.h>
8+
9+
// pins
10+
const uint8_t inputPin = 0;
11+
const uint8_t outputPin = 3;
12+
13+
// test setup
14+
uint32_t testTimeSec = 300;
15+
const uint16_t samples = 500;
16+
uint32_t settleTimeSec = 10;
17+
const float inputSpan = 80;
18+
const float outputSpan = 255;
19+
float outputStart = 0;
20+
float outputStep = 25;
21+
22+
// temperature
23+
const float mvResolution = 3300 / 1024.0f;
24+
const float bias = 50;
25+
26+
// test variables
27+
float Input = 0, Output = 0, Setpoint = 30, Kp = 0, Ki = 0, Kd = 0;
28+
29+
QuickPID myPID(&Input, &Output, &Setpoint, Kp, Ki, Kd,
30+
myPID.pMode::pOnError,
31+
myPID.dMode::dOnMeas,
32+
myPID.iAwMode::iAwClamp,
33+
myPID.Action::direct);
34+
35+
sTune tuner = sTune(&Input, &Output, tuner.ZN_PID, tuner.directIP, tuner.serialPLOTTER);
36+
/* ZN_PID directIP serialOFF
37+
ZN_Half_PID direct5T printALL
38+
Damped_PID reverseIP printSUMMARY
39+
NoOvershoot_PID reverse5T printDEBUG
40+
CohenCoon_PID printPIDTUNER
41+
ZN_PI serialPLOTTER
42+
ZN_Half_PI
43+
Damped_PI
44+
NoOvershoot_PI
45+
CohenCoon_PI
46+
*/
47+
void setup() {
48+
analogReference(EXTERNAL); // AVR
49+
Serial.begin(115200);
50+
analogWrite(outputPin, outputStart);
51+
tuner.Configure(inputSpan, outputSpan, outputStart, outputStep, testTimeSec, settleTimeSec, samples);
52+
}
53+
54+
void loop() {
55+
switch (tuner.Run()) { // active while sTune is testing
56+
case tuner.inOut:
57+
Input = (analogRead(inputPin) / mvResolution) - bias;
58+
analogWrite(outputPin, Output);
59+
break;
60+
61+
case tuner.tunings: // active just once when sTune is done
62+
tuner.GetAutoTunings(&Kp, &Ki, &Kd); // sketch variables updated by sTune
63+
myPID.SetMode(myPID.Control::automatic); // the PID is turned on (automatic)
64+
myPID.SetSampleTimeUs((testTimeSec * 1000000) / samples); // PID sample rate
65+
myPID.SetTunings(Kp, Ki, Kd); // update PID with the new tunings
66+
break;
67+
68+
case tuner.runPid: // this case runs once per sample period after case "tunings"
69+
Input = (analogRead(inputPin) / mvResolution) - bias;
70+
myPID.Compute();
71+
analogWrite(outputPin, Output);
72+
tuner.plotter(Setpoint, 10); // plots every 10th sample
73+
break;
74+
}
75+
// put your main code here, to run repeatedly
76+
}

0 commit comments

Comments
 (0)