PidController.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2008, Willow Garage, Inc.
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 Willow Garage 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 
00035 // Original version: Melonee Wise <mwise@willowgarage.com>
00036 #include <cstdio>
00037 #include <youbot_driver/generic/PidController.hpp>
00038 
00039 namespace youbot
00040 {
00041 
00042 PidController::PidController(double P, double I, double D, double I1, double I2) :
00043     p_gain_(P), i_gain_(I), d_gain_(D), i_max_(I1), i_min_(I2)
00044 {
00045   p_error_last_ = 0.0;
00046   p_error_ = 0.0;
00047   d_error_ = 0.0;
00048   i_error_ = 0.0;
00049   cmd_ = 0.0;
00050   last_i_error = 0.0;
00051 }
00052 
00053 PidController::~PidController()
00054 {
00055 }
00056 
00057 void PidController::initPid(double P, double I, double D, double I1, double I2)
00058 {
00059   p_gain_ = P;
00060   i_gain_ = I;
00061   d_gain_ = D;
00062   i_max_ = I1;
00063   i_min_ = I2;
00064 
00065   reset();
00066 }
00067 
00068 void PidController::reset()
00069 {
00070   p_error_last_ = 0.0;
00071   p_error_ = 0.0;
00072   d_error_ = 0.0;
00073   i_error_ = 0.0;
00074   cmd_ = 0.0;
00075 }
00076 
00077 void PidController::getGains(double &p, double &i, double &d, double &i_max, double &i_min)
00078 {
00079   p = p_gain_;
00080   i = i_gain_;
00081   d = d_gain_;
00082   i_max = i_max_;
00083   i_min = i_min_;
00084 }
00085 
00086 void PidController::setGains(double P, double I, double D, double I1, double I2)
00087 {
00088   p_gain_ = P;
00089   i_gain_ = I;
00090   d_gain_ = D;
00091   i_max_ = I1;
00092   i_min_ = I2;
00093 }
00094 
00095 double PidController::updatePid(double error, boost::posix_time::time_duration dt)
00096 {
00097   double p_term, d_term, i_term;
00098   p_error_ = error; //this is pError = pState-pTarget
00099   double deltatime = (double)dt.total_microseconds() / 1000.0; //in milli seconds
00100 
00101   if (deltatime == 0.0 || isnan(error) || isinf(error))
00102     return 0.0;
00103 
00104   // Calculate proportional contribution to command
00105   p_term = p_gain_ * p_error_;
00106 
00107   // Calculate the integral error
00108 
00109   i_error_ = last_i_error + deltatime * p_error_;
00110   last_i_error = deltatime * p_error_;
00111 
00112   //Calculate integral contribution to command
00113   i_term = i_gain_ * i_error_;
00114 
00115   // Limit i_term so that the limit is meaningful in the output
00116   if (i_term > i_max_)
00117   {
00118     i_term = i_max_;
00119     i_error_ = i_term / i_gain_;
00120   }
00121   else if (i_term < i_min_)
00122   {
00123     i_term = i_min_;
00124     i_error_ = i_term / i_gain_;
00125   }
00126 
00127   // Calculate the derivative error
00128   if (deltatime != 0)
00129   {
00130     d_error_ = (p_error_ - p_error_last_) / deltatime;
00131     p_error_last_ = p_error_;
00132   }
00133   // Calculate derivative contribution to command
00134   d_term = d_gain_ * d_error_;
00135   cmd_ = -p_term - i_term - d_term;
00136 
00137   // printf(" p_error_ %lf  i_error_ %lf  p_term %lf i_term %lf  dt %lf out %lf\n", p_error_, i_error_, p_term, i_term, deltatime, cmd_);
00138 
00139   return cmd_;
00140 }
00141 
00142 double PidController::updatePid(double error, double error_dot, boost::posix_time::time_duration dt)
00143 {
00144   double p_term, d_term, i_term;
00145   p_error_ = error; //this is pError = pState-pTarget
00146   d_error_ = error_dot;
00147   double deltatime = (double)dt.total_microseconds() / 1000.0;  //in milli seconds
00148 
00149   if (deltatime == 0.0 || isnan(error) || isinf(error) || isnan(error_dot) || isinf(error_dot))
00150     return 0.0;
00151 
00152   // Calculate proportional contribution to command
00153   p_term = p_gain_ * p_error_;
00154 
00155   // Calculate the integral error
00156   i_error_ = last_i_error + deltatime * p_error_;
00157   last_i_error = deltatime * p_error_;
00158 
00159   // i_error_ = i_error_ + deltatime * p_error_;
00160   //   printf("i_error_ %lf dt.fractional_seconds() %lf\n", i_error_, deltatime);
00161 
00162   //Calculate integral contribution to command
00163   i_term = i_gain_ * i_error_;
00164 
00165   // Limit i_term so that the limit is meaningful in the output
00166   if (i_term > i_max_)
00167   {
00168     i_term = i_max_;
00169     i_error_ = i_term / i_gain_;
00170   }
00171   else if (i_term < i_min_)
00172   {
00173     i_term = i_min_;
00174     i_error_ = i_term / i_gain_;
00175   }
00176 
00177   // Calculate derivative contribution to command
00178   d_term = d_gain_ * d_error_;
00179   cmd_ = -p_term - i_term - d_term;
00180 
00181   return cmd_;
00182 }
00183 
00184 void PidController::setCurrentCmd(double cmd)
00185 {
00186   cmd_ = cmd;
00187 }
00188 
00189 double PidController::getCurrentCmd()
00190 {
00191   return cmd_;
00192 }
00193 
00194 void PidController::getCurrentPIDErrors(double& pe, double& ie, double& de)
00195 {
00196   pe = p_error_;
00197   ie = i_error_;
00198   de = d_error_;
00199 }
00200 
00201 }


youbot_driver
Author(s): Jan Paulus
autogenerated on Mon Oct 6 2014 09:08:01