Skip to content

Commit

Permalink
Update
Browse files Browse the repository at this point in the history
- 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
  • Loading branch information
Dlloydev committed Jan 22, 2022
1 parent 1630ba7 commit 936204e
Show file tree
Hide file tree
Showing 11 changed files with 185 additions and 160 deletions.
13 changes: 7 additions & 6 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,7 @@ This tuning method determines the process gain, dead time, time constant and mor

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

- [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)
- [Autotune Digital Output](https://github.com/Dlloydev/sTune/wiki/Autotune_PID_Digital_Out_Reference)
- [Get_All_Tunings](https://github.com/Dlloydev/sTune/wiki/Get_All_Tunings)
- [plotter function reference](https://github.com/Dlloydev/sTune/wiki/plotter-function-reference)

Expand Down Expand Up @@ -102,11 +102,11 @@ sTune(float *input, float *output, TuningRule tuningRule, Action action, SerialM
#### Instantiate sTune

```c++
sTune tuner = sTune(&Input, &Output, tuner.Mixed_PID, tuner.directIP, tuner.printALL);
/* ZN_PID directIP serialOFF
DampedOsc_PID direct5T printALL
NoOvershoot_PID reverseIP printSUMMARY
CohenCoon_PID reverse5T printDEBUG
sTune tuner = sTune(&Input, &Output, tuner.ZN_PID, tuner.directIP, tuner.printALL);
/* ZN_PID directIP serialOFF
DampedOsc_PID direct5T printALL
NoOvershoot_PID reverseIP printSUMMARY
CohenCoon_PID reverse5T printDEBUG
Mixed_PID
ZN_PI
DampedOsc_PI
Expand All @@ -128,6 +128,7 @@ This function applies the sTune test settings.
#### Set Functions
```c++
void SetEmergencyStop(float e_Stop);
void SetControllerAction(Action Action);
void SetSerialMode(SerialMode SerialMode);
void SetTuningMethod(TuningMethod TuningMethod);
Expand Down
108 changes: 62 additions & 46 deletions examples/Autotune_PID_Digital_Out/Autotune_PID_Digital_Out.ino
Original file line number Diff line number Diff line change
@@ -1,42 +1,53 @@
/****************************************************************************
Autotune QuickPID Digital Output Example
https://github.com/Dlloydev/sTune/wiki/Autotune_PID_Digital_Out_Reference
Autotune QuickPID Digital Output Example
https://github.com/Dlloydev/sTune/wiki/Autotune_PID_Digital_Out_Reference
The output is a digital pin controlling a mechanical relay, SSR, MOSFET or
other device. To interface the PID output to the digital pin, we use
software PWM. The PID compute rate controls the output update rate. All
transitions are debounced and there's only one call to digitalWrite()
per transition.
This sketch runs sTune then applies the tunings to QuickPID. Open the
serial plotter to view the input response through the complete tuning and
PID control process.
****************************************************************************/

#include <sTune.h>
#include <QuickPID.h>

// pins
const uint8_t inputPin = 0;
const uint8_t outputPin = 3;
const uint8_t ledPin = 9;

// test setup
uint32_t testTimeSec = 600; // testTimeSec / samples = sample interval
const uint16_t samples = 300;
const uint8_t relayPin = 3;

// user settings (sTune)
uint32_t settleTimeSec = 15;
uint32_t testTimeSec = 300;
const uint16_t samples = 300;
const float inputSpan = 80;
const float outputSpan = 2000; // window size for sTune and PID
const float minSpan = 50;
const float outputSpan = (testTimeSec / samples) * 1000;
float outputStart = 0;
float outputStep = 200;
bool clearPidOutput = false; // false: "on the fly" testing, true: PID starts at 0 output
float outputStep = 100;

// temperature
const float mvResolution = 3300 / 1024.0f;
const float bias = 50;
// user settings (PID)
float Setpoint = 30;
const float windowSize = 5000;
const byte debounce = 50;

// status
unsigned long windowStartTime, nextSwitchTime, msNow;
boolean relayStatus = false;

// variables
float Input, Output, Setpoint = 30, Kp, Ki, Kd;
float Input, Output, Kp, Ki, Kd;

QuickPID myPID(&Input, &Output, &Setpoint, Kp, Ki, Kd,
myPID.pMode::pOnError,
myPID.dMode::dOnMeas,
myPID.iAwMode::iAwClamp,
myPID.Action::direct);

sTune tuner = sTune(&Input, &Output, tuner.ZN_PID, tuner.directIP, tuner.printALL);
sTune tuner = sTune(&Input, &Output, tuner.ZN_PID, tuner.directIP, tuner.printOFF);
/* ZN_PID directIP printOFF
DampedOsc_PID direct5T printALL
NoOvershoot_PID reverseIP printSUMMARY
Expand All @@ -49,49 +60,54 @@ sTune tuner = sTune(&Input, &Output, tuner.ZN_PID, tuner.directIP, tuner.printAL
Mixed_PI
*/
void setup() {
pinMode(outputPin, OUTPUT);
pinMode(ledPin, OUTPUT);
digitalWrite(outputPin, LOW);
analogReference(EXTERNAL); // used by TCLab
Serial.begin(115200);
pinMode(relayPin, OUTPUT);
pinMode(LED_BUILTIN, OUTPUT);
tuner.Configure(inputSpan, outputSpan, outputStart, outputStep, testTimeSec, settleTimeSec, samples);
}

void loop() {
softPwmOutput();
switch (tuner.Run()) {
case tuner.inOut: // active while sTune is testing
Input = (analogRead(inputPin) / mvResolution) - bias;
case tuner.sample: // active once per sample during test
windowStartTime = msNow;
Input = analogRead(inputPin);
tuner.plotter(Setpoint, 0.05, 5, 1); // scaled output, every 5th sample, averaged input
break;
case tuner.tunings: // active just once when sTune is done
tuner.GetAutoTunings(&Kp, &Ki, &Kd); // sketch variables updated by sTune
myPID.SetOutputLimits(0, outputSpan); // PID output spans from 0 to the full window size
myPID.SetSampleTimeUs(outputSpan * 1000); // PID sample rate matches sTune
if (clearPidOutput) Output = 0;
myPID.SetMode(myPID.Control::automatic); // the PID is turned on (automatic)
myPID.SetTunings(Kp, Ki, Kd); // update PID with the new tunings

case tuner.tunings: // active just once when sTune is done
tuner.GetAutoTunings(&Kp, &Ki, &Kd); // sketch variables updated by sTune
myPID.SetOutputLimits(0, windowSize);
myPID.SetSampleTimeUs(windowSize * 1000);
// Output = 0; // optional output preset value
myPID.SetMode(myPID.Control::automatic); // the PID is turned on
myPID.SetTunings(Kp, Ki, Kd); // update PID with the new tunings
break;
case tuner.runPid: // active once per sample period after case "tunings"
Input = (analogRead(inputPin) / mvResolution) - bias;
myPID.Compute();
tuner.plotter(Setpoint, 0.1, 5, 1); // scaled output, every 5th sample, averaged input

case tuner.runPid: // active once per sample after tunings
tuner.plotter(Setpoint, 0.05, 5, 1);
break;
}
// put your main code here, to run repeatedly
msNow = millis();
softPwmOutput();
Input = analogRead(inputPin);
if (myPID.Compute()) windowStartTime = msNow;
}

void softPwmOutput() {
static uint32_t tPrev;
uint32_t tNow = millis();
uint32_t tElapsed = (tNow - tPrev);
if (tElapsed >= outputSpan) tPrev = tNow;
if (tElapsed > minSpan && tElapsed < outputSpan - minSpan) { // in range?
if (tElapsed <= Output) {
digitalWrite(outputPin, HIGH);
digitalWrite(ledPin, HIGH);
} else {
digitalWrite(outputPin, LOW);
digitalWrite(ledPin, LOW);
if (!relayStatus && Output > (msNow - windowStartTime)) {
if (msNow > nextSwitchTime) {
nextSwitchTime = msNow + debounce;
relayStatus = true;
digitalWrite(relayPin, HIGH);
digitalWrite(LED_BUILTIN, HIGH);
}
} else if (relayStatus && Output < (msNow - windowStartTime)) {
if (msNow > nextSwitchTime) {
nextSwitchTime = msNow + debounce;
relayStatus = false;
digitalWrite(relayPin, LOW);
digitalWrite(LED_BUILTIN, LOW);
}
}
}
57 changes: 28 additions & 29 deletions examples/Autotune_PID_v1/Autotune_PID_v1.ino
Original file line number Diff line number Diff line change
@@ -1,6 +1,8 @@
/********************************************************************
Autotune PID_v1 Example (using Temperature Control Lab)
http://apmonitor.com/pdc/index.php/Main/ArduinoTemperatureControl
Autotune PID_v1 Example
This sketch runs sTune then applies the tunings to PID_v1. Open
the serial printer to view the test progress and results.
********************************************************************/

#include <sTune.h>
Expand All @@ -10,27 +12,25 @@
const uint8_t inputPin = 0;
const uint8_t outputPin = 3;

// test setup
// user settings (sTune)
uint32_t settleTimeSec = 15;
uint32_t testTimeSec = 300;
const uint16_t samples = 500;
uint32_t settleTimeSec = 10;
const float inputSpan = 80;
const float outputSpan = 255;
float outputStart = 0;
float outputStep = 25;
bool clearPidOutput = false; // false: "on the fly" testing, true: PID starts at 0 output

// temperature
const float mvResolution = 3300 / 1024.0f;
const float bias = 50;
// user settings (PID)
double Setpoint = 30;

// test variables
double Input = 0, Output = 0, Setpoint = 30; // myPID
float input = 0, output = 0, kp = 0, ki = 0, kd = 0; // tuner
// variables
double Input, Output; // PID
float input, output, kp, ki, kd; // sTune

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

sTune tuner = sTune(&input, &output, tuner.Mixed_PID, tuner.directIP, tuner.printALL);
sTune tuner = sTune(&input, &output, tuner.ZN_PID, tuner.directIP, tuner.printALL);
/* ZN_PID directIP serialOFF
DampedOsc_PID direct5T printALL
NoOvershoot_PID reverseIP printSUMMARY
Expand All @@ -43,33 +43,32 @@ sTune tuner = sTune(&input, &output, tuner.Mixed_PID, tuner.directIP, tuner.prin
Mixed_PI
*/
void setup() {
analogReference(EXTERNAL); // used by TCLab
Serial.begin(115200);
analogWrite(outputPin, outputStart);
tuner.Configure(inputSpan, outputSpan, outputStart, outputStep, testTimeSec, settleTimeSec, samples);
}

void loop() {

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

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

case tuner.runPid: // this case runs once per sample period after case "tunings"
Input = (analogRead(inputPin) / mvResolution) - bias;
myPID.Compute();
analogWrite(outputPin, Output);
break;
}
// put your main code here, to run repeatedly
case tuner.runPid: // active once per sample after tunings
Input = analogRead(inputPin);
myPID.Compute();
analogWrite(outputPin, Output);
break;
}
// put your main code here, to run repeatedly
}
49 changes: 25 additions & 24 deletions examples/Autotune_Plotter/Autotune_Plotter.ino
Original file line number Diff line number Diff line change
@@ -1,6 +1,9 @@
/********************************************************************
Autotune Plotter Example (using Temperature Control Lab)
http://apmonitor.com/pdc/index.php/Main/ArduinoTemperatureControl
Autotune Plotter Example
This sketch runs sTune then applies the tunings to QuickPID. Open
the serial plotter to view the input response through the complete
tuning and PID control process.
********************************************************************/

#include <sTune.h>
Expand All @@ -10,30 +13,28 @@
const uint8_t inputPin = 0;
const uint8_t outputPin = 3;

// test setup
// user settings (sTune)
uint32_t settleTimeSec = 10;
uint32_t testTimeSec = 300;
const uint16_t samples = 500;
uint32_t settleTimeSec = 10;
const float inputSpan = 80;
const float outputSpan = 255;
float outputStart = 0;
float outputStep = 25;
bool clearPidOutput = false; // false: "on the fly" testing, true: PID starts at 0 output

// temperature
const float mvResolution = 3300 / 1024.0f;
const float bias = 50;
// user settings (PID)
float Setpoint = 30;

// test variables
float Input = 0, Output = 0, Setpoint = 30, Kp = 0, Ki = 0, Kd = 0;
// variables
float Input, Output, Kp, Ki, Kd;

QuickPID myPID(&Input, &Output, &Setpoint, Kp, Ki, Kd,
myPID.pMode::pOnError,
myPID.dMode::dOnMeas,
myPID.iAwMode::iAwClamp,
myPID.Action::direct);

sTune tuner = sTune(&Input, &Output, tuner.Mixed_PID, tuner.directIP, tuner.printALL);
sTune tuner = sTune(&Input, &Output, tuner.ZN_PID, tuner.directIP, tuner.printOFF);
/* ZN_PID directIP serialOFF
DampedOsc_PID direct5T printALL
NoOvershoot_PID reverseIP printSUMMARY
Expand All @@ -46,32 +47,32 @@ sTune tuner = sTune(&Input, &Output, tuner.Mixed_PID, tuner.directIP, tuner.prin
Mixed_PI
*/
void setup() {
analogReference(EXTERNAL); // used by TCLab
Serial.begin(115200);
analogWrite(outputPin, outputStart);
tuner.Configure(inputSpan, outputSpan, outputStart, outputStep, testTimeSec, settleTimeSec, samples);
}

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

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

case tuner.runPid: // this case runs once per sample period after case "tunings"
Input = (analogRead(inputPin) / mvResolution) - bias;
case tuner.runPid: // active once per sample after tunings
Input = analogRead(inputPin);
myPID.Compute();
analogWrite(outputPin, Output);
tuner.plotter(Setpoint, 0.5, 6, 1); // plot output scaled 0.5, plot every 6th sample, plot averaged input
tuner.plotter(Setpoint, 0.5, 6, 1);
break;
}
// put your main code here, to run repeatedly
Expand Down
Loading

0 comments on commit 936204e

Please sign in to comment.