Skip to content

Commit

Permalink
Update
Browse files Browse the repository at this point in the history
Major update
  • Loading branch information
Dlloydev committed Jan 11, 2022
1 parent 937f00b commit 4d6d76c
Show file tree
Hide file tree
Showing 10 changed files with 393 additions and 185 deletions.
66 changes: 37 additions & 29 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -4,13 +4,13 @@ This is an open loop PID autotuner using a novel s-curve inflection point test m

#### Reaction Curve Inflection Point Tuning Method

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.
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.

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

#### Inflection Point Discovery

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.
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).

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.

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

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

- 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.
Expand All @@ -34,6 +34,12 @@ The slope of the tangent line is checked at every sample. When the sign of the c

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

- `inputSpan` and `outputSpan` represent the maximum operating range of input and output. Examples:

- If your input works with temp readings of 20C min and 150C max, then `inputSpan = 130;`
If the output uses 8-bit PWM and your using its full range, then `outputSpan = 255;`
If the output is digital relay controlled by millis() with window period of 2000ms, then `outputSpan = 2000;`

- `outputStart` is the initial control output value which is used for the first 12 samples.

- `outputStep` is the stepped output value used for sample 13 to test completion.
Expand Down Expand Up @@ -67,18 +73,18 @@ sTune(float *input, float *output, TuningRule tuningRule, Action action, SerialM
- `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`.
- `serialMode` provides 6 choices for serial output as described in the table below.

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

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

```c++
sTune tuner = sTune(&Input, &Output, tuner.zieglerNicholsPID, tuner.directIP, tuner.printALL);
/* zieglerNicholsPI directIP serialOFF
zieglerNicholsPID direct5T printALL
tyreusLuybenPI reverseIP printSUMMARY
tyreusLuybenPID reverse5T printDEBUG
cianconeMarlinPI printPIDTUNER
cianconeMarlinPID serialPLOTTER
amigofPID
pessenIntegralPID
someOvershootPID
noOvershootPID
sTune tuner = sTune(&Input, &Output, tuner.ZN_PID, tuner.directIP, tuner.printALL);
/* ZN_PID directIP serialOFF
ZN_Half_PID direct5T printALL
Damped_PID reverseIP printSUMMARY
NoOvershoot_PID reverse5T printDEBUG
CohenCoon_PID printPIDTUNER
ZN_PI serialPLOTTER
ZN_Half_PI
Damped_PI
NoOvershoot_PI
CohenCoon_PI
*/
```

#### Configure

```c++
void Configure(const float outputStart, const float outputStep, const uint32_t testTimeSec, const uint32_t settleTimeSec, const uint16_t samples);
void Configure(const float inputSpan, const float outputSpan, float outputStart, float outputStep,
uint32_t testTimeSec, uint32_t settleTimeSec, const uint16_t samples);
```
This function applies the sTune test settings.
#### Set Functions
```c++
void SetAutoTunings(float * kp, float * ki, float * kd);
void SetControllerAction(Action Action);
void SetSerialMode(SerialMode SerialMode);
void SetTuningRule(TuningRule TuningRule);
void SetTuningMethod(TuningMethod TuningMethod);
```

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

#### References

- [Comparison of PID Controller Tuning Methods](http://www.ie.tec.ac.cr/einteriano/analisis/clase/13.1.Zomorrodi_Shahrokhi_PID_Tunning_Comparison.pdf)
- [Ziegler-Nichols Open-Loop Tuning Rules](https://blog.opticontrols.com/archives/477)
- [Inflection point](https://en.wikipedia.org/wiki/Inflection_point)
- [Time Constant (Re: Step response with arbitrary initial conditions)](https://en.wikipedia.org/wiki/Time_constant)
Expand Down
52 changes: 28 additions & 24 deletions examples/Autotune_PID_v1/Autotune_PID_v1.ino
Original file line number Diff line number Diff line change
@@ -1,65 +1,69 @@
/********************************************************************
PID_v1 Autotune Example (using Temperature Control Lab)
Autotune PID_v1 Example (using Temperature Control Lab)
http://apmonitor.com/pdc/index.php/Main/ArduinoTemperatureControl
********************************************************************/

#include <sTune.h>
#include <PID_v1.h>

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

//user settings
const uint32_t testTimeSec = 300;
const float outputStart = 0;
const float outputStep = 20;
// test setup
uint32_t testTimeSec = 300;
const uint16_t samples = 500;
const uint32_t settleTimeSec = 10;
uint32_t settleTimeSec = 10;
const float inputSpan = 80;
const float outputSpan = 255;
float outputStart = 0;
float outputStep = 25;

//input constants
// temperature
const float mvResolution = 3300 / 1024.0f;
const float bias = 50;

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

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

sTune tuner = sTune(&input, &output, tuner.zieglerNicholsPID, tuner.directIP, tuner.printALL);
/* zieglerNicholsPI directIP serialOFF
zieglerNicholsPID direct5T printALL
tyreusLuybenPI reverseIP printSUMMARY
tyreusLuybenPID reverse5T printDEBUG
cianconeMarlinPI printPIDTUNER
cianconeMarlinPID serialPLOTTER
amigofPID
pessenIntegralPID
someOvershootPID
noOvershootPID
sTune tuner = sTune(&input, &output, tuner.ZN_PID, tuner.directIP, tuner.printALL);
/* ZN_PID directIP serialOFF
ZN_Half_PID direct5T printALL
Damped_PID reverseIP printSUMMARY
NoOvershoot_PID reverse5T printDEBUG
CohenCoon_PID printPIDTUNER
ZN_PI serialPLOTTER
ZN_Half_PI
Damped_PI
NoOvershoot_PI
CohenCoon_PI
*/
void setup() {
analogReference(EXTERNAL); // AVR
Serial.begin(115200);
analogWrite(outputPin, outputStart);
tuner.Configure(outputStart, outputStep, testTimeSec, settleTimeSec, samples);
tuner.Configure(inputSpan, outputSpan, outputStart, outputStep, testTimeSec, settleTimeSec, samples);
}

void loop() {

switch (tuner.Run()) { // active while sTune is testing (non-blocking)
switch (tuner.Run()) { // active while sTune is testing
case tuner.inOut:
input = (analogRead(inputPin) / mvResolution) - bias;
analogWrite(outputPin, output);
break;

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

case tuner.runPid:
case tuner.runPid: // this case runs once per sample period after case "tunings"
Input = (analogRead(inputPin) / mvResolution) - bias;
myPID.Compute();
analogWrite(outputPin, Output);
Expand Down
76 changes: 76 additions & 0 deletions examples/Autotune_Plotter/Autotune_Plotter.ino
Original file line number Diff line number Diff line change
@@ -0,0 +1,76 @@
/********************************************************************
Autotune Plotter Example (using Temperature Control Lab)
http://apmonitor.com/pdc/index.php/Main/ArduinoTemperatureControl
********************************************************************/

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

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

// test setup
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;

// temperature
const float mvResolution = 3300 / 1024.0f;
const float bias = 50;

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

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.serialPLOTTER);
/* ZN_PID directIP serialOFF
ZN_Half_PID direct5T printALL
Damped_PID reverseIP printSUMMARY
NoOvershoot_PID reverse5T printDEBUG
CohenCoon_PID printPIDTUNER
ZN_PI serialPLOTTER
ZN_Half_PI
Damped_PI
NoOvershoot_PI
CohenCoon_PI
*/
void setup() {
analogReference(EXTERNAL); // AVR
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;
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.SetMode(myPID.Control::automatic); // the PID is turned on (automatic)
myPID.SetSampleTimeUs((testTimeSec * 1000000) / samples); // PID sample rate
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);
tuner.plotter(Setpoint, 10); // plots every 10th sample
break;
}
// put your main code here, to run repeatedly
}
Loading

0 comments on commit 4d6d76c

Please sign in to comment.