PID_v1.cpp 7.9 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223
  1. /**********************************************************************************************
  2. * Arduino PID Library - Version 1.2.1
  3. * by Brett Beauregard <br3ttb@gmail.com> brettbeauregard.com
  4. *
  5. * This Library is licensed under the MIT License
  6. **********************************************************************************************/
  7. #if ARDUINO >= 100
  8. #include "Arduino.h"
  9. #else
  10. #include "WProgram.h"
  11. #endif
  12. #include "PID_v1.h"
  13. /*Constructor (...)*********************************************************
  14. * The parameters specified here are those for for which we can't set up
  15. * reliable defaults, so we need to have the user set them.
  16. ***************************************************************************/
  17. PID::PID(double* Input, double* Output, double* Setpoint,
  18. double Kp, double Ki, double Kd, int POn, int ControllerDirection)
  19. {
  20. myOutput = Output;
  21. myInput = Input;
  22. mySetpoint = Setpoint;
  23. inAuto = false;
  24. PID::SetOutputLimits(0, 255); //default output limit corresponds to
  25. //the arduino pwm limits
  26. SampleTime = 100; //default Controller Sample Time is 0.1 seconds
  27. PID::SetControllerDirection(ControllerDirection);
  28. PID::SetTunings(Kp, Ki, Kd, POn);
  29. lastTime = millis()-SampleTime;
  30. }
  31. /*Constructor (...)*********************************************************
  32. * To allow backwards compatability for v1.1, or for people that just want
  33. * to use Proportional on Error without explicitly saying so
  34. ***************************************************************************/
  35. PID::PID(double* Input, double* Output, double* Setpoint,
  36. double Kp, double Ki, double Kd, int ControllerDirection)
  37. :PID::PID(Input, Output, Setpoint, Kp, Ki, Kd, P_ON_E, ControllerDirection)
  38. {
  39. }
  40. /* Compute() **********************************************************************
  41. * This, as they say, is where the magic happens. this function should be called
  42. * every time "void loop()" executes. the function will decide for itself whether a new
  43. * pid Output needs to be computed. returns true when the output is computed,
  44. * false when nothing has been done.
  45. **********************************************************************************/
  46. bool PID::Compute()
  47. {
  48. if(!inAuto) return false;
  49. unsigned long now = millis();
  50. unsigned long timeChange = (now - lastTime);
  51. if(timeChange>=SampleTime)
  52. {
  53. /*Compute all the working error variables*/
  54. double input = *myInput;
  55. double error = *mySetpoint - input;
  56. double dInput = (input - lastInput);
  57. outputSum+= (ki * error);
  58. /*Add Proportional on Measurement, if P_ON_M is specified*/
  59. if(!pOnE) outputSum-= kp * dInput;
  60. if(outputSum > outMax) outputSum= outMax;
  61. else if(outputSum < outMin) outputSum= outMin;
  62. /*Add Proportional on Error, if P_ON_E is specified*/
  63. double output;
  64. if(pOnE) output = kp * error;
  65. else output = 0;
  66. /*Compute Rest of PID Output*/
  67. output += outputSum - kd * dInput;
  68. if(output > outMax) output = outMax;
  69. else if(output < outMin) output = outMin;
  70. *myOutput = output;
  71. /*Remember some variables for next time*/
  72. lastInput = input;
  73. lastTime = now;
  74. return true;
  75. }
  76. else return false;
  77. }
  78. /* SetTunings(...)*************************************************************
  79. * This function allows the controller's dynamic performance to be adjusted.
  80. * it's called automatically from the constructor, but tunings can also
  81. * be adjusted on the fly during normal operation
  82. ******************************************************************************/
  83. void PID::SetTunings(double Kp, double Ki, double Kd, int POn)
  84. {
  85. if (Kp<0 || Ki<0 || Kd<0) return;
  86. pOn = POn;
  87. pOnE = POn == P_ON_E;
  88. dispKp = Kp; dispKi = Ki; dispKd = Kd;
  89. double SampleTimeInSec = ((double)SampleTime)/1000;
  90. kp = Kp;
  91. ki = Ki * SampleTimeInSec;
  92. kd = Kd / SampleTimeInSec;
  93. if(controllerDirection ==REVERSE)
  94. {
  95. kp = (0 - kp);
  96. ki = (0 - ki);
  97. kd = (0 - kd);
  98. }
  99. }
  100. /* SetTunings(...)*************************************************************
  101. * Set Tunings using the last-rembered POn setting
  102. ******************************************************************************/
  103. void PID::SetTunings(double Kp, double Ki, double Kd){
  104. SetTunings(Kp, Ki, Kd, pOn);
  105. }
  106. /* SetSampleTime(...) *********************************************************
  107. * sets the period, in Milliseconds, at which the calculation is performed
  108. ******************************************************************************/
  109. void PID::SetSampleTime(int NewSampleTime)
  110. {
  111. if (NewSampleTime > 0)
  112. {
  113. double ratio = (double)NewSampleTime
  114. / (double)SampleTime;
  115. ki *= ratio;
  116. kd /= ratio;
  117. SampleTime = (unsigned long)NewSampleTime;
  118. }
  119. }
  120. /* SetOutputLimits(...)****************************************************
  121. * This function will be used far more often than SetInputLimits. while
  122. * the input to the controller will generally be in the 0-1023 range (which is
  123. * the default already,) the output will be a little different. maybe they'll
  124. * be doing a time window and will need 0-8000 or something. or maybe they'll
  125. * want to clamp it from 0-125. who knows. at any rate, that can all be done
  126. * here.
  127. **************************************************************************/
  128. void PID::SetOutputLimits(double Min, double Max)
  129. {
  130. if(Min >= Max) return;
  131. outMin = Min;
  132. outMax = Max;
  133. if(inAuto)
  134. {
  135. if(*myOutput > outMax) *myOutput = outMax;
  136. else if(*myOutput < outMin) *myOutput = outMin;
  137. if(outputSum > outMax) outputSum= outMax;
  138. else if(outputSum < outMin) outputSum= outMin;
  139. }
  140. }
  141. /* SetMode(...)****************************************************************
  142. * Allows the controller Mode to be set to manual (0) or Automatic (non-zero)
  143. * when the transition from manual to auto occurs, the controller is
  144. * automatically initialized
  145. ******************************************************************************/
  146. void PID::SetMode(int Mode)
  147. {
  148. bool newAuto = (Mode == AUTOMATIC);
  149. if(newAuto && !inAuto)
  150. { /*we just went from manual to auto*/
  151. PID::Initialize();
  152. }
  153. inAuto = newAuto;
  154. }
  155. /* Initialize()****************************************************************
  156. * does all the things that need to happen to ensure a bumpless transfer
  157. * from manual to automatic mode.
  158. ******************************************************************************/
  159. void PID::Initialize()
  160. {
  161. outputSum = *myOutput;
  162. lastInput = *myInput;
  163. if(outputSum > outMax) outputSum = outMax;
  164. else if(outputSum < outMin) outputSum = outMin;
  165. }
  166. /* SetControllerDirection(...)*************************************************
  167. * The PID will either be connected to a DIRECT acting process (+Output leads
  168. * to +Input) or a REVERSE acting process(+Output leads to -Input.) we need to
  169. * know which one, because otherwise we may increase the output when we should
  170. * be decreasing. This is called from the constructor.
  171. ******************************************************************************/
  172. void PID::SetControllerDirection(int Direction)
  173. {
  174. if(inAuto && Direction !=controllerDirection)
  175. {
  176. kp = (0 - kp);
  177. ki = (0 - ki);
  178. kd = (0 - kd);
  179. }
  180. controllerDirection = Direction;
  181. }
  182. /* Status Funcions*************************************************************
  183. * Just because you set the Kp=-1 doesn't mean it actually happened. these
  184. * functions query the internal state of the PID. they're here for display
  185. * purposes. this are the functions the PID Front-end uses for example
  186. ******************************************************************************/
  187. double PID::GetKp(){ return dispKp; }
  188. double PID::GetKi(){ return dispKi;}
  189. double PID::GetKd(){ return dispKd;}
  190. int PID::GetMode(){ return inAuto ? AUTOMATIC : MANUAL;}
  191. int PID::GetDirection(){ return controllerDirection;}