Skip to content

Commit a55f341

Browse files
committed
New Version with AutoTune
1 parent 6be0fbe commit a55f341

File tree

8 files changed

+235
-118
lines changed

8 files changed

+235
-118
lines changed

QuickPID.cpp

Lines changed: 112 additions & 27 deletions
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,5 @@
11
/**********************************************************************************
2-
QuickPID Library for Arduino - Version 2.0.5
2+
QuickPID Library for Arduino - Version 2.1.0
33
by dlloydev https://github.com/Dlloydev/QuickPID
44
Based on the Arduino PID Library by Brett Beauregard
55
@@ -27,12 +27,12 @@ QuickPID::QuickPID(int16_t* Input, int16_t* Output, int16_t* Setpoint,
2727
inAuto = false;
2828

2929
QuickPID::SetOutputLimits(0, 255); // default is same as the arduino PWM limit
30-
SampleTimeUs = 100000; // default is 0.1 seconds
30+
sampleTimeUs = 100000; // default is 0.1 seconds
3131

3232
QuickPID::SetControllerDirection(ControllerDirection);
3333
QuickPID::SetTunings(Kp, Ki, Kd, POn);
3434

35-
lastTime = micros() - SampleTimeUs;
35+
lastTime = micros() - sampleTimeUs;
3636
}
3737

3838
/* Constructor ********************************************************************
@@ -58,29 +58,100 @@ bool QuickPID::Compute()
5858
if (!inAuto) return false;
5959
uint32_t now = micros();
6060
uint32_t timeChange = (now - lastTime);
61-
if (timeChange >= SampleTimeUs)
62-
{
63-
/*Compute all the working error variables*/
61+
62+
if (timeChange >= sampleTimeUs) { // Compute the working error variables
6463
int16_t input = *myInput;
6564
int16_t dInput = input - lastInput;
6665
error = *mySetpoint - input;
6766

68-
/*Working error, Proportional distribution and Remaining PID output*/
69-
if (kpi < 31 && kpd < 31) outputSum += FX_MUL(FL_FX(kpi) , error) - FX_MUL(FL_FX(kpd), dInput);
70-
else outputSum += (kpi * error) - (kpd * dInput);
67+
if (kpi < 31 && kpd < 31) outputSum += FX_MUL(FL_FX(kpi) , error) - FX_MUL(FL_FX(kpd), dInput); // fixed-point
68+
else outputSum += (kpi * error) - (kpd * dInput); // floating-point
7169

72-
if (outputSum > outMax) outputSum = outMax;
73-
if (outputSum < outMin) outputSum = outMin;
70+
outputSum = QuickPID::Saturate(outputSum);
7471
*myOutput = outputSum;
7572

76-
/*Remember some variables for next time*/
7773
lastInput = input;
7874
lastTime = now;
7975
return true;
8076
}
8177
else return false;
8278
}
8379

80+
/* AutoTune(...)***************************************************************************
81+
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
83+
Ziegler-Nichols tuning rules to compute Kp, Ki and Kd.
84+
******************************************************************************************/
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.
94+
95+
float Ku, Tu;
96+
bool stepDir = true;
97+
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+
}
104+
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+
}
110+
111+
timeout *= 1000;
112+
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;
143+
}
144+
145+
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);
151+
}
152+
SetTunings(kp, ki, kd);
153+
}
154+
84155
/* SetTunings(....)************************************************************
85156
This function allows the controller's dynamic performance to be adjusted.
86157
it's called automatically from the constructor, but tunings can also
@@ -93,12 +164,12 @@ void QuickPID::SetTunings(float Kp, float Ki, float Kd, float POn = 1)
93164
pOn = POn;
94165
dispKp = Kp; dispKi = Ki; dispKd = Kd;
95166

96-
float SampleTimeSec = (float)SampleTimeUs / 1000000;
167+
float SampleTimeSec = (float)sampleTimeUs / 1000000;
97168
kp = Kp;
98169
ki = Ki * SampleTimeSec;
99170
kd = Kd / SampleTimeSec;
100-
kpi = kp * pOn + ki;
101-
kpd = kp * (1 - pOn) + kd;
171+
kpi = (kp * pOn) + ki;
172+
kpd = (kp * (1 - pOn)) + kd;
102173

103174
if (controllerDirection == REVERSE)
104175
{
@@ -120,16 +191,20 @@ void QuickPID::SetTunings(float Kp, float Ki, float Kd) {
120191
******************************************************************************/
121192
void QuickPID::SetSampleTimeUs(uint32_t NewSampleTimeUs)
122193
{
123-
if (NewSampleTimeUs > 0)
124-
{
125-
float ratio = (float)NewSampleTimeUs / (float)SampleTimeUs;
194+
if (NewSampleTimeUs > 0) {
195+
float ratio = (float)NewSampleTimeUs / (float)sampleTimeUs;
126196
ki *= ratio;
127197
kd /= ratio;
128-
129-
SampleTimeUs = NewSampleTimeUs;
198+
sampleTimeUs = NewSampleTimeUs;
130199
}
131200
}
132201

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+
133208
/* SetOutputLimits(...)********************************************************
134209
The PID controller is designed to vary its output within a given range.
135210
By default this range is 0-255, the Arduino PWM range.
@@ -142,11 +217,8 @@ void QuickPID::SetOutputLimits(int16_t Min, int16_t Max)
142217

143218
if (inAuto)
144219
{
145-
if (*myOutput > outMax) *myOutput = outMax;
146-
else if (*myOutput < outMin) *myOutput = outMin;
147-
148-
if (outputSum > outMax) outputSum = outMax;
149-
else if (outputSum < outMin) outputSum = outMin;
220+
*myOutput = QuickPID::Saturate(*myOutput);
221+
outputSum = QuickPID::Saturate(outputSum);
150222
}
151223
}
152224

@@ -173,8 +245,7 @@ void QuickPID::Initialize()
173245
{
174246
outputSum = *myOutput;
175247
lastInput = *myInput;
176-
if (outputSum > outMax) outputSum = outMax;
177-
else if (outputSum < outMin) outputSum = outMin;
248+
outputSum = QuickPID::Saturate(outputSum);
178249
}
179250

180251
/* SetControllerDirection(...)*************************************************
@@ -243,3 +314,17 @@ int QuickPID::analogReadFast(int ADCpin) {
243314
return analogRead(ADCpin);
244315
# endif
245316
}
317+
318+
int QuickPID::analogReadAvg(int ADCpin)
319+
{
320+
static int arrDat[16];
321+
static int dat;
322+
static int pos;
323+
static long sum;
324+
dat = QuickPID::analogReadFast(ADCpin);
325+
pos++;
326+
if (pos >= 16) pos = 0;
327+
sum = sum - arrDat[pos] + dat;
328+
arrDat[pos] = dat;
329+
return sum / 16;
330+
}

QuickPID.h

Lines changed: 11 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -7,15 +7,14 @@ class QuickPID
77
public:
88

99
//Constants used in some of the functions below
10-
#define AUTOMATIC 1
11-
#define MANUAL 0
10+
#define AUTOMATIC 1
11+
#define MANUAL 0
1212
#define DIRECT 0
1313
#define REVERSE 1
1414

1515
#define FL_FX(a) (int32_t)(a*256.0) // float to fixed point
1616
#define FX_MUL(a,b) ((a*b)>>8) // fixed point multiply
1717

18-
1918
// commonly used functions ************************************************************************************
2019

2120
// Constructor. Links the PID to Input, Output, Setpoint and initial Tuning Parameters.
@@ -31,8 +30,13 @@ class QuickPID
3130
// can be set using SetMode and SetSampleTime respectively.
3231
bool Compute();
3332

34-
// Clamps the output to a specific range. 0-255 by default, but it's likely the user will want to change this
35-
// depending on the application.
33+
// Automatically determines and sets the tuning parameters Kp, Ki and Kd. Use this in the setup loop.
34+
void AutoTune(int, int, int, int, uint32_t);
35+
36+
// Clamps the output to its pre-determined limits.
37+
int16_t Saturate(int16_t);
38+
39+
// Sets and clamps the output to a specific range (0-255 by default).
3640
void SetOutputLimits(int16_t, int16_t);
3741

3842
// available but not commonly used functions ******************************************************************
@@ -61,6 +65,7 @@ class QuickPID
6165

6266
// Utility functions ******************************************************************************************
6367
int analogReadFast(int);
68+
int analogReadAvg(int);
6469

6570
private:
6671
void Initialize();
@@ -82,7 +87,7 @@ class QuickPID
8287
int16_t *myOutput; // hard link between the variables and the PID, freeing the user from having
8388
int16_t *mySetpoint; // to constantly tell us what these values are. With pointers we'll just know.
8489

85-
uint32_t SampleTimeUs, lastTime;
90+
uint32_t sampleTimeUs, lastTime;
8691
int16_t outMin, outMax, error;
8792
int16_t lastInput, outputSum;
8893
bool inAuto;

README.md

Lines changed: 38 additions & 15 deletions
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,6 @@
11
# QuickPID
22

3-
A fast hybrid fixed-point and floating-point PID controller for Arduino.
3+
QuickPID is a fast fixed/floating point implementation of the Arduino PID library with built-in AutoTune function. This controller can automatically determine and set parameters (Kp, Ki, Kd). The POn setting controls the mix of Proportional on Errror to Proportional on Measurement and can be used to set the desired amount of overshoot.
44

55
### About
66

@@ -11,7 +11,8 @@ This PID controller provides a faster *read-compute-write* cycle than alternativ
1111
Development began with a fork of the Arduino PID Library. Some modifications and new features have been added as follows:
1212

1313
- Quicker hybrid fixed/floating point math in compute function
14-
- `POn` parameter now controls the setpoint weighting of Proportional on Error and Proportional on Measurement
14+
- Built-in `AutoTune()` function automatically determines and sets `Kp`, `Ki` and `Kd`. Also determines critical gain `Ku` and critical period `Tu` of the control system
15+
- `POn` parameter now controls the setpoint weighting and mix of Proportional on Error to Proportional on Measurement
1516
- Reorganized and more efficient PID algorithm
1617
- micros() timing resolution
1718
- Faster analog read function
@@ -30,15 +31,15 @@ Development began with a fork of the Arduino PID Library. Some modifications and
3031

3132
### Self Test Example (RC Filter):
3233

33-
[This example](https://github.com/Dlloydev/QuickPID/wiki/QuickPID_RC_Filter) allows you to experiment with the four tuning parameters.
34+
[This example](https://github.com/Dlloydev/QuickPID/wiki/AutoTune_RC_Filter) allows you to experiment with the AutoTune and POn control on an RC filter.
3435

3536
### Simplified PID Algorithm
3637

3738
```c++
3839
outputSum += (kpi * error) - (kpd * dInput);
3940
```
4041

41-
The new `kpi` and `kpd` parameters are calculated in the `SetTunings()` function. This results in a simple and fast algorithm with only two multiply operations required The pOn variable controls the setpoint weighting of Proportional on Error and Proportional on Measurement. The gains for `error` (`kpi`) and measurement `dInput` (`kpd`) are calculated as follows:
42+
The new `kpi` and `kpd` parameters are calculated in the `SetTunings()` function. This results in a simple and fast algorithm with only two multiply operations required. The pOn variable controls the setpoint weighting of Proportional on Error and Proportional on Measurement. The gains for `error` (`kpi`) and measurement `dInput` (`kpd`) are calculated as follows:
4243

4344
```c++
4445
kpi = kp * pOn + ki;
@@ -77,6 +78,33 @@ bool QuickPID::Compute()
7778

7879
This function contains the PID algorithm and it should be called once every loop(). Most of the time it will just return false without doing anything. However, at a frequency specified by `SetSampleTime` it will calculate a new Output and return true.
7980

81+
#### AutoTune
82+
83+
```c++
84+
void QuickPID::AutoTune(int inputPin, int outputPin, int tuningRule, int Print = 0, uint32_t timeout = 30)
85+
```
86+
87+
The `AutoTune()` function automatically determines and sets `Kp`, `Ki` and `Kd`. It also determines the critical gain `Ku` and critical period `Tu` of the control system.
88+
89+
`int tuningRule = 0; // PID(0), PI(1)`
90+
91+
Selects the appropriate Ziegler–Nichols tuning rule for the PID or PI type controller.
92+
93+
| Controller | Kp | Ki | Kd |
94+
| ---------- | ----------- | ---------------- | ----------------- |
95+
| PI | `0.45 * Ku` | `0.54 * Ku / Tu` | `0` |
96+
| PID | `0.6 * Ku` | `1.2 * Ku / Tu` | `0.075 * Ku * Tu` |
97+
98+
`int Print = 0; // on(1), off(0)`
99+
100+
When using Serial Monitor, turn on serial print output to view the AutoTune status and results. When using the Serial Plotter, turn off the AutoTune print output to prevent plot labels from being overwritten.
101+
102+
`uint32_t timeout = 30`
103+
104+
Sets the AutoTune timeout where the default is 30 seconds.
105+
106+
For more inormation, see [QuickPID AutoTune.](https://github.com/Dlloydev/QuickPID/wiki/AutoTune)
107+
80108
#### SetTunings
81109
82110
```c++
@@ -150,21 +178,16 @@ These functions query the internal state of the PID. They're here for display pu
150178
int QuickPID::analogReadFast(int ADCpin)
151179
```
152180
153-
A faster configuration of `analogRead()`where a preset of 32 is used. Works with the following defines:
154-
155-
`__AVR_ATmega328P__`
181+
A faster configuration of `analogRead()`where a preset of 32 is used. If the architecture definition isn't found, normal `analogRead()`is used to return a value.
156182
157-
`__AVR_ATtiny_Zero_One__`
158-
159-
`__AVR_ATmega_Zero__`
160-
161-
`__AVR_DA__`
183+
### Change Log
162184
163-
If the definition isn't found, normal `analogRead()`is used to return a value.
185+
#### Version 2.1.0 (latest)
164186
165-
### Change Log
187+
- Added AutoTune function and documentation
188+
- Added AutoTune_RC_Filter example and documentation
166189
167-
#### Version 2.0.5 (latest)
190+
#### Version 2.0.5
168191
169192
- Added MIT license text file
170193
- POn defaults to 1

0 commit comments

Comments
 (0)