Skip to content

Commit 98c20fe

Browse files
committed
Update Readme
1 parent 2e98e96 commit 98c20fe

File tree

2 files changed

+155
-38
lines changed

2 files changed

+155
-38
lines changed

QuickPID.cpp

Lines changed: 4 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -109,7 +109,7 @@ void QuickPID::SetTunings(float Kp, float Ki, float Kd, float POn)
109109
}
110110

111111
/* SetTunings(...)*************************************************************
112-
Set Tunings using the last-rembered POn setting
112+
Set Tunings using the last remembered POn setting.
113113
******************************************************************************/
114114
void QuickPID::SetTunings(float Kp, float Ki, float Kd) {
115115
SetTunings(Kp, Ki, Kd, pOn);
@@ -131,10 +131,8 @@ void QuickPID::SetSampleTimeUs(uint32_t NewSampleTimeUs)
131131
}
132132

133133
/* SetOutputLimits(...)********************************************************
134-
This function will be used far more often than SetInputLimits. While
135-
the input to the controller will generally be in the 0-1023 range, which is
136-
the default already, the required output limits might be unique, like using
137-
a time window of 0-8000 needing to clamp it from 0-125.
134+
The PID controller is designed to vary its output within a given range.
135+
By default this range is 0-255, the Arduino PWM range.
138136
******************************************************************************/
139137
void QuickPID::SetOutputLimits(int16_t Min, int16_t Max)
140138
{
@@ -168,7 +166,7 @@ void QuickPID::SetMode(bool Mode)
168166
}
169167

170168
/* Initialize()****************************************************************
171-
Does all the things that need to happen to ensure a bumpless transfer
169+
Does all the things that need to happen to ensure a bumpless transfer
172170
from manual to automatic mode.
173171
******************************************************************************/
174172
void QuickPID::Initialize()

README.md

Lines changed: 151 additions & 32 deletions
Original file line numberDiff line numberDiff line change
@@ -1,56 +1,175 @@
11
# QuickPID
22

3-
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:
3+
A fast hybrid fixed-point and floating-point PID controller for Arduino.
4+
5+
### About
6+
7+
This PID controller provides a faster *read-compute-write* cycle than alternatives as it has a more efficient and reduced algorithm that avoids time consuming partial calculations, it takes advantage of fixed point math and has a faster analog read function. The `Ki` and `Kd` are scaled by time (µs) and 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 in `Compute()`.
8+
9+
### Features
10+
11+
Development began with a fork of the Arduino PID Library. Some modifications and new features have been added as follows:
412

513
- 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)
14+
- `POn` parameter now controls the setpoint weighting of Proportional on Error and Proportional on Measurement
715
- Reorganized and more efficient PID algorithm
816
- micros() timing resolution
917
- Faster analog read function
10-
- `GetError()`and `GetpOnE()`functions added for diagnostics and control benefits
18+
- `GetError()` function added
1119
- Runs a complete PID cycle (*read-compute-write*) faster than just an `analogRead()` command in Arduino
1220

1321
### Performance
1422

15-
| Compute | Kp | Ki | Kd | Step Time (µS) |
16-
| :----------------------------------- | ---- | ---- | ---- | -------------- |
17-
| QuickPID | 2.0 | 15.0 | 0.05 | 72 |
18-
| Arduino PID | 2.0 | 15.0 | 0.05 | 104 |
19-
| **analogRead, Compute, analogWrite** | | | | |
20-
| QuickPID | 2.0 | 5.0 | 0.2 | 96 |
21-
| Arduino PID | 2.0 | 5.0 | 0.2 | 224 |
22-
23-
#### Self Test Example (RC Filter):
23+
| `Compute()` | Kp | Ki | Kd | Step Time (µS) |
24+
| :----------------------------------------------------------- | ---- | ---- | ---- | -------------- |
25+
| QuickPID | 2.0 | 15.0 | 0.05 | 72 |
26+
| Arduino PID | 2.0 | 15.0 | 0.05 | 104 |
27+
| **Full PID cycle:** **`analogRead(), Compute(), analogWrite()`** | | | | |
28+
| QuickPID using `analogReadFast()` | 2.0 | 5.0 | 0.2 | 96 |
29+
| Arduino PID using `analogRead()` | 2.0 | 5.0 | 0.2 | 224 |
30+
31+
### Functions
32+
33+
[QuickPID::QuickPID Constructor](#QuickPID::QuickPID Constructor)
34+
[Compute()](#Compute())
35+
[SetTunings()](#SetTunings())
36+
[SetSampleTime()](#SetSampleTime())
37+
[SetOutputLimits()](#SetOutputLimits())
38+
[SetMode()](#SetMode())
39+
[Initialize()](#Initialize())
40+
[SetControllerDirection()](#SetControllerDirection())
41+
[Display Functions](#Display Functions())
42+
[Utility Functions](#Utility Functions())
43+
44+
### Self Test Example (RC Filter):
2445

2546
[This example](https://github.com/Dlloydev/QuickPID/wiki/QuickPID_RC_Filter) allows you to experiment with the four tuning parameters.
2647

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

29-
### Simplified PID Algorithm
50+
### Simplified PID Algorithm
51+
52+
```c++
53+
outputSum += (kpi * error) - (kpd * dInput);
54+
```
55+
56+
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 parameter controls the setpoint weighting of Proportional on Error and Proportional on Measurement. The gains for `error` (`kpi`) and measurement `dInput` (`kpd`) are calculated in the `QuickPID::SetTunings()` function as follows:
57+
58+
```c++
59+
kpi = kp * pOn + ki;
60+
kpd = kp * (1 - pOn) + kd;
61+
```
62+
63+
#### QuickPID::QuickPID Constructor
64+
65+
```c++
66+
QuickPID::QuickPID(int16_t* Input, int16_t* Output, int16_t* Setpoint,
67+
float Kp, float Ki, float Kd, float POn, bool ControllerDirection)
68+
```
69+
70+
- `Input`, `Output`, and `Setpoint` are pointers to the variables holding these values.
71+
- `Kp`, `Ki`, and `Kd` are the PID proportional, integral, and derivative gains.
72+
- `POn` is the Proportional on Error weighting value (0.0-1.0). This controls the amount of Proportional on Error and Proportional on Measurement factor that's used in the compute algorithm.
73+
- `ControllerDirection` Either DIRECT or REVERSE determines which direction the output will move for a given error. DIRECT is most common.
74+
75+
```c++
76+
QuickPID::QuickPID(int16_t* Input, int16_t* Output, int16_t* Setpoint,
77+
float Kp, float Ki, float Kd, bool ControllerDirection)
78+
```
79+
80+
This allows you to use Proportional on Error without explicitly saying so.
81+
82+
#### Compute()
83+
84+
```c++
85+
bool QuickPID::Compute()
86+
```
87+
88+
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.
89+
90+
#### SetTunings()
91+
92+
```c++
93+
void QuickPID::SetTunings(float Kp, float Ki, float Kd, float POn)
94+
```
95+
96+
This function allows the controller's dynamic performance to be adjusted. It's called automatically from the constructor, but tunings can also be adjusted on the fly during normal operation. The parameters are as described in the constructor.
97+
98+
```c++
99+
void QuickPID::SetTunings(float Kp, float Ki, float Kd)
100+
```
101+
102+
Set Tunings using the last remembered POn setting.
103+
104+
#### SetSampleTime()
105+
106+
```c++
107+
void QuickPID::SetSampleTimeUs(uint32_t NewSampleTimeUs)
108+
```
109+
110+
Sets the period, in microseconds, at which the calculation is performed. The default is 100ms.
111+
112+
#### SetOutputLimits()
113+
114+
```c++
115+
void QuickPID::SetOutputLimits(int16_t Min, int16_t Max)
116+
```
117+
118+
The PID controller is designed to vary its output within a given range. By default this range is 0-255, the Arduino PWM range.
119+
120+
#### SetMode()
121+
122+
```c++
123+
void QuickPID::SetMode(bool Mode)
124+
```
125+
126+
Allows the controller Mode to be set to `MANUAL` (0) or `AUTOMATIC` (non-zero). when the transition from manual to automatic occurs, the controller is automatically initialized.
127+
128+
#### Initialize()
30129
31-
| Proportional Term Mode | Algorithm |
32-
| --------------------------- | --------------------------------------------- |
33-
| Proportional on Error | `outputSum += (kpi * error) - (kd * dInput);` |
34-
| Proportional on Measurement | `outputSum += (ki * error) - (kpd * dInput);` |
130+
```c++
131+
void QuickPID::Initialize()
132+
```
133+
134+
Does all the things that need to happen to ensure a bumpless transfer from manual to automatic mode.
135+
136+
#### SetControllerDirection()
137+
138+
```c++
139+
void QuickPID::SetControllerDirection(bool Direction)
140+
```
141+
142+
The PID will either be connected to a DIRECT acting process (+Output leads to +Input) or a REVERSE acting process (+Output leads to -Input.) We need to know which one, because otherwise we may increase the output when we should be decreasing. This is called from the constructor.
143+
144+
#### Display Functions
145+
146+
```c++
147+
float QuickPID::GetKp()
148+
float QuickPID::GetKi()
149+
float QuickPID::GetKd()
150+
bool QuickPID::GetMode()
151+
bool QuickPID::GetDirection()
152+
int16_t QuickPID::GetError()
153+
```
154+
155+
These functions query the internal state of the PID. They're here for display purposes.
156+
157+
#### Utility Functions
158+
159+
```c++
160+
int QuickPID::analogReadFast(int ADCpin)
161+
```
35162
36-
### Variables
163+
A faster configuration of `analogRead()`where a preset of 32 is used. Works with the following defines:
37164
165+
`__AVR_ATmega328P__`
166+
`__AVR_ATtiny_Zero_One__`
167+
`__AVR_ATmega_Zero__`
168+
`__AVR_DA__`
38169
39-
| Variable | Arduino PID | QuickPID |
40-
| :----------- | :---------- | :------- |
41-
| Setpoint | double | int16_t |
42-
| Input | double | int16_t |
43-
| Output | double | int16_t |
44-
| Kp | double | float |
45-
| Ki | double | float |
46-
| Kd | double | float |
47-
| ratio | double | float |
48-
| SampleTimeUs | double | uint32_t |
49-
| outputSum | double | int16_t |
50-
| error | double | int16_t |
51-
| dInput | double | int16_t |
170+
Uses Arduino's default settings and returns `analogRead()` if the definition isn't found.
52171
53-
### Original README
172+
### Original README (Arduino PID)
54173
55174
```
56175
***************************************************************

0 commit comments

Comments
 (0)