From 323d52e3801884cf58ffe5479fb9b3e23b1873f0 Mon Sep 17 00:00:00 2001 From: Dlloydev Date: Thu, 20 May 2021 10:26:47 -0400 Subject: [PATCH] Major update --- README.md | 10 +- .../AutoTune_Filter_DIRECT.ino | 68 +++--- .../AutoTune_Filter_REVERSE.ino | 39 ++-- src/QuickPID.cpp | 197 ++++++++++-------- src/QuickPID.h | 35 +++- 5 files changed, 202 insertions(+), 147 deletions(-) diff --git a/README.md b/README.md index 5397165..115fb1c 100644 --- a/README.md +++ b/README.md @@ -1,6 +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. 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. +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 @@ -164,6 +164,14 @@ Use this link for reference. Note that if you're using QuickPID, there's no need #### Change Log +#### 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. diff --git a/examples/AutoTune_Filter_DIRECT/AutoTune_Filter_DIRECT.ino b/examples/AutoTune_Filter_DIRECT/AutoTune_Filter_DIRECT.ino index 04cbcb9..d4723e2 100644 --- a/examples/AutoTune_Filter_DIRECT/AutoTune_Filter_DIRECT.ino +++ b/examples/AutoTune_Filter_DIRECT/AutoTune_Filter_DIRECT.ino @@ -23,6 +23,7 @@ int output = 85; // 1/3 of 8-bit PWM range for symetrical waveform float Input, Output, Setpoint; float Kp = 0, Ki = 0, Kd = 0; +bool pidLoop = false; QuickPID _myPID = QuickPID(&Input, &Output, &Setpoint, Kp, Ki, Kd, POn, QuickPID::DIRECT); @@ -33,46 +34,47 @@ void setup() { Serial.println(F("AutoTune test exceeds outMax limit. Check output, hysteresis and outputStep values")); while (1); } - _myPID.AutoTune(tuningRule); + _myPID.AutoTune(tuningMethod::ZIEGLER_NICHOLS_PID); _myPID.autoTune->autoTuneConfig(outputStep, hysteresis, setpoint, output, QuickPID::DIRECT, printOrPlotter); } void loop() { -if (_myPID.autoTune) // Avoid deferencing nullptr after _myPID.clearAutoTune() -{ - uint8_t autoTuningCurrentStage = autoTuneLoop(); - if(autoTuningCurrentStage < _myPID.autoTune->RUN_PID) - { - Input = avg(_myPID.analogReadFast(inputPin)); // filtered input - analogWrite(outputPin, Output); - - if (autoTuningCurrentStage == _myPID.autoTune->NEW_TUNINGS) // get new tunings - { - _myPID.autoTune->setAutoTuneConstants(&Kp, &Ki, &Kd); // set new tunings - _myPID.SetMode(QuickPID::AUTOMATIC); // setup PID - _myPID.SetTunings(Kp, Ki, Kd, POn); // apply new tunings to PID - Setpoint = 500; - } - } - else // RUN_PID stage - { - if (printOrPlotter == 0) // plotter - { - _myPID.clearAutoTune(); // releases memory used by AutoTune object - Serial.print("Setpoint:"); Serial.print(Setpoint); Serial.print(","); - Serial.print("Input:"); Serial.print(Input); Serial.print(","); - Serial.print("Output:"); Serial.print(Output); Serial.println(); - } - } - -} -else // Autotune already done (or not created) -{ - Input = _myPID.analogReadFast(inputPin); + if (_myPID.autoTune) // Avoid dereferencing nullptr after _myPID.clearAutoTune() + { + switch (_myPID.autoTune->autoTuneLoop()) { + case _myPID.autoTune->AUTOTUNE: + Input = avg(_myPID.analogReadFast(inputPin)); + analogWrite(outputPin, Output); + break; + + case _myPID.autoTune->TUNINGS: + _myPID.autoTune->setAutoTuneConstants(&Kp, &Ki, &Kd); // set new tunings + _myPID.SetMode(QuickPID::AUTOMATIC); // setup PID + _myPID.SetSampleTimeUs(10000); // 10ms + _myPID.SetTunings(Kp, Ki, Kd, POn); // apply new tunings to PID + Setpoint = 500; + break; + + case _myPID.autoTune->CLR: + if (!pidLoop) { + _myPID.clearAutoTune(); // releases memory used by AutoTune object + pidLoop = true; + } + break; + } + } + if (pidLoop) { + if (printOrPlotter == 0) { // plotter + Serial.print("Setpoint:"); Serial.print(Setpoint); Serial.print(","); + Serial.print("Input:"); Serial.print(Input); Serial.print(","); + Serial.print("Output:"); Serial.print(Output); Serial.println(); + } + Input = _myPID.analogReadFast(inputPin); _myPID.Compute(); analogWrite(outputPin, Output); -} + } + //delay(1); // adjust loop speed } float avg(int inputVal) { diff --git a/examples/AutoTune_Filter_REVERSE/AutoTune_Filter_REVERSE.ino b/examples/AutoTune_Filter_REVERSE/AutoTune_Filter_REVERSE.ino index 2e889ee..9fc6110 100644 --- a/examples/AutoTune_Filter_REVERSE/AutoTune_Filter_REVERSE.ino +++ b/examples/AutoTune_Filter_REVERSE/AutoTune_Filter_REVERSE.ino @@ -24,6 +24,7 @@ int output = 85; // 1/3 of 8-bit PWM range for symetrical waveform float Input, Output, Setpoint; float Kp = 0, Ki = 0, Kd = 0; +bool pidLoop = false; QuickPID _myPID = QuickPID(&Input, &Output, &Setpoint, Kp, Ki, Kd, POn, QuickPID::REVERSE); @@ -34,26 +35,37 @@ void setup() { Serial.println(F("AutoTune test exceeds outMax limit. Check output, hysteresis and outputStep values")); while (1); } - _myPID.AutoTune(tuningRule); + _myPID.AutoTune(tuningMethod::ZIEGLER_NICHOLS_PID); _myPID.autoTune->autoTuneConfig(outputStep, hysteresis, inputMax - setpoint, output, QuickPID::REVERSE, printOrPlotter); } void loop() { - if (_myPID.autoTune->autoTuneLoop() != _myPID.autoTune->RUN_PID) { // running autotune - Input = inputMax - avg(_myPID.analogReadFast(inputPin)); // filtered input (reverse acting) - analogWrite(outputPin, Output); - } + if (_myPID.autoTune) // Avoid dereferencing nullptr after _myPID.clearAutoTune() + { + switch (_myPID.autoTune->autoTuneLoop()) { + case _myPID.autoTune->AUTOTUNE: + Input = inputMax - avg(_myPID.analogReadFast(inputPin)); // filtered, reverse acting + analogWrite(outputPin, Output); + break; - if (_myPID.autoTune->autoTuneLoop() == _myPID.autoTune->NEW_TUNINGS) { // get new tunings - _myPID.autoTune->setAutoTuneConstants(&Kp, &Ki, &Kd); // set new tunings - _myPID.clearAutoTune(); // releases memory used by AutoTune object - _myPID.SetMode(QuickPID::AUTOMATIC); // setup PID - _myPID.SetTunings(Kp, Ki, Kd, POn); // apply new tunings to PID - Setpoint = 500; - } + case _myPID.autoTune->TUNINGS: + _myPID.autoTune->setAutoTuneConstants(&Kp, &Ki, &Kd); // set new tunings + _myPID.SetMode(QuickPID::AUTOMATIC); // setup PID + _myPID.SetSampleTimeUs(10000); // 10ms + _myPID.SetTunings(Kp, Ki, Kd, POn); // apply new tunings to PID + Setpoint = 500; + break; - if (_myPID.autoTune->autoTuneLoop() == _myPID.autoTune->RUN_PID) { // running PID + case _myPID.autoTune->CLR: + if (!pidLoop) { + _myPID.clearAutoTune(); // releases memory used by AutoTune object + pidLoop = true; + } + break; + } + } + if (pidLoop) { if (printOrPlotter == 0) { // plotter Serial.print("Setpoint:"); Serial.print(Setpoint); Serial.print(","); Serial.print("Input:"); Serial.print(Input); Serial.print(","); @@ -63,6 +75,7 @@ void loop() { _myPID.Compute(); analogWrite(outputPin, Output); } + //delay(1); // adjust loop speed } float avg(int inputVal) { diff --git a/src/QuickPID.cpp b/src/QuickPID.cpp index b675257..7dbb8f0 100644 --- a/src/QuickPID.cpp +++ b/src/QuickPID.cpp @@ -180,35 +180,11 @@ QuickPID::direction_t QuickPID::GetDirection() { return controllerDirection; } -/* Other Functions************************************************************/ +/* AutoTune Functions************************************************************/ -int QuickPID::analogReadFast(int ADCpin) { -#if defined(__AVR_ATmega328P__) - byte ADCregOriginal = ADCSRA; - ADCSRA = (ADCSRA & B11111000) | 5; // 32 prescaler - int adc = analogRead(ADCpin); - ADCSRA = ADCregOriginal; - return adc; -#elif defined(__AVR_ATtiny_Zero_One__) || defined(__AVR_ATmega_Zero__) - byte ADCregOriginal = ADC0_CTRLC; - ADC0_CTRLC = 0x54; // reduced cap, Vdd ref, 32 prescaler - int adc = analogRead(ADCpin); - ADC0_CTRLC = ADCregOriginal; - return adc; -#elif defined(__AVR_DA__) - byte ADCregOriginal = ADC0.CTRLC; - ADC0.CTRLC = ADC_PRESC_DIV32_gc; // 32 prescaler - int adc = analogRead(ADCpin); - ADC0.CTRLC = ADCregOriginal; - return adc; -#else - return analogRead(ADCpin); -# endif -} - -void QuickPID::AutoTune(uint8_t tuningRule) +void QuickPID::AutoTune(tuningMethod tuningRule) { - autoTune = new AutoTunePID(myInput, myOutput, (uint8_t)tuningRule); + autoTune = new AutoTunePID(myInput, myOutput, tuningRule); } void QuickPID::clearAutoTune() @@ -221,10 +197,11 @@ AutoTunePID::AutoTunePID() { _input = nullptr; _output = nullptr; + reset(); } -AutoTunePID::AutoTunePID(float *input, float *output, uint8_t tuningRule) +AutoTunePID::AutoTunePID(float *input, float *output, tuningMethod tuningRule) { AutoTunePID(); _input = input; @@ -234,6 +211,7 @@ AutoTunePID::AutoTunePID(float *input, float *output, uint8_t tuningRule) void AutoTunePID::reset() { + _t0 = 0; _t1 = 0; _t2 = 0; @@ -247,9 +225,11 @@ void AutoTunePID::reset() _rdAvg = 0.0; _peakHigh = 0.0; _peakLow = 0.0; + _autoTuneStage = 0; } -void AutoTunePID::autoTuneConfig(const byte outputStep, const byte hysteresis, const int atSetpoint, const int atOutput, const bool dir, const bool printOrPlotter) +void AutoTunePID::autoTuneConfig(const byte outputStep, const byte hysteresis, const int atSetpoint, + const int atOutput, const bool dir, const bool printOrPlotter) { _outputStep = outputStep; _hysteresis = hysteresis; @@ -257,128 +237,139 @@ void AutoTunePID::autoTuneConfig(const byte outputStep, const byte hysteresis, c _atOutput = atOutput; _direction = dir; _printOrPlotter = printOrPlotter; + _autoTuneStage = STABILIZING; } byte AutoTunePID::autoTuneLoop() { switch (_autoTuneStage) { + case AUTOTUNE: + return AUTOTUNE; + break; case STABILIZING: + if (_printOrPlotter == 1) Serial.print(F("Stabilizing →")); _peakHigh = _atSetpoint; _peakLow = _atSetpoint; - if (_printOrPlotter == 1) Serial.print(F("Stabilizing →")); - *_output = 0; - _autoTuneStage++; + (!_direction) ? *_output = 0 : *_output = _atOutput + _outputStep + 5; + _autoTuneStage = COARSE; + return AUTOTUNE; break; case COARSE: // coarse adjust + delay(2000); if (*_input < (_atSetpoint - _hysteresis)) { - if (_printOrPlotter == 1) Serial.print(F(" coarse →")); (!_direction) ? *_output = _atOutput + _outputStep + 5 : *_output = _atOutput - _outputStep - 5; - _autoTuneStage++; + _autoTuneStage = FINE; } + return AUTOTUNE; break; case FINE: // fine adjust if (*_input > _atSetpoint) { - if (_printOrPlotter == 1) Serial.print(F(" fine →")); (!_direction) ? *_output = _atOutput - _outputStep : *_output = _atOutput + _outputStep; - _autoTuneStage++; + _autoTuneStage = TEST; } + return AUTOTUNE; break; - case AUTOTUNE: // run AutoTune relay method + case TEST: // run AutoTune relay method if (*_input < _atSetpoint) { - if (_printOrPlotter == 1) Serial.print(F(" autotune →")); + if (_printOrPlotter == 1) Serial.print(F(" AutoTune →")); (!_direction) ? *_output = _atOutput + _outputStep : *_output = _atOutput - _outputStep; - _autoTuneStage++; + _autoTuneStage = T0; } + return AUTOTUNE; break; case T0: // get t0 if (*_input > _atSetpoint) { _t0 = micros(); if (_printOrPlotter == 1) Serial.print(F(" t0 →")); - _autoTuneStage++; + _autoTuneStage = T1; } + return AUTOTUNE; break; case T1: // get t1 if (*_input > _atSetpoint + 0.2) { _t1 = micros(); if (_printOrPlotter == 1) Serial.print(F(" t1 →")); - _autoTuneStage++; + _autoTuneStage = T2; } + return AUTOTUNE; break; case T2: // get t2 _rdAvg = *_input; if (_rdAvg > _peakHigh) _peakHigh = _rdAvg; if ((_rdAvg < _peakLow) && (_peakHigh >= (_atSetpoint + _hysteresis))) _peakLow = _rdAvg; - if (_rdAvg > _atSetpoint + _hysteresis) { _t2 = micros(); if (_printOrPlotter == 1) Serial.print(F(" t2 →")); (!_direction) ? *_output = _atOutput - _outputStep : *_output = _atOutput + _outputStep; - _autoTuneStage++; + _autoTuneStage = T3L; } + return AUTOTUNE; break; - case T3: // get t3 + case T3L: // t3 low cycle _rdAvg = *_input; if (_rdAvg > _peakHigh) _peakHigh = _rdAvg; if ((_rdAvg < _peakLow) && (_peakHigh >= (_atSetpoint + _hysteresis))) _peakLow = _rdAvg; if (_rdAvg < _atSetpoint - _hysteresis) { - if (_printOrPlotter == 1) Serial.print(F(" t3 →")); (!_direction) ? *_output = _atOutput + _outputStep : *_output = _atOutput - _outputStep; - _autoTuneStage++; + _autoTuneStage = T3H; } + return AUTOTUNE; break; - case DONE: // calculate everything + case T3H: // t3 high cycle, relay test done _rdAvg = *_input; if (_rdAvg > _peakHigh) _peakHigh = _rdAvg; if ((_rdAvg < _peakLow) && (_peakHigh >= (_atSetpoint + _hysteresis))) _peakLow = _rdAvg; if (_rdAvg > _atSetpoint + _hysteresis) { _t3 = micros(); - if (_printOrPlotter == 1) Serial.println(F(" done.")); - _autoTuneStage++; - _td = (float)(_t1 - _t0) / 1000000.0; // dead time (seconds) - _Tu = (float)(_t3 - _t2) / 1000000.0; // ultimate period (seconds) - _Ku = (float)(4 * _outputStep * 2) / (float)(3.14159 * sqrt (sq (_peakHigh - _peakLow) - sq (_hysteresis))); // ultimate gain - if (_tuningRule == 6) { //AMIGO_PID - (_td < 0.1) ? _td = 0.1 : _td = _td; - _kp = (0.2 + 0.45 * (_Tu / _td)) / _Ku; - float Ti = (((0.4 * _td) + (0.8 * _Tu)) / (_td + (0.1 * _Tu)) * _td); - float Td = (0.5 * _td * _Tu) / ((0.3 * _td) + _Tu); - _ki = _kp / Ti; - _kd = Td * _kp; - } else { //other rules - _kp = RulesContants[_tuningRule][0] / 1000.0 * _Ku; - _ki = RulesContants[_tuningRule][1] / 1000.0 * _Ku / _Tu; - _kd = RulesContants[_tuningRule][2] / 1000.0 * _Ku * _Tu; - } - if (_printOrPlotter == 1) { - // Controllability https://blog.opticontrols.com/wp-content/uploads/2011/06/td-versus-tau.png - if ((_Tu / _td + 0.0001) > 0.75) Serial.println(F("This process is easy to control.")); - else if ((_Tu / _td + 0.0001) > 0.25) Serial.println(F("This process has average controllability.")); - else Serial.println(F("This process is difficult to control.")); - Serial.print(F("Tu: ")); Serial.print(_Tu); // Ultimate Period (sec) - Serial.print(F(" td: ")); Serial.print(_td); // Dead Time (sec) - Serial.print(F(" Ku: ")); Serial.print(_Ku); // Ultimate Gain - Serial.print(F(" Kp: ")); Serial.print(_kp); - Serial.print(F(" Ki: ")); Serial.print(_ki); - Serial.print(F(" Kd: ")); Serial.println(_kd); - Serial.println(); - } + if (_printOrPlotter == 1) Serial.println(F(" t3 → done.")); + _autoTuneStage = CALC; } + return AUTOTUNE; break; - case NEW_TUNINGS: // ready to apply tunings - *_output = 0; - _autoTuneStage++; - //return NEW_TUNINGS; + case CALC: // calculations + _td = (float)(_t1 - _t0) / 1000000.0; // dead time (seconds) + _Tu = (float)(_t3 - _t2) / 1000000.0; // ultimate period (seconds) + _Ku = (float)(4 * _outputStep * 2) / (float)(3.14159 * sqrt (sq (_peakHigh - _peakLow) - sq (_hysteresis))); // ultimate gain + if (_tuningRule == tuningMethod::AMIGOF_PID) { + (_td < 0.1) ? _td = 0.1 : _td = _td; + _kp = (0.2 + 0.45 * (_Tu / _td)) / _Ku; + float Ti = (((0.4 * _td) + (0.8 * _Tu)) / (_td + (0.1 * _Tu)) * _td); + float Td = (0.5 * _td * _Tu) / ((0.3 * _td) + _Tu); + _ki = _kp / Ti; + _kd = Td * _kp; + } else { //other rules + _kp = RulesContants[(int)_tuningRule][0] / 1000.0 * _Ku; + _ki = RulesContants[(int)_tuningRule][1] / 1000.0 * _Ku / _Tu; + _kd = RulesContants[(int)_tuningRule][2] / 1000.0 * _Ku * _Tu; + } + if (_printOrPlotter == 1) { + // Controllability https://blog.opticontrols.com/wp-content/uploads/2011/06/td-versus-tau.png + if ((_Tu / _td + 0.0001) > 0.75) Serial.println(F("This process is easy to control.")); + else if ((_Tu / _td + 0.0001) > 0.25) Serial.println(F("This process has average controllability.")); + else Serial.println(F("This process is difficult to control.")); + Serial.print(F("Tu: ")); Serial.print(_Tu); // Ultimate Period (sec) + Serial.print(F(" td: ")); Serial.print(_td); // Dead Time (sec) + Serial.print(F(" Ku: ")); Serial.print(_Ku); // Ultimate Gain + Serial.print(F(" Kp: ")); Serial.print(_kp); + Serial.print(F(" Ki: ")); Serial.print(_ki); + Serial.print(F(" Kd: ")); Serial.println(_kd); + Serial.println(); + } + _autoTuneStage = TUNINGS; + return AUTOTUNE; + break; + case TUNINGS: + _autoTuneStage = CLR; + return TUNINGS; + break; + case CLR: + return CLR; + break; + default: + return CLR; break; - - case RUN_PID: // ready to apply tunings - return RUN_PID; - break; } - - if(_autoTuneStage < 1) // safety measure to avoid overflow of _autoTuneStage variable if its value is 0, which shouldn't happen never. Nonetheless... - return 0 - else - return _autoTuneStage - 1; + return CLR; } void AutoTunePID::setAutoTuneConstants(float* kp, float* ki, float* kd) @@ -387,3 +378,29 @@ void AutoTunePID::setAutoTuneConstants(float* kp, float* ki, float* kd) *ki = _ki; *kd = _kd; } + +/* Other Functions************************************************************/ + +int QuickPID::analogReadFast(int ADCpin) { +#if defined(__AVR_ATmega328P__) + byte ADCregOriginal = ADCSRA; + ADCSRA = (ADCSRA & B11111000) | 5; // 32 prescaler + int adc = analogRead(ADCpin); + ADCSRA = ADCregOriginal; + return adc; +#elif defined(__AVR_ATtiny_Zero_One__) || defined(__AVR_ATmega_Zero__) + byte ADCregOriginal = ADC0_CTRLC; + ADC0_CTRLC = 0x54; // reduced cap, Vdd ref, 32 prescaler + int adc = analogRead(ADCpin); + ADC0_CTRLC = ADCregOriginal; + return adc; +#elif defined(__AVR_DA__) + byte ADCregOriginal = ADC0.CTRLC; + ADC0.CTRLC = ADC_PRESC_DIV32_gc; // 32 prescaler + int adc = analogRead(ADCpin); + ADC0.CTRLC = ADCregOriginal; + return adc; +#else + return analogRead(ADCpin); +# endif +} diff --git a/src/QuickPID.h b/src/QuickPID.h index 676f3bb..d4b5b64 100644 --- a/src/QuickPID.h +++ b/src/QuickPID.h @@ -2,28 +2,44 @@ #ifndef QuickPID_h #define QuickPID_h +enum class tuningMethod : uint8_t +{ + ZIEGLER_NICHOLS_PI, + ZIEGLER_NICHOLS_PID, + TYREUS_LUYBEN_PI, + TYREUS_LUYBEN_PID, + CIANCONE_MARLIN_PI, + CIANCONE_MARLIN_PID, + AMIGOF_PID, + PESSEN_INTEGRAL_PID, + SOME_OVERSHOOT_PID, + NO_OVERSHOOT_PID +}; + class AutoTunePID { public: AutoTunePID(); - AutoTunePID(float *input, float *output, uint8_t tuningRule); + AutoTunePID(float *input, float *output, tuningMethod tuningRule); ~AutoTunePID() {}; void reset(); void autoTuneConfig(const byte outputStep, const byte hysteresis, const int setpoint, const int output, - const bool dir = false, const bool printOrPlotter = false); + const bool dir = false, const bool printOrPlotter = false); byte autoTuneLoop(); void setAutoTuneConstants(float* kp, float* ki, float* kd); - enum atStage : byte { STABILIZING, COARSE, FINE, AUTOTUNE, T0, T1, T2, T3, DONE, NEW_TUNINGS, RUN_PID }; + enum atStage : byte { AUTOTUNE, STABILIZING, COARSE, FINE, TEST, T0, T1, T2, T3L, T3H, CALC, TUNINGS, CLR }; private: - float *_input = nullptr; // Pointers to the Input, Output, and Setpoint variables. This creates a - float *_output = nullptr; // hard link between the variables and the PID, freeing the user from having - byte _autoTuneStage = 0; - byte _tuningRule = 0; + float *_input = nullptr; // Pointers to the Input, Output, and Setpoint variables. This creates a + float *_output = nullptr; // hard link between the variables and the PID, freeing the user from having + // float *mySetpoint = nullptr; // to constantly tell us what these values are. With pointers we'll just know. + + byte _autoTuneStage = 1; + tuningMethod _tuningRule; byte _outputStep; byte _hysteresis; - int _atSetpoint; // 1/3 of 10-bit ADC range for symetrical waveform + int _atSetpoint; // 1/3 of 10-bit ADC range for symetrical waveform int _atOutput; bool _direction = false; bool _printOrPlotter = false; @@ -73,8 +89,7 @@ class QuickPID { bool Compute(); // Automatically determines and sets the tuning parameters Kp, Ki and Kd. Use this in the setup loop. - // void AutoTune(int inputPin, int outputPin, int tuningRule, int Print, uint32_t timeout); - void AutoTune(uint8_t tuningRule); + void AutoTune(tuningMethod tuningRule); void clearAutoTune(); // Sets and clamps the output to a specific range (0-255 by default).