PID_v1.h
Go to the documentation of this file.
00001 #ifndef PID_v1_h
00002 #define PID_v1_h
00003 #define LIBRARY_VERSION 1.0.0
00004 
00005 class PID
00006 {
00007 
00008 
00009   public:
00010 
00011   //Constants used in some of the functions below
00012   #define AUTOMATIC     1
00013   #define MANUAL        0
00014   #define DIRECT  0
00015   #define REVERSE  1
00016 
00017   //commonly used functions **************************************************************************
00018     PID(double*, double*, double*,        // * constructor.  links the PID to the Input, Output, and 
00019         double, double, double, int);     //   Setpoint.  Initial tuning parameters are also set here
00020         
00021     void SetMode(int Mode);               // * sets PID to either Manual (0) or Auto (non-0)
00022 
00023     bool Compute();                       // * performs the PID calculation.  it should be
00024                                           //   called every time loop() cycles. ON/OFF and
00025                                           //   calculation frequency can be set using SetMode
00026                                           //   SetSampleTime respectively
00027 
00028     void SetOutputLimits(double, double); //clamps the output to a specific range. 0-255 by default, but
00029                                                                                   //it's likely the user will want to change this depending on
00030                                                                                   //the application
00031         
00032 
00033 
00034   //available but not commonly used functions ********************************************************
00035     void SetTunings(double, double,       // * While most users will set the tunings once in the 
00036                     double);              //   constructor, this function gives the user the option
00037                                           //   of changing tunings during runtime for Adaptive control
00038         void SetControllerDirection(int);         // * Sets the Direction, or "Action" of the controller. DIRECT
00039                                                                                   //   means the output will increase when error is positive. REVERSE
00040                                                                                   //   means the opposite.  it's very unlikely that this will be needed
00041                                                                                   //   once it is set in the constructor.
00042     void SetSampleTime(int);              // * sets the frequency, in Milliseconds, with which 
00043                                           //   the PID calculation is performed.  default is 100
00044                                                                                   
00045                                                                                   
00046                                                                                   
00047   //Display functions ****************************************************************
00048         double GetKp();                                           // These functions query the pid for interal values.
00049         double GetKi();                                           //  they were created mainly for the pid front-end,
00050         double GetKd();                                           // where it's important to know what is actually 
00051         int GetMode();                                            //  inside the PID.
00052         int GetDirection();                                       //
00053 
00054   private:
00055         void Initialize();
00056         
00057         double dispKp;                          // * we'll hold on to the tuning parameters in user-entered 
00058         double dispKi;                          //   format for display purposes
00059         double dispKd;                          //
00060     
00061         double kp;                  // * (P)roportional Tuning Parameter
00062     double ki;                  // * (I)ntegral Tuning Parameter
00063     double kd;                  // * (D)erivative Tuning Parameter
00064 
00065         int controllerDirection;
00066 
00067     double *myInput;              // * Pointers to the Input, Output, and Setpoint variables
00068     double *myOutput;             //   This creates a hard link between the variables and the 
00069     double *mySetpoint;           //   PID, freeing the user from having to constantly tell us
00070                                   //   what these values are.  with pointers we'll just know.
00071                           
00072         unsigned long lastTime;
00073         double ITerm, lastInput;
00074 
00075         unsigned long SampleTime;
00076         double outMin, outMax;
00077         bool inAuto;
00078 };
00079 #endif
00080 


ric_mc
Author(s): RoboTiCan
autogenerated on Thu Aug 27 2015 14:39:50