Skip to content

Commit

Permalink
Update
Browse files Browse the repository at this point in the history
#### Version 2.3.2

- Removed fixed point calculations as the speed benefit was very minimal.
- Prevent integral windup if output exceeds limits.
- Added  the following new functions that return the P, I and D terms of the calculation.

```c++
    float GetPeTerm();           // proportional on error component of output
    float GetPmTerm();           // proportional on measurement component of output
    float GetIterm();            // integral component of output
    float GetDterm();            // derivative component of output
```

####
  • Loading branch information
Dlloydev committed May 24, 2021
1 parent 77c028b commit c601c20
Show file tree
Hide file tree
Showing 6 changed files with 96 additions and 152 deletions.
113 changes: 27 additions & 86 deletions README.md
Original file line number Diff line number Diff line change
@@ -1,10 +1,6 @@
# QuickPID [![arduino-library-badge](https://www.ardu-badge.com/badge/QuickPID.svg?)](https://www.ardu-badge.com/QuickPID)

QuickPID is a fast fixed/floating point implementation of the Arduino PID library with built-in [AutoTune](https://github.com/Dlloydev/QuickPID/wiki/AutoTune) class as a dynamic object to reduce memory if not used, thanks to contributions by [gnalbandian (Gonzalo)](https://github.com/gnalbandian). This controller can automatically determine and set parameters `Kp, Ki, Kd`. Additionally the Ultimate Gain `Ku`, Ultimate Period `Tu`, Dead Time `td` and determine how easy the process is to control. There are 10 tuning rules available to choose from. Also available is a POn setting that controls the mix of Proportional on Error to Proportional on Measurement.

### About

This PID controller provides a shortened *read-compute-write* cycle by taking advantage of fixed point math and using a fast analog read function.
QuickPID is an updated implementation of the Arduino PID library with a built-in [AutoTune](https://github.com/Dlloydev/QuickPID/wiki/AutoTune) class as a dynamic object to reduce memory if not used, thanks to contributions by [gnalbandian (Gonzalo)](https://github.com/gnalbandian). This controller can automatically determine and set parameters `Kp, Ki, Kd`. Additionally the Ultimate Gain `Ku`, Ultimate Period `Tu`, Dead Time `td` and determine how easy the process is to control. There are 10 tuning rules available to choose from. Also available is a POn setting that controls the mix of Proportional on Error to Proportional on Measurement.

### Features

Expand All @@ -18,7 +14,7 @@ This example allows you to experiment with the AutoTunePID class, various tuning

### Direct and Reverse Controller Action

If a positive error increases the controller's output, the controller is said to be direct acting (i.e. heating process). When a positive error decreases the controller's output, the controller is said to be reverse acting (i.e. cooling process). When the controller is set to `REVERSE` acting, the sign of the `error` and `dInput` (derivative of Input) is internally changed. All operating ranges and limits remain the same. To simulate a `REVERSE` acting process from a process that's `DIRECT` acting, the Input value needs to be "flipped". That is, if your reading from a 10-bit ADC with 0-1023 range, the input value used is (1023 - reading). See the examples `AutoTune_Filter_DIRECT.ino` and `AutoTune_Filter_REVERSE.ino` for details.
If a positive error increases the controller's output, the controller is said to be direct acting (i.e. heating process). When a positive error decreases the controller's output, the controller is said to be reverse acting (i.e. cooling process). When the controller is set to `REVERSE` acting, the sign of the `error` and `dInput` (derivative of Input) is internally changed. All operating ranges and limits remain the same. To simulate a `REVERSE` acting process from a process that's `DIRECT` acting, the Input value needs to be "flipped". That is, if your reading from a 10-bit ADC with 0-1023 range, the input value used is (1023 - reading). See the examples [AutoTune_Filter_DIRECT.ino](https://github.com/Dlloydev/QuickPID/blob/master/examples/AutoTune_Filter_DIRECT/AutoTune_Filter_DIRECT.ino) and [AutoTune_Filter_REVERSE.ino](https://github.com/Dlloydev/QuickPID/blob/master/examples/AutoTune_Filter_REVERSE/AutoTune_Filter_REVERSE.ino) for details.

### Functions

Expand All @@ -31,11 +27,11 @@ QuickPID::QuickPID(float* Input, float* Output, float* Setpoint,
- `Input`, `Output`, and `Setpoint` are pointers to the variables holding these values.
- `Kp`, `Ki`, and `Kd` are the PID proportional, integral, and derivative gains.
- `POn` is the Proportional on Error weighting value (0.0-1.0). This controls the mix of Proportional on Error (PonE) and Proportional on Measurement (PonM) that's used in the compute algorithm. Note that POn controls the PonE amount, where the remainder (1-PonE) is the PonM amount. Also, the default POn is 1
- `POn` is the Proportional on Error weighting value with range 0.0-1.0 and default 1.0 (100% Proportional on Error). This controls the mix of Proportional on Error to Proportional on Measurement.
![image](https://user-images.githubusercontent.com/63488701/118383726-986b6e80-b5ce-11eb-94b8-fdbddd4c914e.png)
- `ControllerDirection` Either DIRECT or REVERSE determines which direction the output will move for a given error. DIRECT is most common.
- `ControllerDirection` Either DIRECT or REVERSE determines which direction the output will move for a given error.
```c++
QuickPID::QuickPID(float* Input, float* Output, float* Setpoint,
Expand Down Expand Up @@ -110,22 +106,23 @@ void QuickPID::SetControllerDirection(uint8_t Direction)
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.
#### Display_Functions
#### PID Query Functions
```c++
float QuickPID::GetKp();
float QuickPID::GetKi();
float QuickPID::GetKd();
float QuickPID::GetKu();
float QuickPID::GetTu();
float QuickPID::GetTd();
uint8_t QuickPID::GetMode();
uint8_t QuickPID::GetDirection();
float GetKp(); // proportional gain
float GetKi(); // integral gain
float GetKd(); // derivative gain
float GetPeTerm(); // proportional on error component of output
float GetPmTerm(); // proportional on measurement component of output
float GetIterm(); // integral component of output
float GetDterm(); // derivative component of output
mode_t GetMode(); // MANUAL (0) or AUTOMATIC (1)
direction_t GetDirection(); // DIRECT (0) or REVERSE (1)
```

These functions query the internal state of the PID. They're here for display purposes.
These functions query the internal state of the PID.

#### Utility_Functions
#### Utility Functions

```c++
int QuickPID::analogReadFast(int ADCpin)
Expand All @@ -137,76 +134,20 @@ A faster configuration of `analogRead()`where a preset of 32 is used. If the ar
Use this link for reference. Note that if you're using QuickPID, there's no need to install the AnalogWrite library as this feature is already included.
#### Change Log
#### Version 2.3.1
- Resolved `Kp` windup as noted in issue #6. Algorithm reverts to upstream library, but with fixed point math option and newer controller direction method maintained.
- Updated AutoTune examples and documentation.
- Default AutoTune `outputStep` value in examples (and documentation) is now 5.
#### Version 2.3.0
- New AutoTune class added as a dynamic object to reduce memory if not used, thanks to contributions by [gnalbandian (Gonzalo)](https://github.com/gnalbandian).
- AutoTune now works for a reverse acting controller.
- AutoTune configuration parameters include outputStep, hysteresis, setpoint, output, direction and printOrPlotter.
- Defined tuningMethod as an enum.
- Updated AnalogWrite methods for ESP32/ESP32-S2.
#### Version 2.2.8
- AutoTune is now independent of the QuickPID library and can be run from a sketch. AutoTune is now non-blocking, no timeouts are required and it uses Input and Output variables directly.
#### Version 2.2.7
- Fixed REVERSE acting controller mode.
- now using src folder for source code
- replaced defines with enumerated types and inline functions
#### Version 2.2.6
- Changed Input, Output and Setpoint parameters to float.
- Updated compatibility with the ESP32 AnalogWrite
#### Version 2.2.2
### [Change Log](https://github.com/Dlloydev/QuickPID/wiki/Change-Log)
- Added compatibility with the ESP32 Arduino framework
- Added full featured AnalogWrite methods for ESP32 and ESP32S2
#### Latest Version 2.3.2
#### Version 2.2.1
- Removed fixed point calculations as the speed benefit was very minimal.
- Prevent integral windup if output exceeds limits.
- Added the following new functions that return the P, I and D terms of the calculation.
- Even faster AutoTune function
- AutoTune now determines the controllability of the process
- Added AMIGO_PID tuning rule
- Added `GetTd()` function to display dead time
#### Version 2.2.0
- Improved AutoTune function
- Added 8 tuning rules
- Added `GetKu()` function to display ultimate gain
- Added `GetTu()` function to display ultimate period (time constant)
- Updated example and documentation
#### Version 2.1.0
- Added AutoTune function and documentation
- Added AutoTune_RC_Filter example and documentation
#### Version 2.0.5
- Added MIT license text file
- POn defaults to 1
#### Version 2.0.4
- Added `QuickPID_AdaptiveTunings.ino`, `QuickPID_Basic.ino`, `QuickPID_PonM.ino` and `QuickPID_RelayOutput.ino` to the examples folder.
- `QuickPID_RelayOutput.ino` has the added feature of `minWindow` setting that sets the minimum on time for the relay.
#### Version 2.0.3
- Initial Version
```c++
float GetPeTerm(); // proportional on error component of output
float GetPmTerm(); // proportional on measurement component of output
float GetIterm(); // integral component of output
float GetDterm(); // derivative component of output
```

------

Expand Down
7 changes: 4 additions & 3 deletions keywords.txt
Original file line number Diff line number Diff line change
Expand Up @@ -23,9 +23,10 @@ SetSampleTimeUs KEYWORD2
GetKp KEYWORD2
GetKi KEYWORD2
GetKd KEYWORD2
GetKu KEYWORD2
GetTu KEYWORD2
GetTd KEYWORD2
GetPeTerm KEYWORD2
GetPmTerm KEYWORD2
GetIterm KEYWORD2
GetDterm KEYWORD2
GetMode KEYWORD2
GetDirection KEYWORD2
analogReadFast KEYWORD2
Expand Down
2 changes: 1 addition & 1 deletion library.json
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@
"keywords": "PID, controller, signal",
"description": "A fast fixed/floating point PID controller with AutoTune and 10 tuning rules to choose from. This controller can automatically determine and set tuning parameters. Compatible with most Arduino and ESP32 boards.",
"license": "MIT",
"version": "2.3.1",
"version": "2.3.2",
"url": "https://github.com/Dlloydev/QuickPID",
"include": "QuickPID",
"authors":
Expand Down
2 changes: 1 addition & 1 deletion library.properties
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
name=QuickPID
version=2.3.1
version=2.3.2
author=David Lloyd
maintainer=David Lloyd <dlloydev@testcor.ca>
sentence=A fast fixed/floating point PID controller with AutoTune and 10 tuning rules to choose from.
Expand Down
Loading

0 comments on commit c601c20

Please sign in to comment.