From 1626eef57f54d00eddb6f55c042adea4837661ad Mon Sep 17 00:00:00 2001 From: Dlloydev Date: Tue, 15 Jun 2021 00:04:11 -0400 Subject: [PATCH] Update - autoTune parameters `outputStep`, `hysteresis`, `Setpoint` and `Output` are now float - minimum `outputStep` is now 0 (previously 5). --- README.md | 2 +- library.json | 4 ++-- library.properties | 2 +- src/QuickPID.cpp | 14 +++++++------- src/QuickPID.h | 7 ++----- 5 files changed, 13 insertions(+), 16 deletions(-) diff --git a/README.md b/README.md index e6e9b67..28d3429 100644 --- a/README.md +++ b/README.md @@ -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. diff --git a/library.json b/library.json index 9362daf..5af1625 100644 --- a/library.json +++ b/library.json @@ -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": @@ -20,7 +20,7 @@ "license": "MIT", "homepage": "https://github.com/Dlloydev/QuickPID", "dependencies": { - "QuickPID": "~2.4.4" + "QuickPID": "~2.4.5" }, "frameworks": "*", "platforms": "*" diff --git a/library.properties b/library.properties index adbce13..8e8be56 100644 --- a/library.properties +++ b/library.properties @@ -1,5 +1,5 @@ name=QuickPID -version=2.4.4 +version=2.4.5 author=David Lloyd maintainer=David Lloyd 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. diff --git a/src/QuickPID.cpp b/src/QuickPID.cpp index 3948bce..feb0a59 100644 --- a/src/QuickPID.cpp +++ b/src/QuickPID.cpp @@ -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. @@ -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(...)************************************************************ @@ -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; @@ -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; @@ -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; diff --git a/src/QuickPID.h b/src/QuickPID.h index 96bd6a6..5d857dd 100644 --- a/src/QuickPID.h +++ b/src/QuickPID.h @@ -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); @@ -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] =