PIDFFController.c
Go to the documentation of this file.
00001 /*********************************************************************
00002 * Software License Agreement (BSD License)
00003 *
00004 *  Copyright (c) 2010, LABUST, UNIZG-FER
00005 *  All rights reserved.
00006 *
00007 *  Redistribution and use in source and binary forms, with or without
00008 *  modification, are permitted provided that the following conditions
00009 *  are met:
00010 *
00011 *   * Redistributions of source code must retain the above copyright
00012 *     notice, this list of conditions and the following disclaimer.
00013 *   * Redistributions in binary form must reproduce the above
00014 *     copyright notice, this list of conditions and the following
00015 *     disclaimer in the documentation and/or other materials provided
00016 *     with the distribution.
00017 *   * Neither the name of the LABUST nor the names of its
00018 *     contributors may be used to endorse or promote products derived
00019 *     from this software without specific prior written permission.
00020 *
00021 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032 *  POSSIBILITY OF SUCH DAMAGE.
00033 *********************************************************************/
00034 #include <labust/control/PIDFFController.h>
00035 #include <math.h>
00036 
00037 void PIDFF_modelTune(PIDBase* self,
00038                 const PT1Model* const model,
00039                 float w)
00040 {
00041         self->Kp = model->alpha*w*w;
00042         self->Ki = model->alpha/(w*w*w);
00043         self->Kd = model->alpha*w - model->beta;
00044         self->Kt = self->Tf = 0;
00045 
00046         self->model.alpha = model->alpha;
00047         self->model.beta = model->beta;
00048         self->model.betaa = model->betaa;
00049 }
00050 
00051 void PIDFF_tune(PIDBase* self, float w)
00052 {
00053         self->Kp = 2*w;
00054         self->Ki = w*w;
00055         self->Kd = self->Kt = self->Tf = 0;
00056 }
00057 
00058 void PIDFF_wffStep(PIDBase* self, float Ts, float error, float ff)
00059 {
00060         //Perform windup test if automatic mode is enabled.
00061         if (self->autoWindup == 1)
00062         {
00063                 self->windup = (self->internalState > self->output) && (error>0);
00064                 self->windup = (self->windup) ||
00065                                 ((self->internalState < self->output) && (error<0));
00066         }
00067         else
00068         {
00069                 //Experimental
00070                 //self->windup = ((self->windup >0) && (error>0)) ||
00071                 //              ((self->windup <0) && (error<0));
00072         }
00073 
00074         //Proportional term
00075         self->internalState += self->Kp*(error-self->lastError);
00076         //Integral term
00077         //Disabled if windup is in progress.
00078   if (!self->windup) self->internalState += self->Ki*Ts*error;
00079   //Derivative
00080   self->internalState += self->Kd*1/Ts*(error-2*self->lastError+self->llastError);
00081         //Feed forward term
00082         self->internalState += ff - self->lastFF;
00083         //Set final output
00084         self->output = self->internalState;
00085 
00086         if (self->autoWindup == 1)
00087         {
00088                 self->output = sat(self->output,-self->outputLimit, self->outputLimit);
00089         }
00090 
00091         self->llastError = self->lastError;
00092         self->lastError = error;
00093         self->lastRef = self->desired;
00094         self->lastFF = ff;
00095 }
00096 
00097 void PIDFF_dwffStep(PIDBase* self, float Ts, float error, float ff, float ds)
00098 {
00099         //Perform windup test if automatic mode is enabled.
00100         if (self->autoWindup == 1)
00101         {
00102                 self->windup = (self->internalState > self->output) && (error>0);
00103                 self->windup = (self->windup) ||
00104                                 ((self->internalState < self->output) && (error<0));
00105         }
00106         else
00107         {
00108                 //Experimental
00109                 //self->windup = ((self->windup >0) && (error>0)) ||
00110                 //              ((self->windup <0) && (error<0));
00111         }
00112 
00113         //Proportional term
00114         self->internalState += self->Kp*(error-self->lastError);
00115         //Integral term
00116         //Disabled if windup is in progress.
00117   if (!self->windup) self->internalState += self->Ki*Ts*error;
00118   //Derivative
00119   self->internalState += self->Kd*(self->lastDerivative - ds);
00120         //Feed forward term
00121         self->internalState += ff - self->lastFF;
00122         //Set final output
00123         self->output = self->internalState;
00124 
00125         if (self->autoWindup == 1)
00126         {
00127                 self->output = sat(self->output,-self->outputLimit, self->outputLimit);
00128         }
00129 
00130         self->lastDerivative = ds;
00131         self->llastError = self->lastError;
00132         self->lastError = error;
00133         self->lastRef = self->desired;
00134         self->lastFF = ff;
00135 }
00136 
00137 
00138 


labust_control
Author(s): Gyula Nagy
autogenerated on Fri Aug 28 2015 11:22:42