Skip to content

Commit 2e98e96

Browse files
committed
Add setpoint weighting feature
1 parent 061b903 commit 2e98e96

File tree

7 files changed

+32
-50
lines changed

7 files changed

+32
-50
lines changed

QuickPID.cpp

Lines changed: 8 additions & 20 deletions
Original file line numberDiff line numberDiff line change
@@ -19,7 +19,7 @@
1919
reliable defaults, so we need to have the user set them.
2020
**********************************************************************************/
2121
QuickPID::QuickPID(int16_t* Input, int16_t* Output, int16_t* Setpoint,
22-
float Kp, float Ki, float Kd, bool POn, bool ControllerDirection)
22+
float Kp, float Ki, float Kd, float POn, bool ControllerDirection)
2323
{
2424
myOutput = Output;
2525
myInput = Input;
@@ -42,7 +42,7 @@ QuickPID::QuickPID(int16_t* Input, int16_t* Output, int16_t* Setpoint,
4242

4343
QuickPID::QuickPID(int16_t* Input, int16_t* Output, int16_t* Setpoint,
4444
float Kp, float Ki, float Kd, bool ControllerDirection)
45-
: QuickPID::QuickPID(Input, Output, Setpoint, Kp, Ki, Kd, P_ON_E, ControllerDirection)
45+
: QuickPID::QuickPID(Input, Output, Setpoint, Kp, Ki, Kd, pOn, ControllerDirection)
4646
{
4747

4848
}
@@ -65,17 +65,9 @@ bool QuickPID::Compute()
6565
int16_t dInput = input - lastInput;
6666
error = *mySetpoint - input;
6767

68-
/*Working error, Proportional on Measurement and Remaining PID output*/
69-
if (!pOnE) {
70-
if (ki < 31 && kpd < 31) outputSum += FX_MUL(FL_FX(ki) , error) - FX_MUL(FL_FX(kpd), dInput);
71-
else outputSum += (ki * error) - (kpd * dInput);
72-
}
73-
74-
/*Working error, Proportional on Error and remaining PID output*/
75-
if (pOnE) {
76-
if (kpi < 31 && kd < 31) outputSum += FX_MUL(FL_FX(kpi) , error) - FX_MUL(FL_FX(kd), dInput);
77-
else outputSum += (kpi * error) - (kd * dInput);
78-
}
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);
7971

8072
if (outputSum > outMax) outputSum = outMax;
8173
if (outputSum < outMin) outputSum = outMin;
@@ -94,20 +86,19 @@ bool QuickPID::Compute()
9486
it's called automatically from the constructor, but tunings can also
9587
be adjusted on the fly during normal operation
9688
******************************************************************************/
97-
void QuickPID::SetTunings(float Kp, float Ki, float Kd, bool POn)
89+
void QuickPID::SetTunings(float Kp, float Ki, float Kd, float POn)
9890
{
9991
if (Kp < 0 || Ki < 0 || Kd < 0) return;
10092

10193
pOn = POn;
102-
pOnE = POn == P_ON_E;
10394
dispKp = Kp; dispKi = Ki; dispKd = Kd;
10495

10596
float SampleTimeSec = (float)SampleTimeUs / 1000000;
10697
kp = Kp;
10798
ki = Ki * SampleTimeSec;
10899
kd = Kd / SampleTimeSec;
109-
kpd = kp + kd;
110-
kpi = kp + ki;
100+
kpi = kp * pOn + ki;
101+
kpd = kp * (1 - pOn) + kd;
111102

112103
if (controllerDirection == REVERSE)
113104
{
@@ -228,9 +219,6 @@ bool QuickPID::GetDirection() {
228219
int16_t QuickPID::GetError() {
229220
return error;
230221
}
231-
bool QuickPID::GetpOnE() {
232-
return pOnE;
233-
}
234222

235223
// Utility functions **********************************************************
236224

QuickPID.h

Lines changed: 7 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -11,8 +11,6 @@ class QuickPID
1111
#define MANUAL 0
1212
#define DIRECT 0
1313
#define REVERSE 1
14-
#define P_ON_M 0
15-
#define P_ON_E 1
1614

1715
#define FL_FX(a) (int32_t)(a*256.0) // float to fixed point
1816
#define FX_MUL(a,b) ((a*b)>>8) // fixed point multiply
@@ -21,7 +19,7 @@ class QuickPID
2119
// commonly used functions ************************************************************************************
2220

2321
// Constructor. Links the PID to Input, Output, Setpoint and initial Tuning Parameters.
24-
QuickPID(int16_t*, int16_t*, int16_t*, float, float, float, bool, bool);
22+
QuickPID(int16_t*, int16_t*, int16_t*, float, float, float, float, bool);
2523

2624
// Overload constructor with proportional mode. Links the PID to Input, Output, Setpoint and Tuning Parameters.
2725
QuickPID(int16_t*, int16_t*, int16_t*, float, float, float, bool);
@@ -44,7 +42,7 @@ class QuickPID
4442
void SetTunings(float, float, float);
4543

4644
// Overload for specifying proportional mode.
47-
void SetTunings(float, float, float, bool);
45+
void SetTunings(float, float, float, float);
4846

4947
// Sets the Direction, or "Action" of control. DIRECT means the output will increase when error is positive.
5048
// REVERSE means the opposite. It's very unlikely that this will be needed once it is set in the constructor.
@@ -60,26 +58,25 @@ class QuickPID
6058
bool GetMode();
6159
bool GetDirection();
6260
int16_t GetError();
63-
bool GetpOnE();
6461

6562
// Utility functions ******************************************************************************************
6663
int analogReadFast(int);
6764

6865
private:
6966
void Initialize();
7067

71-
float dispKp; // We'll hold on to the tuning parameters in user-entered format for display purposes.
68+
float dispKp; // We'll hold on to the tuning parameters for display purposes.
7269
float dispKi;
7370
float dispKd;
7471

72+
float pOn; // proportional mode (0-1) default 1 (100% on Error, 0% on Measurement)
7573
float kp; // (P)roportional Tuning Parameter
7674
float ki; // (I)ntegral Tuning Parameter
7775
float kd; // (D)erivative Tuning Parameter
78-
float kpd = kp + kd;
79-
float kpi = kp + ki;
76+
float kpi; // proportional on error amount
77+
float kpd; // proportional on measurement amount
8078

8179
bool controllerDirection;
82-
bool pOn;
8380

8481
int16_t *myInput; // Pointers to the Input, Output, and Setpoint variables. This creates a
8582
int16_t *myOutput; // hard link between the variables and the PID, freeing the user from having
@@ -88,7 +85,7 @@ class QuickPID
8885
uint32_t SampleTimeUs, lastTime;
8986
int16_t outMin, outMax, error;
9087
int16_t lastInput, outputSum;
91-
bool inAuto, pOnE;
88+
bool inAuto;
9289
};
9390

9491
#endif

README.md

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -2,8 +2,8 @@
22

33
This API (version 2.03) follows the [ArduinoPID](https://github.com/br3ttb/Arduino-PID-Library) library, however there have been some significant updates as follows:
44

5-
- This library named as **QuickPID** and can run alongside with Arduino **PID** if needed
6-
- Quicker fixed point math in compute function for small tuning values, floating point math used for large tuning values
5+
- Quicker hybrid fixed/floating point math in compute function
6+
- POn parameter controls the setpoint weighting of Proportional on Error (PonE) to Proportional on Measurement (PonM)
77
- Reorganized and more efficient PID algorithm
88
- micros() timing resolution
99
- Faster analog read function
@@ -14,15 +14,15 @@ This API (version 2.03) follows the [ArduinoPID](https://github.com/br3ttb/Ardui
1414

1515
| Compute | Kp | Ki | Kd | Step Time (µS) |
1616
| :----------------------------------- | ---- | ---- | ---- | -------------- |
17-
| QuickPID | 2.0 | 15.0 | 0.05 | 68 |
17+
| QuickPID | 2.0 | 15.0 | 0.05 | 72 |
1818
| Arduino PID | 2.0 | 15.0 | 0.05 | 104 |
1919
| **analogRead, Compute, analogWrite** | | | | |
2020
| QuickPID | 2.0 | 5.0 | 0.2 | 96 |
2121
| Arduino PID | 2.0 | 5.0 | 0.2 | 224 |
2222

2323
#### Self Test Example (RC Filter):
2424

25-
This example allows you to set an output voltage, then view the result of your tuning parameters. The mode of the P-Term automatically toggles from Proportional on Error to [Proportional on Measurement.](http://brettbeauregard.com/blog/2017/06/introducing-proportional-on-measurement/)
25+
[This example](https://github.com/Dlloydev/QuickPID/wiki/QuickPID_RC_Filter) allows you to experiment with the four tuning parameters.
2626

2727
![pid_self_test_pom](https://user-images.githubusercontent.com/63488701/104389509-a66a8f00-5509-11eb-927b-1190231a1ee9.gif)
2828

examples/QuickPID_Self_Test/QuickPID_Self_Test.ino renamed to examples/QuickPID_RC_Filter/QuickPID_RC_Filter.ino

Lines changed: 7 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -1,9 +1,10 @@
1-
/************************************************************
2-
PID RC Filter Self Test Example:
3-
One 47µF capacitor connected from GND to a 27K resistor
1+
/**************************************************************
2+
PID RC Filter Example:
3+
One 47µF capacitor connected from GND to a 10K resistor
44
terminated at pwm pin 3. Junction point of the RC filter
55
is connected to A0. Use Serial Plotter to view results.
6-
************************************************************/
6+
https://github.com/Dlloydev/QuickPID/wiki/QuickPID_RC_Filter
7+
**************************************************************/
78

89
#include "QuickPID.h"
910

@@ -19,14 +20,14 @@ unsigned long before, after;
1920
int cnt = 0;
2021

2122
//Specify the initial tuning parameters
22-
float Kp = 2.0, Ki = 15.0, Kd = 0.05;
23+
float Kp = 2.0, Ki = 15.0, Kd = 0.05, POn = 1.0;
2324

2425
QuickPID myQuickPID(&Input, &Output, &Setpoint, Kp, Ki, Kd, DIRECT);
2526

2627
void setup()
2728
{
2829
Serial.begin(115200);
29-
myQuickPID.SetTunings(Kp, Ki, Kd, P_ON_E);
30+
myQuickPID.SetTunings(Kp, Ki, Kd, POn);
3031
myQuickPID.SetMode(AUTOMATIC);
3132
analogWrite(PIN_OUTPUT, 0); // discharge capacitor
3233
delay(1000);
@@ -59,6 +60,5 @@ void loop()
5960
analogWrite(PIN_OUTPUT, 0);
6061
delay(1000); // discharge capacitor
6162
cnt = 0;
62-
myQuickPID.SetTunings(Kp, Ki, Kd, !(myQuickPID.GetpOnE())); //toggle P-Term mode
6363
}
6464
}

keywords.txt

Lines changed: 0 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -23,7 +23,6 @@ GetKi KEYWORD2
2323
GetKd KEYWORD2
2424
GetMode KEYWORD2
2525
GetError KEYWORD2
26-
GetpOnE KEYWORD2
2726
GetDirection KEYWORD2
2827
analogReadFast KEYWORD2
2928

@@ -35,5 +34,3 @@ AUTOMATIC LITERAL1
3534
MANUAL LITERAL1
3635
DIRECT LITERAL1
3736
REVERSE LITERAL1
38-
P_ON_E LITERAL1
39-
P_ON_M LITERAL1

library.json

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,7 +1,7 @@
11
{
22
"name": "QuickPID",
33
"keywords": "PID, controller, signal",
4-
"description": "A fast, fixed point PID controller that seeks to keep an input variable close to a desired setpoint by adjusting an output. The way in which it does this can be 'tuned' by adjusting three parameters (P,I,D).",
4+
"description": "QuickPID controller - a faster implementation of the Arduino PID Library with more features. This hybrid fixed/floating point controller seeks to keep an output close to a desired setpoint by adjusting four parameters (P,I,D) and POn (PonE, PonM setpoint weighting).",
55
"url": "https://github.com/Dlloydev/QuickPID",
66
"include": "QuickPID",
77
"authors":

library.properties

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -1,9 +1,9 @@
11
name=QuickPID
22
version=2.0.3
3-
author=dlloydev
4-
maintainer=dlloydev
5-
sentence=QuickPID controller
6-
paragraph=A fast, fixed point PID controller that seeks to keep an input variable close to a desired setpoint by adjusting an output. The way in which it does this can be 'tuned' by adjusting three parameters (P,I,D).
3+
author=dlloydev
4+
maintainer=David Lloyd <dlloydev@testcor.ca>
5+
sentence=QuickPID controller - a faster hybrid fixed/floating point implementation of the Arduino PID Library with more features.
6+
paragraph=This controller seeks to keep an output close to a desired setpoint by adjusting four parameters (P,I,D) and POn (PonE, PonM setpoint weighting).
77
category=Signal Input/Output
88
url=https://github.com/Dlloydev/QuickPID
9-
architectures=*
9+
architectures=avr

0 commit comments

Comments
 (0)