Skip to content

Commit

Permalink
Update
Browse files Browse the repository at this point in the history
- autoTune parameters `outputStep`, `hysteresis`, `Setpoint` and `Output` are now float
- minimum `outputStep` is now 0 (previously 5).
  • Loading branch information
Dlloydev committed Jun 15, 2021
1 parent a8cf244 commit 1626eef
Show file tree
Hide file tree
Showing 5 changed files with 13 additions and 16 deletions.
2 changes: 1 addition & 1 deletion README.md
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
# QuickPID ![arduino-library-badge](https://camo.githubusercontent.com/989057908f34abd0c8bc2a8d762f86ccebbe377ed9ffef8c3dfdf27a09c6dac9/68747470733a2f2f7777772e617264752d62616467652e636f6d2f62616467652f517569636b5049442e7376673f)
# QuickPID [![arduino-library-badge](https://www.ardu-badge.com/badge/QuickPID.svg?)](https://www.ardu-badge.com/QuickPID)

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 are POn and DOn settings where POn controls the mix of Proportional on Error to Proportional on Measurement and DOn controls the mix of Derivative on Error to Derivative on Measurement.

Expand Down
4 changes: 2 additions & 2 deletions library.json
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
{
"name": "QuickPID",
"version": "2.4.4",
"version": "2.4.5",
"description": "A fast PID controller with AutoTune dynamic object, 10 tuning rules, Integral anti-windup, TIMER Mode and mixing of Proportional and Derivative on Error to Measurement. Also includes analogWrite compatibility for ESP32 and ESP32-S2.",
"keywords": "PID, controller, signal",
"repository":
Expand All @@ -20,7 +20,7 @@
"license": "MIT",
"homepage": "https://github.com/Dlloydev/QuickPID",
"dependencies": {
"QuickPID": "~2.4.4"
"QuickPID": "~2.4.5"
},
"frameworks": "*",
"platforms": "*"
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.4.4
version=2.4.5
author=David Lloyd
maintainer=David Lloyd <dlloydev@testcor.ca>
sentence=A fast PID controller with AutoTune dynamic object, 10 tuning rules, Integral anti-windup, TIMER Mode and mixing of Proportional and Derivative on Error to Measurement.
Expand Down
14 changes: 7 additions & 7 deletions src/QuickPID.cpp
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
/**********************************************************************************
QuickPID Library for Arduino - Version 2.4.4
QuickPID Library for Arduino - Version 2.4.5
by dlloydev https://github.com/Dlloydev/QuickPID
Based on the Arduino PID Library and work on AutoTunePID class
by gnalbandian (Gonzalo). Licensed under the MIT License.
Expand Down Expand Up @@ -95,8 +95,8 @@ void QuickPID::SetTunings(float Kp, float Ki, float Kd, float POn = 1.0, float D
kd = Kd / SampleTimeSec;
kpe = kp * pOn;
kpm = kp * (1 - pOn);
kde = kp * dOn;
kdm = kp * (1 - dOn);
kde = kd * dOn;
kdm = kd * (1 - dOn);
}

/* SetTunings(...)************************************************************
Expand Down Expand Up @@ -234,8 +234,8 @@ void AutoTunePID::reset() {
_autoTuneStage = 0;
}

void AutoTunePID::autoTuneConfig(const byte outputStep, const byte hysteresis, const int atSetpoint,
const int atOutput, const bool dir, const bool printOrPlotter, uint32_t sampleTimeUs)
void AutoTunePID::autoTuneConfig(const float outputStep, const float hysteresis, const float atSetpoint,
const float atOutput, const bool dir, const bool printOrPlotter, uint32_t sampleTimeUs)
{
_outputStep = outputStep;
_hysteresis = hysteresis;
Expand All @@ -262,7 +262,7 @@ byte AutoTunePID::autoTuneLoop() {
_t0 = millis();
_peakHigh = _atSetpoint;
_peakLow = _atSetpoint;
(!_direction) ? *_output = 0 : *_output = _atOutput + _outputStep + 5;
(!_direction) ? *_output = 0 : *_output = _atOutput + (_outputStep * 2);
_autoTuneStage = COARSE;
return AUTOTUNE;
break;
Expand All @@ -272,7 +272,7 @@ byte AutoTunePID::autoTuneLoop() {
break;
}
if (*_input < (_atSetpoint - _hysteresis)) {
(!_direction) ? *_output = _atOutput + _outputStep + 5 : *_output = _atOutput - _outputStep - 5;
(!_direction) ? *_output = _atOutput + (_outputStep * 2) : *_output = _atOutput - (_outputStep * 2);
_autoTuneStage = FINE;
}
return AUTOTUNE;
Expand Down
7 changes: 2 additions & 5 deletions src/QuickPID.h
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@ class AutoTunePID {
~AutoTunePID() {};

void reset();
void autoTuneConfig(const byte outputStep, const byte hysteresis, const int setpoint, const int output,
void autoTuneConfig(const float outputStep, const float hysteresis, const float setpoint, const float output,
const bool dir = false, const bool printOrPlotter = false, uint32_t sampleTimeUs = 10000);
byte autoTuneLoop();
void setAutoTuneConstants(float* kp, float* ki, float* kd);
Expand All @@ -37,13 +37,10 @@ class AutoTunePID {

byte _autoTuneStage = 1;
tuningMethod _tuningRule;
byte _outputStep;
byte _hysteresis;
int _atSetpoint; // 1/3 of 10-bit ADC range for symetrical waveform
int _atOutput;
bool _direction = false;
bool _printOrPlotter = false;
uint32_t _tLoop, _tLast, _t0, _t1, _t2, _t3;
float _outputStep, _hysteresis, _atSetpoint, _atOutput;
float _Ku, _Tu, _td, _kp, _ki, _kd, _rdAvg, _peakHigh, _peakLow;

const uint16_t RulesContants[10][3] =
Expand Down

0 comments on commit 1626eef

Please sign in to comment.