Skip to content

Commit ab8da72

Browse files
committed
QuickPID 2.2.0
Includes enhanced AutoTune, 8 tuning rules to choose from and GetKu() and GetTu() display functions.
1 parent d20a0ca commit ab8da72

File tree

7 files changed

+209
-174
lines changed

7 files changed

+209
-174
lines changed

QuickPID.cpp

Lines changed: 133 additions & 98 deletions
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,5 @@
11
/**********************************************************************************
2-
QuickPID Library for Arduino - Version 2.1.0
2+
QuickPID Library for Arduino - Version 2.2.0
33
by dlloydev https://github.com/Dlloydev/QuickPID
44
Based on the Arduino PID Library by Brett Beauregard
55
@@ -79,84 +79,78 @@ bool QuickPID::Compute()
7979

8080
/* AutoTune(...)***************************************************************************
8181
This function uses the Relay Method to tune the loop without operator intervention.
82-
It determines the critical gain (Ku) and critical period (Tu) which is used in the
82+
It determines the ultimate gain (Ku) and ultimate period (Tu) which is used in the
8383
Ziegler-Nichols tuning rules to compute Kp, Ki and Kd.
8484
******************************************************************************************/
85-
void QuickPID::AutoTune(int inputPin, int outputPin, int tuningRule, int Print = 0, uint32_t timeout = 30) {
86-
const byte outputStep = 2; // ±2 = span of 4
87-
const byte hysteresis = 1; // ±1 = span of 2
88-
89-
static uint32_t stepPrevTime, stepTime;
90-
int peakHigh = 341, peakLow = 341; // Why 341? Because its exacly 1/3 of the 10-bit
91-
*myInput = 341; // ADC max and this perfectly matches the 8-bit
92-
*mySetpoint = 341; // PWM value (85/255 = 1/3). We need 0% digital bias
93-
*myOutput = 85; // for a symetrical waveform over the setpoint.
85+
void QuickPID::AutoTune(int inputPin, int outputPin, int tuningRule, int Print = 0, uint32_t timeout = 120) {
9486

87+
uint32_t stepPrevTime, stepTime;
9588
float Ku, Tu;
96-
bool stepDir = true;
9789

98-
analogWrite(outputPin, 85);
99-
if (Print == 1) Serial.print("Settling at 33% for 7 sec ");
100-
for (int i = 0; i < 7; i++) {
101-
delay(1000);
102-
if (Print == 1) Serial.print(".");
103-
}
90+
const int Rule[10][3] =
91+
{ //ckp, cki, ckd x 1000
92+
{ 450, 540, 0 }, // ZIEGLER_NICHOLS_PI
93+
{ 600, 1176, 75 }, // ZIEGLER_NICHOLS_PID
94+
{ 313, 142, 0 }, // TYREUS_LUYBEN_PI
95+
{ 454, 206, 72 }, // TYREUS_LUYBEN_PID
96+
{ 303, 1212, 0 }, // CIANCONE_MARLIN_PI
97+
{ 303, 1333, 37 }, // CIANCONE_MARLIN_PID
98+
{ 0, 0, 0 }, // AMIGOF_PI (reserved)
99+
{ 700, 1750, 105 }, // PESSEN_INTEGRAL_PID
100+
{ 333, 667, 111 }, // SOME_OVERSHOOT_PID
101+
{ 200, 400, 67 }, // NO_OVERSHOOT_PID
102+
};
103+
const byte ckp = 0, cki = 1, ckd = 2; // c = column
104+
peakHigh = atSetpoint;
105+
peakLow = atSetpoint;
106+
timeout *= 1000;
104107
if (Print == 1) Serial.println();
105-
if (Print == 1) Serial.print("AutoTune:");
106-
107-
for (int i = 0; i < 16; i++) { // fill the rolling average
108-
*myInput = analogReadAvg(inputPin);
109-
}
108+
if (Print == 1) Serial.print("Stabilizing (33%) →");
109+
QuickPID::Stabilize(inputPin, outputPin, timeout);
110+
if (Print == 1) Serial.print("→ Running AutoTune");
111+
QuickPID::StepUp(inputPin, outputPin, timeout);
112+
stepPrevTime = micros();
113+
if (Print == 1) Serial.print("");
114+
QuickPID::StepDown(inputPin, outputPin, timeout);
115+
if (Print == 1) Serial.print("");
116+
QuickPID::StepUp(inputPin, outputPin, timeout);
117+
stepTime = micros();
118+
if (Print == 1) Serial.print("");
119+
QuickPID::StepDown(inputPin, outputPin, timeout);
120+
if (Print == 1) Serial.print("");
121+
QuickPID::StepUp(inputPin, outputPin, timeout);
122+
if (Print == 1) Serial.print("");
123+
stepTime = micros();
124+
Tu = (float)(stepTime - stepPrevTime) / 2000000.0; // ultimate period based on 2 cycles
125+
dispTu = Tu;
126+
Ku = (float)(4 * outputStep * 2) / (float)(3.14159 * sqrt (sq (peakHigh - peakLow) - sq (hysteresis))); // ultimate gain
127+
dispKu = Ku;
110128

111-
timeout *= 1000;
129+
if (Print == 1) {
130+
Serial.println(); Serial.print("Ultimate Period Tu: "); Serial.print(Tu, 3); Serial.println("s");
131+
Serial.print("Ultimate Gain Ku: "); Serial.println(Ku, 3);
112132

113-
do { //oscillate the output based on the input's relation to the setpoint
114-
if (*myInput > *mySetpoint + hysteresis) { // input passes +'ve hysteresis
115-
*myOutput = 85 - outputStep; // step down
116-
if (*myInput > peakHigh) peakHigh = *myInput; // update peakHigh
117-
if (!stepDir) { // if previous direction was down
118-
stepPrevTime = stepTime; // update step time variables
119-
stepTime = micros();
120-
stepDir = true;
121-
}
122-
}
123-
else if (*myInput < *mySetpoint - hysteresis) { // input passes -'ve hysteresis
124-
*myOutput = 85 + outputStep; // step up
125-
if (stepPrevTime && (*myInput < peakLow)) peakLow = *myInput; // update peakLow only if prev peakHigh timing > 0
126-
stepDir = false;
127-
}
128-
*myInput = analogReadAvg(inputPin); // update input (rolling average)
129-
analogWrite(outputPin, *myOutput); // update output
130-
Ku = (float)(4 * outputStep * 2) / (float)(3.14159 * sqrt (sq (peakHigh - peakLow) - sq (hysteresis * 2))); // critical gain
131-
Tu = (float)(stepTime - stepPrevTime) / 1000000.0; // critical period
132-
delay(2); // allow some iteration time
133-
} while ((isinf(Ku) || isnan(Ku)) && (millis() <= timeout));
134-
135-
if (tuningRule == 0) { // Ziegler Nichols PID
136-
kp = 0.6 * Ku;
137-
ki = 1.2 * Ku / Tu;
138-
kd = 0.075 * Ku * Tu;
139-
} else { // Ziegler Nichols PI
140-
kp = 0.45 * Ku;
141-
ki = 0.54 * Ku / Tu;
142-
kd = 0.0;
133+
Serial.print("peakHigh: "); Serial.println(peakHigh);
134+
Serial.print("peakLow: "); Serial.println(peakLow);
143135
}
144136

137+
kp = Rule[tuningRule][ckp] / 1000.0 * Ku;
138+
ki = Rule[tuningRule][cki] / 1000.0 * Ku / Tu;
139+
kd = Rule[tuningRule][ckd] / 1000.0 * Ku * Tu;
140+
145141
if (Print == 1) {
146-
Serial.print(" Ku: "); Serial.print(Ku);
147-
Serial.print(" Tu: "); Serial.print(Tu);
148-
Serial.print(" Kp: "); Serial.print(kp);
149-
Serial.print(" Ki: "); Serial.print(ki);
150-
Serial.print(" Kd: "); Serial.println(kd);
142+
Serial.print("Kp: "); Serial.print(kp, 3);
143+
Serial.print(" Ki: "); Serial.print(ki, 3);
144+
Serial.print(" Kd: "); Serial.println(kd, 3);
151145
}
152146
SetTunings(kp, ki, kd);
153147
}
154148

155149
/* SetTunings(....)************************************************************
156-
This function allows the controller's dynamic performance to be adjusted.
157-
it's called automatically from the constructor, but tunings can also
158-
be adjusted on the fly during normal operation
159-
******************************************************************************/
150+
This function allows the controller's dynamic performance to be adjusted.
151+
it's called automatically from the constructor, but tunings can also
152+
be adjusted on the fly during normal operation
153+
******************************************************************************/
160154
void QuickPID::SetTunings(float Kp, float Ki, float Kd, float POn = 1)
161155
{
162156
if (Kp < 0 || Ki < 0 || Kd < 0) return;
@@ -180,15 +174,15 @@ void QuickPID::SetTunings(float Kp, float Ki, float Kd, float POn = 1)
180174
}
181175

182176
/* SetTunings(...)*************************************************************
183-
Set Tunings using the last remembered POn setting.
184-
******************************************************************************/
177+
Set Tunings using the last remembered POn setting.
178+
******************************************************************************/
185179
void QuickPID::SetTunings(float Kp, float Ki, float Kd) {
186180
SetTunings(Kp, Ki, Kd, pOn);
187181
}
188182

189183
/* SetSampleTime(...) *********************************************************
190-
Sets the period, in microseconds, at which the calculation is performed
191-
******************************************************************************/
184+
Sets the period, in microseconds, at which the calculation is performed
185+
******************************************************************************/
192186
void QuickPID::SetSampleTimeUs(uint32_t NewSampleTimeUs)
193187
{
194188
if (NewSampleTimeUs > 0) {
@@ -199,16 +193,10 @@ void QuickPID::SetSampleTimeUs(uint32_t NewSampleTimeUs)
199193
}
200194
}
201195

202-
int16_t QuickPID::Saturate(int16_t Out) {
203-
if (Out > outMax) Out = outMax;
204-
else if (Out < outMin) Out = outMin;
205-
return Out;
206-
}
207-
208196
/* SetOutputLimits(...)********************************************************
209-
The PID controller is designed to vary its output within a given range.
210-
By default this range is 0-255, the Arduino PWM range.
211-
******************************************************************************/
197+
The PID controller is designed to vary its output within a given range.
198+
By default this range is 0-255, the Arduino PWM range.
199+
******************************************************************************/
212200
void QuickPID::SetOutputLimits(int16_t Min, int16_t Max)
213201
{
214202
if (Min >= Max) return;
@@ -223,10 +211,10 @@ void QuickPID::SetOutputLimits(int16_t Min, int16_t Max)
223211
}
224212

225213
/* SetMode(...)****************************************************************
226-
Allows the controller Mode to be set to manual (0) or Automatic (non-zero)
227-
when the transition from manual to auto occurs, the controller is
228-
automatically initialized
229-
******************************************************************************/
214+
Allows the controller Mode to be set to manual (0) or Automatic (non-zero)
215+
when the transition from manual to auto occurs, the controller is
216+
automatically initialized
217+
******************************************************************************/
230218
void QuickPID::SetMode(bool Mode)
231219
{
232220
bool newAuto = (Mode == AUTOMATIC);
@@ -238,9 +226,9 @@ void QuickPID::SetMode(bool Mode)
238226
}
239227

240228
/* Initialize()****************************************************************
241-
Does all the things that need to happen to ensure a bumpless transfer
242-
from manual to automatic mode.
243-
******************************************************************************/
229+
Does all the things that need to happen to ensure a bumpless transfer
230+
from manual to automatic mode.
231+
******************************************************************************/
244232
void QuickPID::Initialize()
245233
{
246234
outputSum = *myOutput;
@@ -249,11 +237,11 @@ void QuickPID::Initialize()
249237
}
250238

251239
/* SetControllerDirection(...)*************************************************
252-
The PID will either be connected to a DIRECT acting process (+Output leads
253-
to +Input) or a REVERSE acting process(+Output leads to -Input.) we need to
254-
know which one, because otherwise we may increase the output when we should
255-
be decreasing. This is called from the constructor.
256-
******************************************************************************/
240+
The PID will either be connected to a DIRECT acting process (+Output leads
241+
to +Input) or a REVERSE acting process(+Output leads to -Input.) we need to
242+
know which one, because otherwise we may increase the output when we should
243+
be decreasing. This is called from the constructor.
244+
******************************************************************************/
257245
void QuickPID::SetControllerDirection(bool Direction)
258246
{
259247
if (inAuto && Direction != controllerDirection)
@@ -266,10 +254,10 @@ void QuickPID::SetControllerDirection(bool Direction)
266254
}
267255

268256
/* Status Functions************************************************************
269-
Just because you set the Kp=-1 doesn't mean it actually happened. These
270-
functions query the internal state of the PID. They're here for display
271-
purposes. These are the functions the PID Front-end uses for example.
272-
******************************************************************************/
257+
Just because you set the Kp=-1 doesn't mean it actually happened. These
258+
functions query the internal state of the PID. They're here for display
259+
purposes. These are the functions the PID Front-end uses for example.
260+
******************************************************************************/
273261
float QuickPID::GetKp() {
274262
return dispKp;
275263
}
@@ -279,15 +267,18 @@ float QuickPID::GetKi() {
279267
float QuickPID::GetKd() {
280268
return dispKd;
281269
}
270+
float QuickPID::GetKu() {
271+
return dispKu;
272+
}
273+
float QuickPID::GetTu() {
274+
return dispTu;
275+
}
282276
bool QuickPID::GetMode() {
283277
return inAuto ? AUTOMATIC : MANUAL;
284278
}
285279
bool QuickPID::GetDirection() {
286280
return controllerDirection;
287281
}
288-
int16_t QuickPID::GetError() {
289-
return error;
290-
}
291282

292283
// Utility functions **********************************************************
293284

@@ -315,8 +306,7 @@ int QuickPID::analogReadFast(int ADCpin) {
315306
# endif
316307
}
317308

318-
int QuickPID::analogReadAvg(int ADCpin)
319-
{
309+
float QuickPID::analogReadAvg(int ADCpin) {
320310
static int arrDat[16];
321311
static int dat;
322312
static int pos;
@@ -326,5 +316,50 @@ int QuickPID::analogReadAvg(int ADCpin)
326316
if (pos >= 16) pos = 0;
327317
sum = sum - arrDat[pos] + dat;
328318
arrDat[pos] = dat;
329-
return sum / 16;
319+
return (float)sum / 16.0;
320+
}
321+
322+
int16_t QuickPID::Saturate(int16_t Out) {
323+
if (Out > outMax) Out = outMax;
324+
else if (Out < outMin) Out = outMin;
325+
return Out;
326+
}
327+
328+
void QuickPID::StepUp(int inputPin, int outputPin, uint32_t timeout) {
329+
analogWrite (outputPin, (atOutput + outputStep)); // step up output, wait for input to reach +'ve hysteresis
330+
while ((analogReadAvg(inputPin) < (atSetpoint + hysteresis)) && (millis() <= timeout)) {
331+
float rdAvg = analogReadAvg(inputPin);
332+
if (rdAvg > peakHigh) peakHigh = rdAvg;
333+
if ((rdAvg < peakLow) && (peakHigh >= (atSetpoint + hysteresis))) peakLow = rdAvg;
334+
delayMicroseconds(readPeriod);
335+
}
336+
}
337+
338+
void QuickPID::StepDown(int inputPin, int outputPin, uint32_t timeout) {
339+
analogWrite (outputPin, (atOutput - outputStep)); // step down output, wait for input to reach -'ve hysteresis
340+
while ((analogReadAvg(inputPin) > (atSetpoint - hysteresis)) && (millis() <= timeout)) {
341+
float rdAvg = analogReadAvg(inputPin);
342+
if (rdAvg > peakHigh) peakHigh = rdAvg;
343+
if ((rdAvg < peakLow) && (peakHigh >= (atSetpoint + hysteresis))) peakLow = rdAvg;
344+
delayMicroseconds(readPeriod);
345+
}
346+
}
347+
348+
void QuickPID::Stabilize(int inputPin, int outputPin, uint32_t timeout) {
349+
// initial reading
350+
for (int i = 0; i <= 16; i++) {
351+
analogReadAvg(inputPin);
352+
}
353+
// coarse adjust
354+
analogWrite (outputPin, 0);
355+
while ((analogReadAvg(inputPin) > atSetpoint) && (millis() <= timeout));
356+
analogWrite(outputPin, atOutput * 2);
357+
while ((analogReadAvg(inputPin) < atSetpoint) && (millis() <= timeout));
358+
359+
// fine adjust
360+
analogWrite (outputPin, atOutput - outputStep - 1);
361+
while ((analogReadAvg(inputPin) > atSetpoint) && (millis() <= timeout));
362+
analogWrite(outputPin, atOutput + outputStep + 1);
363+
while ((analogReadAvg(inputPin) < atSetpoint) && (millis() <= timeout));
364+
analogWrite(outputPin, atOutput);
330365
}

QuickPID.h

Lines changed: 18 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -33,9 +33,6 @@ class QuickPID
3333
// Automatically determines and sets the tuning parameters Kp, Ki and Kd. Use this in the setup loop.
3434
void AutoTune(int, int, int, int, uint32_t);
3535

36-
// Clamps the output to its pre-determined limits.
37-
int16_t Saturate(int16_t);
38-
3936
// Sets and clamps the output to a specific range (0-255 by default).
4037
void SetOutputLimits(int16_t, int16_t);
4138

@@ -59,20 +56,27 @@ class QuickPID
5956
float GetKp(); // These functions query the pid for interal values. They were created mainly for
6057
float GetKi(); // the pid front-end, where it's important to know what is actually inside the PID.
6158
float GetKd();
59+
float GetKu();
60+
float GetTu();
6261
bool GetMode();
6362
bool GetDirection();
64-
int16_t GetError();
6563

6664
// Utility functions ******************************************************************************************
6765
int analogReadFast(int);
68-
int analogReadAvg(int);
66+
float analogReadAvg(int);
6967

7068
private:
7169
void Initialize();
70+
int16_t Saturate(int16_t);
71+
void StepUp(int, int, uint32_t);
72+
void StepDown(int, int, uint32_t);
73+
void Stabilize(int, int, uint32_t);
7274

7375
float dispKp; // We'll hold on to the tuning parameters for display purposes.
7476
float dispKi;
7577
float dispKd;
78+
float dispKu;
79+
float dispTu;
7680

7781
float pOn; // proportional mode (0-1) default = 1, 100% Proportional on Error
7882
float kp; // (P)roportional Tuning Parameter
@@ -91,6 +95,15 @@ class QuickPID
9195
int16_t outMin, outMax, error;
9296
int16_t lastInput, outputSum;
9397
bool inAuto;
98+
99+
// AutoTune
100+
float peakHigh, peakLow;
101+
const word readPeriod = 250;
102+
const byte outputStep = 1;
103+
const byte hysteresis = 1;
104+
const int atSetpoint = 341; // 1/3 of 10-bit ADC matches 8-bit PWM value of 85 for symetrical waveform
105+
const int atOutput = 85;
106+
94107
};
95108

96109
#endif

0 commit comments

Comments
 (0)