Skip to content

Commit

Permalink
New TIMER mode
Browse files Browse the repository at this point in the history
#### QuickPID 2.3.3

- Added new `TIMER` mode which is used when the PID compute is called by an external timer function or ISR. In this mode, the timer function and SetSampleTimeUs use the same time period value. The PID compute and timer will always remain in sync because the sample time variable and calculations remain constant. See AutoTune_`TIMER` mode example [AutoTune_Filter_TIMER_Mode.ino](https://github.com/Dlloydev/QuickPID/blob/master/examples/AutoTune_Filter_TIMER_Mode/AutoTune_Filter_TIMER_Mode.ino)
  • Loading branch information
Dlloydev committed May 25, 2021
1 parent 4568146 commit ca599e0
Show file tree
Hide file tree
Showing 7 changed files with 146 additions and 35 deletions.
7 changes: 5 additions & 2 deletions README.md
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
# QuickPID [![arduino-library-badge](https://www.ardu-badge.com/badge/QuickPID.svg?)](https://www.ardu-badge.com/QuickPID)
# QuickPID ![arduino-library-badge](https://camo.githubusercontent.com/989057908f34abd0c8bc2a8d762f86ccebbe377ed9ffef8c3dfdf27a09c6dac9/68747470733a2f2f7777772e617264752d62616467652e636f6d2f62616467652f517569636b5049442e7376673f)

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.

Expand All @@ -8,6 +8,7 @@ Development began with a fork of the Arduino PID Library. Modifications and new

#### New feature Summary

- [x] `TIMER` mode for calling PID compute by an external timer function or ISR
- [x] `analogReadFast()` support for AVR (4x faster)
- [x] `analogWrite()` support for ESP32 and ESP32-S2
- [x] Variable Proportional on Error Proportional on Measurement parameter `POn`
Expand Down Expand Up @@ -103,7 +104,9 @@ The PID controller is designed to vary its output within a given range. By defa
void QuickPID::SetMode(uint8_t Mode);
```
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.
Allows the controller Mode to be set to `MANUAL` (0) or `AUTOMATIC` (1) or `TIMER` (2). when the transition from manual to automatic or timer occurs, the controller is automatically initialized.
Timer mode is used when the PID compute is called by an external timer function or ISR. In this mode, the timer function and SetSampleTimeUs use the same time period value. The PID compute and timer will always remain in sync because the sample time variable and calculations remain constant. See example [AutoTune_Filter_TIMER_Mode.ino](https://github.com/Dlloydev/QuickPID/blob/master/examples/AutoTune_Filter_TIMER_Mode/AutoTune_Filter_TIMER_Mode.ino)
#### Initialize
Expand Down
109 changes: 109 additions & 0 deletions examples/AutoTune_Filter_TIMER_Mode/AutoTune_Filter_TIMER_Mode.ino
Original file line number Diff line number Diff line change
@@ -0,0 +1,109 @@
/******************************************************************************
AutoTune Filter TIMER Mode Example
Circuit: https://github.com/Dlloydev/QuickPID/wiki/AutoTune_RC_Filter
******************************************************************************/
#include "NoDelay.h" // https://github.com/M-tech-Creations/NoDelay
#include "QuickPID.h"
void runPid(); // declare function before noDelay
noDelay LEDtime(10, runPid); // creates a noDelay varible set to 10ms, will call runPid function

const byte inputPin = 0;
const byte outputPin = 3;

const int outputMax = 255;
const int outputMin = 0;

float POn = 1.0; // mix of PonE to PonM (0.0-1.0)
bool printOrPlotter = 0; // on(1) monitor, off(0) plotter
byte outputStep = 5;
byte hysteresis = 1;
int setpoint = 341; // 1/3 of 10-bit ADC range for symetrical waveform
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;
static boolean computeNow = false;

QuickPID _myPID = QuickPID(&Input, &Output, &Setpoint, Kp, Ki, Kd, POn, QuickPID::DIRECT);

void setup() {
Serial.begin(115200);
Serial.println();
if (constrain(output, outputMin, outputMax - outputStep - 5) < output) {
Serial.println(F("AutoTune test exceeds outMax limit. Check output, hysteresis and outputStep values"));
while (1);
}
// Select one, reference: https://github.com/Dlloydev/QuickPID/wiki
//_myPID.AutoTune(tuningMethod::ZIEGLER_NICHOLS_PI);
_myPID.AutoTune(tuningMethod::ZIEGLER_NICHOLS_PID);
//_myPID.AutoTune(tuningMethod::TYREUS_LUYBEN_PI);
//_myPID.AutoTune(tuningMethod::TYREUS_LUYBEN_PID);
//_myPID.AutoTune(tuningMethod::CIANCONE_MARLIN_PI);
//_myPID.AutoTune(tuningMethod::CIANCONE_MARLIN_PID);
//_myPID.AutoTune(tuningMethod::AMIGOF_PID);
//_myPID.AutoTune(tuningMethod::PESSEN_INTEGRAL_PID);
//_myPID.AutoTune(tuningMethod::SOME_OVERSHOOT_PID);
//_myPID.AutoTune(tuningMethod::NO_OVERSHOOT_PID);

_myPID.autoTune->autoTuneConfig(outputStep, hysteresis, setpoint, output, QuickPID::DIRECT, printOrPlotter);
}

void loop() {
LEDtime.update();//will check if set time has past and if so will run set function

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::TIMER); // 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.print(",");
Serial.print("iTerm:"); Serial.print(_myPID.GetDterm()); Serial.println();
}
if (computeNow) {
Input = _myPID.analogReadFast(inputPin);
_myPID.Compute();
analogWrite(outputPin, Output);
computeNow = false;
}
}
delay(1); // adjust loop speed
}

void runPid() {
computeNow = true;
}

float avg(int inputVal) {
static int arrDat[16];
static int pos;
static long sum;
pos++;
if (pos >= 16) pos = 0;
sum = sum - arrDat[pos] + inputVal;
arrDat[pos] = inputVal;
return (float)sum / 16.0;
}
1 change: 1 addition & 0 deletions keywords.txt
Original file line number Diff line number Diff line change
Expand Up @@ -41,6 +41,7 @@ analogWriteResolution KEYWORD2

AUTOMATIC LITERAL1
MANUAL LITERAL1
TIMER LITERAL1
DIRECT LITERAL1
REVERSE LITERAL1
mode_t LITERAL1
Expand Down
4 changes: 2 additions & 2 deletions library.json
Original file line number Diff line number Diff line change
@@ -1,9 +1,9 @@
{
"name": "QuickPID",
"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.",
"description": "A fast PID controller with AutoTune and 10 tuning rules. Compatible with most Arduino and ESP32 boards.",
"license": "MIT",
"version": "2.3.2",
"version": "2.3.3",
"url": "https://github.com/Dlloydev/QuickPID",
"include": "QuickPID",
"authors":
Expand Down
4 changes: 2 additions & 2 deletions library.properties
Original file line number Diff line number Diff line change
@@ -1,8 +1,8 @@
name=QuickPID
version=2.3.2
version=2.3.3
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.
sentence=A fast PID controller with AutoTune and 10 tuning rules.
paragraph=This controller can automatically determine and set tuning parameters. Compatible with most Arduino and ESP32 boards.
category=Signal Input/Output
url=https://github.com/Dlloydev/QuickPID
Expand Down
37 changes: 17 additions & 20 deletions src/QuickPID.cpp
Original file line number Diff line number Diff line change
@@ -1,8 +1,8 @@
/**********************************************************************************
QuickPID Library for Arduino - Version 2.3.2
QuickPID Library for Arduino - Version 2.3.3
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
by gnalbandian (Gonzalo). Licensed under the MIT License.
**********************************************************************************/

#if ARDUINO >= 100
Expand All @@ -24,7 +24,7 @@ QuickPID::QuickPID(float* Input, float* Output, float* Setpoint,
myOutput = Output;
myInput = Input;
mySetpoint = Setpoint;
inAuto = false;
mode = MANUAL;

QuickPID::SetOutputLimits(0, 255); // same default as Arduino PWM limit
sampleTimeUs = 100000; // 0.1 sec default
Expand All @@ -48,10 +48,10 @@ QuickPID::QuickPID(float* Input, float* Output, float* Setpoint,
when the output is computed, false when nothing has been done.
**********************************************************************************/
bool QuickPID::Compute() {
if (!inAuto) return false;
uint32_t now = micros();
uint32_t timeChange = (now - lastTime);
if (timeChange >= sampleTimeUs) {
if (mode == MANUAL) return false;
uint32_t now = micros();
uint32_t timeChange = (now - lastTime);
if (mode == TIMER || timeChange >= sampleTimeUs) {
float input = *myInput;
float dInput = input - lastInput;
error = *mySetpoint - input;
Expand Down Expand Up @@ -87,7 +87,7 @@ bool QuickPID::Compute() {
/* SetTunings(....)************************************************************
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
be adjusted on the fly during normal operation.
******************************************************************************/
void QuickPID::SetTunings(float Kp, float Ki, float Kd, float POn = 1) {
if (Kp < 0 || Ki < 0 || Kd < 0) return;
Expand All @@ -110,7 +110,7 @@ void QuickPID::SetTunings(float Kp, float Ki, float Kd) {
}

/* SetSampleTime(.)***********************************************************
Sets the period, in microseconds, at which the calculation is performed
Sets the period, in microseconds, at which the calculation is performed.
******************************************************************************/
void QuickPID::SetSampleTimeUs(uint32_t NewSampleTimeUs) {
if (NewSampleTimeUs > 0) {
Expand All @@ -130,23 +130,22 @@ void QuickPID::SetOutputLimits(int Min, int Max) {
outMin = Min;
outMax = Max;

if (inAuto) {
if (mode != MANUAL) {
*myOutput = CONSTRAIN(*myOutput, outMin, outMax);
outputSum = CONSTRAIN(outputSum, outMin, outMax);
}
}

/* SetMode(.)*****************************************************************
Allows the controller Mode to be set to manual (0) or Automatic (non-zero)
when the transition from manual to auto occurs, the controller is
automatically initialized
Sets the controller mode to MANUAL (0), AUTOMATIC (1) or TIMER (2)
when the transition from MANUAL to AUTOMATIC or TIMER occurs, the
controller is automatically initialized.
******************************************************************************/
void QuickPID::SetMode(mode_t Mode) {
bool newAuto = (Mode == AUTOMATIC);
if (newAuto && !inAuto) { //we just went from manual to auto
if (mode == MANUAL && Mode != MANUAL) { // just went from MANUAL to AUTOMATIC or TIMER
QuickPID::Initialize();
}
inAuto = newAuto;
mode = Mode;
}

/* Initialize()****************************************************************
Expand All @@ -161,7 +160,7 @@ void QuickPID::Initialize() {

/* SetControllerDirection(.)**************************************************
The PID will either be connected to a DIRECT acting process (+Output leads
to +Input) or a REVERSE acting process(+Output leads to -Input.)
to +Input) or a REVERSE acting process(+Output leads to -Input).
******************************************************************************/
void QuickPID::SetControllerDirection(direction_t ControllerDirection) {
controllerDirection = ControllerDirection;
Expand Down Expand Up @@ -192,11 +191,9 @@ float QuickPID::GetIterm() {
float QuickPID::GetDterm() {
return dTerm;
}

QuickPID::mode_t QuickPID::GetMode() {
return inAuto ? QuickPID::AUTOMATIC : QuickPID::MANUAL;
return mode;
}

QuickPID::direction_t QuickPID::GetDirection() {
return controllerDirection;
}
Expand Down
19 changes: 10 additions & 9 deletions src/QuickPID.h
Original file line number Diff line number Diff line change
Expand Up @@ -68,7 +68,7 @@ class QuickPID {
public:

// controller mode
typedef enum { MANUAL = 0, AUTOMATIC = 1 } mode_t;
typedef enum { MANUAL = 0, AUTOMATIC = 1, TIMER = 2 } mode_t;

// DIRECT: intput increases when the error is positive. REVERSE: intput decreases when the error is positive.
typedef enum { DIRECT = 0, REVERSE = 1 } direction_t;
Expand All @@ -78,13 +78,13 @@ class QuickPID {
// Constructor. Links the PID to Input, Output, Setpoint and initial Tuning Parameters.
QuickPID(float *Input, float *Output, float *Setpoint, float Kp, float Ki, float Kd, float POn, direction_t ControllerDirection);

// Overload constructor with proportional mode. Links the PID to Input, Output, Setpoint and Tuning Parameters.
// Overload constructor with proportional ratio. Links the PID to Input, Output, Setpoint and Tuning Parameters.
QuickPID(float *Input, float *Output, float *Setpoint, float Kp, float Ki, float Kd, direction_t ControllerDirection);

// Sets PID to either Manual (0) or Auto (non-0).
// Sets PID mode to MANUAL (0), AUTOMATIC (1) or TIMER (2).
void SetMode(mode_t Mode);

// Performs the PID calculation. It should be called every time loop() cycles. ON/OFF and calculation frequency
// Performs the PID calculation. It should be called every time loop() cycles ON/OFF and calculation frequency
// can be set using SetMode and SetSampleTime respectively.
bool Compute();

Expand All @@ -101,7 +101,7 @@ class QuickPID {
// changing tunings during runtime for Adaptive control.
void SetTunings(float Kp, float Ki, float Kd);

// Overload for specifying proportional mode.
// Overload for specifying proportional ratio.
void SetTunings(float Kp, float Ki, float Kd, float POn);

// Sets the controller Direction or Action. DIRECT means the output will increase when the error is positive.
Expand All @@ -115,11 +115,11 @@ class QuickPID {
float GetKp(); // proportional gain
float GetKi(); // integral gain
float GetKd(); // derivative gain
float GetPeTerm(); // proportional on error component of output
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)
mode_t GetMode(); // MANUAL (0), AUTOMATIC (1) or TIMER (2)
direction_t GetDirection(); // DIRECT (0) or REVERSE (1)

int analogReadFast(int ADCpin);
Expand All @@ -137,9 +137,9 @@ class QuickPID {
float pmTerm;
float iTerm;
float dTerm;


float pOn; // proportional mode (0-1) default = 1 (100% Proportional on Error)

float pOn; // proportional on Error to Measurement ratio (0.0-1.0), default = 1.0
float kp; // (P)roportional Tuning Parameter
float ki; // (I)ntegral Tuning Parameter
float kd; // (D)erivative Tuning Parameter
Expand All @@ -150,6 +150,7 @@ class QuickPID {
float *myOutput; // hard link between the variables and the PID, freeing the user from having
float *mySetpoint; // to constantly tell us what these values are. With pointers we'll just know.

mode_t mode = MANUAL;
direction_t controllerDirection;
uint32_t sampleTimeUs, lastTime;
int outMin, outMax, error;
Expand Down

0 comments on commit ca599e0

Please sign in to comment.