Skip to content

Commit 936204e

Browse files
committed
Update
- Added emergency stop function where the test is stopped and output cleared to 0 if the input exceeds 10% (default) over the input span. This function allows the user to adjust the eStop limit. - `inOut` switch case renamed to `sample` as it now is active once per sample period - Updated `Autotune_PID_Digital_Out` example for software PWM relay control - Updated examples and documentation
1 parent 1630ba7 commit 936204e

File tree

11 files changed

+185
-160
lines changed

11 files changed

+185
-160
lines changed

README.md

Lines changed: 7 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -8,7 +8,7 @@ This tuning method determines the process gain, dead time, time constant and mor
88

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

11-
- [Autotune Digital Output](https://github.com/Dlloydev/sTune/wiki/Autotune_PID_Digital_Out_Reference) ![image](https://user-images.githubusercontent.com/63488701/149647496-f4459516-a483-469e-af1e-90a54fbd909e.png)
11+
- [Autotune Digital Output](https://github.com/Dlloydev/sTune/wiki/Autotune_PID_Digital_Out_Reference)
1212
- [Get_All_Tunings](https://github.com/Dlloydev/sTune/wiki/Get_All_Tunings)
1313
- [plotter function reference](https://github.com/Dlloydev/sTune/wiki/plotter-function-reference)
1414

@@ -102,11 +102,11 @@ sTune(float *input, float *output, TuningRule tuningRule, Action action, SerialM
102102
#### Instantiate sTune
103103

104104
```c++
105-
sTune tuner = sTune(&Input, &Output, tuner.Mixed_PID, tuner.directIP, tuner.printALL);
106-
/* ZN_PID directIP serialOFF
107-
DampedOsc_PID direct5T printALL
108-
NoOvershoot_PID reverseIP printSUMMARY
109-
CohenCoon_PID reverse5T printDEBUG
105+
sTune tuner = sTune(&Input, &Output, tuner.ZN_PID, tuner.directIP, tuner.printALL);
106+
/* ZN_PID directIP serialOFF
107+
DampedOsc_PID direct5T printALL
108+
NoOvershoot_PID reverseIP printSUMMARY
109+
CohenCoon_PID reverse5T printDEBUG
110110
Mixed_PID
111111
ZN_PI
112112
DampedOsc_PI
@@ -128,6 +128,7 @@ This function applies the sTune test settings.
128128
#### Set Functions
129129
130130
```c++
131+
void SetEmergencyStop(float e_Stop);
131132
void SetControllerAction(Action Action);
132133
void SetSerialMode(SerialMode SerialMode);
133134
void SetTuningMethod(TuningMethod TuningMethod);
Lines changed: 62 additions & 46 deletions
Original file line numberDiff line numberDiff line change
@@ -1,42 +1,53 @@
11
/****************************************************************************
2-
Autotune QuickPID Digital Output Example
3-
https://github.com/Dlloydev/sTune/wiki/Autotune_PID_Digital_Out_Reference
2+
Autotune QuickPID Digital Output Example
3+
https://github.com/Dlloydev/sTune/wiki/Autotune_PID_Digital_Out_Reference
4+
5+
The output is a digital pin controlling a mechanical relay, SSR, MOSFET or
6+
other device. To interface the PID output to the digital pin, we use
7+
software PWM. The PID compute rate controls the output update rate. All
8+
transitions are debounced and there's only one call to digitalWrite()
9+
per transition.
10+
11+
This sketch runs sTune then applies the tunings to QuickPID. Open the
12+
serial plotter to view the input response through the complete tuning and
13+
PID control process.
414
****************************************************************************/
515

616
#include <sTune.h>
717
#include <QuickPID.h>
818

919
// pins
1020
const uint8_t inputPin = 0;
11-
const uint8_t outputPin = 3;
12-
const uint8_t ledPin = 9;
13-
14-
// test setup
15-
uint32_t testTimeSec = 600; // testTimeSec / samples = sample interval
16-
const uint16_t samples = 300;
21+
const uint8_t relayPin = 3;
1722

23+
// user settings (sTune)
1824
uint32_t settleTimeSec = 15;
25+
uint32_t testTimeSec = 300;
26+
const uint16_t samples = 300;
1927
const float inputSpan = 80;
20-
const float outputSpan = 2000; // window size for sTune and PID
21-
const float minSpan = 50;
28+
const float outputSpan = (testTimeSec / samples) * 1000;
2229
float outputStart = 0;
23-
float outputStep = 200;
24-
bool clearPidOutput = false; // false: "on the fly" testing, true: PID starts at 0 output
30+
float outputStep = 100;
2531

26-
// temperature
27-
const float mvResolution = 3300 / 1024.0f;
28-
const float bias = 50;
32+
// user settings (PID)
33+
float Setpoint = 30;
34+
const float windowSize = 5000;
35+
const byte debounce = 50;
36+
37+
// status
38+
unsigned long windowStartTime, nextSwitchTime, msNow;
39+
boolean relayStatus = false;
2940

3041
// variables
31-
float Input, Output, Setpoint = 30, Kp, Ki, Kd;
42+
float Input, Output, Kp, Ki, Kd;
3243

3344
QuickPID myPID(&Input, &Output, &Setpoint, Kp, Ki, Kd,
3445
myPID.pMode::pOnError,
3546
myPID.dMode::dOnMeas,
3647
myPID.iAwMode::iAwClamp,
3748
myPID.Action::direct);
3849

39-
sTune tuner = sTune(&Input, &Output, tuner.ZN_PID, tuner.directIP, tuner.printALL);
50+
sTune tuner = sTune(&Input, &Output, tuner.ZN_PID, tuner.directIP, tuner.printOFF);
4051
/* ZN_PID directIP printOFF
4152
DampedOsc_PID direct5T printALL
4253
NoOvershoot_PID reverseIP printSUMMARY
@@ -49,49 +60,54 @@ sTune tuner = sTune(&Input, &Output, tuner.ZN_PID, tuner.directIP, tuner.printAL
4960
Mixed_PI
5061
*/
5162
void setup() {
52-
pinMode(outputPin, OUTPUT);
53-
pinMode(ledPin, OUTPUT);
54-
digitalWrite(outputPin, LOW);
55-
analogReference(EXTERNAL); // used by TCLab
5663
Serial.begin(115200);
64+
pinMode(relayPin, OUTPUT);
65+
pinMode(LED_BUILTIN, OUTPUT);
5766
tuner.Configure(inputSpan, outputSpan, outputStart, outputStep, testTimeSec, settleTimeSec, samples);
5867
}
5968

6069
void loop() {
61-
softPwmOutput();
6270
switch (tuner.Run()) {
63-
case tuner.inOut: // active while sTune is testing
64-
Input = (analogRead(inputPin) / mvResolution) - bias;
71+
case tuner.sample: // active once per sample during test
72+
windowStartTime = msNow;
73+
Input = analogRead(inputPin);
74+
tuner.plotter(Setpoint, 0.05, 5, 1); // scaled output, every 5th sample, averaged input
6575
break;
66-
case tuner.tunings: // active just once when sTune is done
67-
tuner.GetAutoTunings(&Kp, &Ki, &Kd); // sketch variables updated by sTune
68-
myPID.SetOutputLimits(0, outputSpan); // PID output spans from 0 to the full window size
69-
myPID.SetSampleTimeUs(outputSpan * 1000); // PID sample rate matches sTune
70-
if (clearPidOutput) Output = 0;
71-
myPID.SetMode(myPID.Control::automatic); // the PID is turned on (automatic)
72-
myPID.SetTunings(Kp, Ki, Kd); // update PID with the new tunings
76+
77+
case tuner.tunings: // active just once when sTune is done
78+
tuner.GetAutoTunings(&Kp, &Ki, &Kd); // sketch variables updated by sTune
79+
myPID.SetOutputLimits(0, windowSize);
80+
myPID.SetSampleTimeUs(windowSize * 1000);
81+
// Output = 0; // optional output preset value
82+
myPID.SetMode(myPID.Control::automatic); // the PID is turned on
83+
myPID.SetTunings(Kp, Ki, Kd); // update PID with the new tunings
7384
break;
74-
case tuner.runPid: // active once per sample period after case "tunings"
75-
Input = (analogRead(inputPin) / mvResolution) - bias;
76-
myPID.Compute();
77-
tuner.plotter(Setpoint, 0.1, 5, 1); // scaled output, every 5th sample, averaged input
85+
86+
case tuner.runPid: // active once per sample after tunings
87+
tuner.plotter(Setpoint, 0.05, 5, 1);
7888
break;
7989
}
8090
// put your main code here, to run repeatedly
91+
msNow = millis();
92+
softPwmOutput();
93+
Input = analogRead(inputPin);
94+
if (myPID.Compute()) windowStartTime = msNow;
8195
}
8296

8397
void softPwmOutput() {
84-
static uint32_t tPrev;
85-
uint32_t tNow = millis();
86-
uint32_t tElapsed = (tNow - tPrev);
87-
if (tElapsed >= outputSpan) tPrev = tNow;
88-
if (tElapsed > minSpan && tElapsed < outputSpan - minSpan) { // in range?
89-
if (tElapsed <= Output) {
90-
digitalWrite(outputPin, HIGH);
91-
digitalWrite(ledPin, HIGH);
92-
} else {
93-
digitalWrite(outputPin, LOW);
94-
digitalWrite(ledPin, LOW);
98+
if (!relayStatus && Output > (msNow - windowStartTime)) {
99+
if (msNow > nextSwitchTime) {
100+
nextSwitchTime = msNow + debounce;
101+
relayStatus = true;
102+
digitalWrite(relayPin, HIGH);
103+
digitalWrite(LED_BUILTIN, HIGH);
104+
}
105+
} else if (relayStatus && Output < (msNow - windowStartTime)) {
106+
if (msNow > nextSwitchTime) {
107+
nextSwitchTime = msNow + debounce;
108+
relayStatus = false;
109+
digitalWrite(relayPin, LOW);
110+
digitalWrite(LED_BUILTIN, LOW);
95111
}
96112
}
97113
}
Lines changed: 28 additions & 29 deletions
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,8 @@
11
/********************************************************************
2-
Autotune PID_v1 Example (using Temperature Control Lab)
3-
http://apmonitor.com/pdc/index.php/Main/ArduinoTemperatureControl
2+
Autotune PID_v1 Example
3+
4+
This sketch runs sTune then applies the tunings to PID_v1. Open
5+
the serial printer to view the test progress and results.
46
********************************************************************/
57

68
#include <sTune.h>
@@ -10,27 +12,25 @@
1012
const uint8_t inputPin = 0;
1113
const uint8_t outputPin = 3;
1214

13-
// test setup
15+
// user settings (sTune)
16+
uint32_t settleTimeSec = 15;
1417
uint32_t testTimeSec = 300;
1518
const uint16_t samples = 500;
16-
uint32_t settleTimeSec = 10;
1719
const float inputSpan = 80;
1820
const float outputSpan = 255;
1921
float outputStart = 0;
2022
float outputStep = 25;
21-
bool clearPidOutput = false; // false: "on the fly" testing, true: PID starts at 0 output
2223

23-
// temperature
24-
const float mvResolution = 3300 / 1024.0f;
25-
const float bias = 50;
24+
// user settings (PID)
25+
double Setpoint = 30;
2626

27-
// test variables
28-
double Input = 0, Output = 0, Setpoint = 30; // myPID
29-
float input = 0, output = 0, kp = 0, ki = 0, kd = 0; // tuner
27+
// variables
28+
double Input, Output; // PID
29+
float input, output, kp, ki, kd; // sTune
3030

3131
PID myPID(&Input, &Output, &Setpoint, 0, 0, 0, DIRECT);
3232

33-
sTune tuner = sTune(&input, &output, tuner.Mixed_PID, tuner.directIP, tuner.printALL);
33+
sTune tuner = sTune(&input, &output, tuner.ZN_PID, tuner.directIP, tuner.printALL);
3434
/* ZN_PID directIP serialOFF
3535
DampedOsc_PID direct5T printALL
3636
NoOvershoot_PID reverseIP printSUMMARY
@@ -43,33 +43,32 @@ sTune tuner = sTune(&input, &output, tuner.Mixed_PID, tuner.directIP, tuner.prin
4343
Mixed_PI
4444
*/
4545
void setup() {
46-
analogReference(EXTERNAL); // used by TCLab
4746
Serial.begin(115200);
4847
analogWrite(outputPin, outputStart);
4948
tuner.Configure(inputSpan, outputSpan, outputStart, outputStep, testTimeSec, settleTimeSec, samples);
5049
}
5150

5251
void loop() {
5352

54-
switch (tuner.Run()) { // active while sTune is testing
55-
case tuner.inOut:
56-
input = (analogRead(inputPin) / mvResolution) - bias;
53+
switch (tuner.Run()) {
54+
case tuner.sample: // active once per sample during test
55+
Input = analogRead(inputPin);
5756
analogWrite(outputPin, output);
5857
break;
5958

60-
case tuner.tunings: // active just once when sTune is done
61-
tuner.GetAutoTunings(&kp, &ki, &kd); // sketch variables updated by sTune
62-
myPID.SetSampleTime((testTimeSec * 1000) / samples); // PID sample rate
63-
if (clearPidOutput) Output = 0;
64-
myPID.SetMode(AUTOMATIC); // the PID is turned on (automatic)
65-
myPID.SetTunings(kp, ki, kd); // update PID with the new tunings
59+
case tuner.tunings: // active just once when sTune is done
60+
tuner.GetAutoTunings(&kp, &ki, &kd); // sketch variables updated by sTune
61+
myPID.SetSampleTime((testTimeSec * 1000) / samples); // PID sample rate
62+
// Output = 0; // optional output preset value
63+
myPID.SetMode(AUTOMATIC); // the PID is turned on
64+
myPID.SetTunings(kp, ki, kd); // update PID with the new tunings
6665
break;
6766

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-
break;
73-
}
74-
// put your main code here, to run repeatedly
67+
case tuner.runPid: // active once per sample after tunings
68+
Input = analogRead(inputPin);
69+
myPID.Compute();
70+
analogWrite(outputPin, Output);
71+
break;
72+
}
73+
// put your main code here, to run repeatedly
7574
}

examples/Autotune_Plotter/Autotune_Plotter.ino

Lines changed: 25 additions & 24 deletions
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,9 @@
11
/********************************************************************
2-
Autotune Plotter Example (using Temperature Control Lab)
3-
http://apmonitor.com/pdc/index.php/Main/ArduinoTemperatureControl
2+
Autotune Plotter Example
3+
4+
This sketch runs sTune then applies the tunings to QuickPID. Open
5+
the serial plotter to view the input response through the complete
6+
tuning and PID control process.
47
********************************************************************/
58

69
#include <sTune.h>
@@ -10,30 +13,28 @@
1013
const uint8_t inputPin = 0;
1114
const uint8_t outputPin = 3;
1215

13-
// test setup
16+
// user settings (sTune)
17+
uint32_t settleTimeSec = 10;
1418
uint32_t testTimeSec = 300;
1519
const uint16_t samples = 500;
16-
uint32_t settleTimeSec = 10;
1720
const float inputSpan = 80;
1821
const float outputSpan = 255;
1922
float outputStart = 0;
2023
float outputStep = 25;
21-
bool clearPidOutput = false; // false: "on the fly" testing, true: PID starts at 0 output
2224

23-
// temperature
24-
const float mvResolution = 3300 / 1024.0f;
25-
const float bias = 50;
25+
// user settings (PID)
26+
float Setpoint = 30;
2627

27-
// test variables
28-
float Input = 0, Output = 0, Setpoint = 30, Kp = 0, Ki = 0, Kd = 0;
28+
// variables
29+
float Input, Output, Kp, Ki, Kd;
2930

3031
QuickPID myPID(&Input, &Output, &Setpoint, Kp, Ki, Kd,
3132
myPID.pMode::pOnError,
3233
myPID.dMode::dOnMeas,
3334
myPID.iAwMode::iAwClamp,
3435
myPID.Action::direct);
3536

36-
sTune tuner = sTune(&Input, &Output, tuner.Mixed_PID, tuner.directIP, tuner.printALL);
37+
sTune tuner = sTune(&Input, &Output, tuner.ZN_PID, tuner.directIP, tuner.printOFF);
3738
/* ZN_PID directIP serialOFF
3839
DampedOsc_PID direct5T printALL
3940
NoOvershoot_PID reverseIP printSUMMARY
@@ -46,32 +47,32 @@ sTune tuner = sTune(&Input, &Output, tuner.Mixed_PID, tuner.directIP, tuner.prin
4647
Mixed_PI
4748
*/
4849
void setup() {
49-
analogReference(EXTERNAL); // used by TCLab
5050
Serial.begin(115200);
5151
analogWrite(outputPin, outputStart);
5252
tuner.Configure(inputSpan, outputSpan, outputStart, outputStep, testTimeSec, settleTimeSec, samples);
5353
}
5454

5555
void loop() {
56-
switch (tuner.Run()) { // active while sTune is testing
57-
case tuner.inOut:
58-
Input = (analogRead(inputPin) / mvResolution) - bias;
56+
switch (tuner.Run()) {
57+
case tuner.sample: // active once per sample during test
58+
Input = analogRead(inputPin);
5959
analogWrite(outputPin, Output);
60+
tuner.plotter(Setpoint, 0.5, 6, 1); // output scaled 0.5, plot every 6th sample, averaged input
6061
break;
6162

62-
case tuner.tunings: // active just once when sTune is done
63-
tuner.GetAutoTunings(&Kp, &Ki, &Kd); // sketch variables updated by sTune
64-
myPID.SetSampleTimeUs((testTimeSec * 1000000) / samples); // PID sample rate (same as sTune)
65-
if (clearPidOutput) Output = 0;
66-
myPID.SetMode(myPID.Control::automatic); // the PID is turned on (automatic)
67-
myPID.SetTunings(Kp, Ki, Kd); // update PID with the new tunings
63+
case tuner.tunings: // active just once when sTune is done
64+
tuner.GetAutoTunings(&Kp, &Ki, &Kd); // sketch variables updated by sTune
65+
myPID.SetSampleTimeUs((testTimeSec / samples) * 1000000);
66+
// Output = 0; // optional output preset value
67+
myPID.SetMode(myPID.Control::automatic); // the PID is turned on
68+
myPID.SetTunings(Kp, Ki, Kd); // update PID with the new tunings
6869
break;
6970

70-
case tuner.runPid: // this case runs once per sample period after case "tunings"
71-
Input = (analogRead(inputPin) / mvResolution) - bias;
71+
case tuner.runPid: // active once per sample after tunings
72+
Input = analogRead(inputPin);
7273
myPID.Compute();
7374
analogWrite(outputPin, Output);
74-
tuner.plotter(Setpoint, 0.5, 6, 1); // plot output scaled 0.5, plot every 6th sample, plot averaged input
75+
tuner.plotter(Setpoint, 0.5, 6, 1);
7576
break;
7677
}
7778
// put your main code here, to run repeatedly

0 commit comments

Comments
 (0)