手把手教你看懂并理解Arduino PID控制库——引子

介绍

本文主要依托于Brett Beauregard大神针对Arduino平台撰写的PID控制库Arduino PID Library及其对应的帮助博客Improving the Beginner’s PID。在没有Brett Beauregard帮助之前,也尝试过按照PID控制基本理论写过PID控制程序,并成功应用于工业设备中,但从未深入考虑过将其写成适合工业控制的通用库。根据Brett Beauregard的理念,此PID库主要想为以下两类人服务:

  1. 想要从事Arduino PID控制的同志,提供一个快速入门的方法
  2. 已经拥有自己的PID控制算法,想要从中获取到一些新点子的同志。

本文在上述基础上,主要有以下几方面工作:

  1. 对Brett Beauregard的PID控制库代码进行必要的说明
  2. 对其博客教程核心思想进行必要的说明
  3. 对其依托PID控制库改进的autoPID控制库进行必要的说明。

背景

接触过PID控制的工程师应当都会对下面的公式印象深刻:

111843_CMlV_3162997.png

上述公式的具体说明就不加以说明了,请各位参考维基百科的PID controller。大部分同志可能会写出如下代码(或者类似),包括我自己

/*working variables*/
unsigned long lastTime;
double Input, Output, Setpoint;
double errSum, lastErr;
double kp, ki, kd;
void Compute()
{
   /*How long since we last calculated*/
   unsigned long now = millis();
   double timeChange = (double)(now - lastTime);
  
   /*Compute all the working error variables*/
   double error = Setpoint - Input;
   errSum += (error * timeChange);
   double dErr = (error - lastErr) / timeChange;
  
   /*Compute PID Output*/
   Output = kp * error + ki * errSum + kd * dErr;
  
   /*Remember some variables for next time*/
   lastErr = error;
   lastTime = now;
}
  
void SetTunings(double Kp, double Ki, double Kd)
{
   kp = Kp;
   ki = Ki;
   kd = Kd;
}

其中,Compute() 在需要进行PID控制量计算的任何时候被调用,在这样的代码支持下,PID控制可以工作得很好。但是,如果是一个性能较强的工业控制器,还需要考虑一下几个问题:

  1. 采样时间——改变采样时间会带来怎样的后果
  2. 微分项的影响——突然改变设定值或者微分时间,如何避免冲击
  3. PID参数改变——PID控制参数的突然改变,如何避免突变
  4. 积分参数——突然改变I参数,如何便面冲击
  5. 开关——在控制过程中,PID调节开关突然的开启及关闭
  6. 初始化——PID运行一段时候后关闭,经过一段时间再次开启,如何避免突变
  7. 调节的方向——这个不是大问题,仅仅是为了保证系统超预计的方向运行

如果上述几个问题没有太多的理解,没关系,先看一下PID库中代码是如何写的(如果仅想看上述7个问题的解决方案请跳过下一章节)。

代码注释

头文件

#ifndef PID_v1_h
#define PID_v1_h
#define LIBRARY_VERSION	1.1.1

class PID
{
public:

	//Constants used in some of the functions below
	// 这里定义的两个变量分别指代两种工作模式:AUTOMATIC 对应 PID控制开启; MANUAL 对应PID控制关闭
	#define AUTOMATIC	1
	#define MANUAL	0
	// 这里定义两个变量分别指代控制量与被控量方向:DIRECT 对应两者同向; REVERSE 对应两者反向
	// 其中同向指: 如果控制量增大,那么被控量也会增大;反之亦然。
	// 其中反向指: 如果控制量增大,那么被控量缺减小;反之亦然。
	#define DIRECT  0
	#define REVERSE  1

	//commonly used functions **************************************************************************
	//构造函数
	PID(double*, double*, double*,        // * constructor.  links the PID to the Input, Output, and 
		double, double, double, int);     //   Setpoint.  Initial tuning parameters are also set here

	// 设置自动模式还是手动模式,两者区别目前还未清楚
	void SetMode(int Mode);               // * sets PID to either Manual (0) or Auto (non-0)

	// 计算PID, 在每个计算周期都应当调用 ,计算频率和是否计算可以在setMode和SetSampleTime中指定
	bool Compute();                       // * performs the PID calculation.  it should be
										  //   called every time loop() cycles. ON/OFF and
										  //   calculation frequency can be set using SetMode
										  //   SetSampleTime respectively

	//指定输出的范围,其中0-255,表示可限制的输出范围
	void SetOutputLimits(double, double); //clamps the output to a specific range. 0-255 by default, but
										  //it's likely the user will want to change this depending on
										  //the application



	//available but not commonly used functions ********************************************************
	// 设定P、I、D参数,可以在运行的时间周期内,指定运行需要的参数
	void SetTunings(double, double,       // * While most users will set the tunings once in the 
		double);         	  //   constructor, this function gives the user the option
							  //   of changing tunings during runtime for Adaptive control

	// 设定控制器的方向,限制输出的正反向,仅需要在开始的时候设置一次
	void SetControllerDirection(int);	  // * Sets the Direction, or "Action" of the controller. DIRECT
										  //   means the output will increase when error is positive. REVERSE
										  //   means the opposite.  it's very unlikely that this will be needed
										  //   once it is set in the constructor.

	// 采样周期,以毫秒作为设置单位,默认为10
	void SetSampleTime(int);              // * sets the frequency, in Milliseconds, with which 
										  //   the PID calculation is performed.  default is 100



	 //Display functions ****************************************************************
	// 获取PID运行参数
	double GetKp();						  // These functions query the pid for interal values.
	double GetKi();						  //  they were created mainly for the pid front-end,
	double GetKd();						  // where it's important to know what is actually 
	// 获取运行模式
	int GetMode();						  //  inside the PID.
	//获取PID 方向
	int GetDirection();					  //

private:
	// 此函数初始化,还不知什么用,需要参考CPP
	void Initialize();

	double dispKp;				// * we'll hold on to the tuning parameters in user-entered 
	double dispKi;				//   format for display purposes
	double dispKd;				//

	double kp;                  // * (P)roportional Tuning Parameter
	double ki;                  // * (I)ntegral Tuning Parameter
	double kd;                  // * (D)erivative Tuning Parameter

	int controllerDirection;

	// 其中包含了INput、 OUTput以及setPoint
	double *myInput;              // * Pointers to the Input, Output, and Setpoint variables
	double *myOutput;             //   This creates a hard link between the variables and the 
	double *mySetpoint;           //   PID, freeing the user from having to constantly tell us
								  //   what these values are.  with pointers we'll just know.
	// 此3个参数需要参考CPP才知道		  
	unsigned long lastTime;
	double ITerm, lastInput;

	unsigned long SampleTime;
	double outMin, outMax;
	// 是否自动参数的标志
	bool inAuto;
};
#endif

源文件

/**********************************************************************************************
 * Arduino PID Library - Version 1.1.1
 * by Brett Beauregard <br3ttb@gmail.com> brettbeauregard.com
 * This Library is licensed under a GPLv3 License
 **********************************************************************************************/
#include "PID_v1.h"

/*Constructor (...)*********************************************************
 *    The parameters specified here are those for for which we can't set up 
 *    reliable defaults, so we need to have the user set them.
 ***************************************************************************/
PID::PID(double* Input, double* Output, double* Setpoint,
        double Kp, double Ki, double Kd, int ControllerDirection)
{
	// 赋值控制量、被控量及设定值初始地址,注意这里是地址
    myOutput = Output;
    myInput = Input;
    mySetpoint = Setpoint;
	// 初始化auto模式为false
	inAuto = false;
	
	// 默认控制量限制在0到255,此函数可以根据实际系统需要修改控制量输出限制范围
	PID::SetOutputLimits(0, 255);				//default output limit corresponds to 
												//the arduino pwm limits
	// 默认采样周期为100ms,同样可以根据需求修改
    SampleTime = 100;							//default Controller Sample Time is 0.1 seconds

	// 设置输出的方向
    PID::SetControllerDirection(ControllerDirection);
	// 设置PID 控制参数
    PID::SetTunings(Kp, Ki, Kd);

	// 用于存储PID构造时,对应的系统运行时间
	// millis()作用是获取当前系统运行时间(单位ms),此函数针对arduino;移植到别的系统,可以其他类似作用函数替代
	// 这里减去SampleTime是为了保证在构造后能力马上进行PID控制,而不需要等待到下一个SampleTime周期
    lastTime = millis()-SampleTime;				
}
 
 
/* Compute() **********************************************************************
 *     This, as they say, is where the magic happens.  this function should be called
 *   every time "void loop()" executes.  the function will decide for itself whether a new
 *   pid Output needs to be computed.  returns true when the output is computed,
 *   false when nothing has been done.
 *   此函数用于PID控制量计算,函数可以频繁的在进程中被调用。
 **********************************************************************************/ 
bool PID::Compute()
{
	// 如果没有开启PID返回 计算失败,退出;控制量不变,仍为上一次控制量
   if(!inAuto) return false;
   // 获取当前系统运行时间并求出相对上一次计算时间间隔
   unsigned long now = millis();
   unsigned long timeChange = (now - lastTime);
   // 如果时间间隔大于或者等于采样时间,那么则计算,否则不满足采样条件,计算失败,退出;
   if(timeChange>=SampleTime)
   {
      /*Compute all the working error variables*/
	   // 保存当前被控量,如果是一个实时控制系统,此时被控量可能与构造时的被控量不一致
	  double input = *myInput;
	  // 求出设定值与当前被控量之间的偏差
      double error = *mySetpoint - input;
	  // 计算积分项 此处积分项和标准PID控制方程略微有差距
      ITerm+= (ki * error);
	  // 如果 积分项超过最大限制,那么设置积分项为最大限制;同样,最小限制也做同样处理
	  // 此处为何这么做一句两句说不清楚,主要是为了PID 控制量长时间超限后,突然降低设定值,能够让系统马上反应而不会产生一个时间滞后。
      if(ITerm > outMax) ITerm= outMax;
      else if(ITerm < outMin) ITerm= outMin;

	  // 求出两个被控量之间偏差,也就是在计算周期(这里不用采用周期是因为计算周期可能会超过采样周期)被控量的变化。
	  // 其实就是微分项的 因子,但是看起来和标准表达式也不一样啊!!!
	  // 。。。。一两句也说不清楚,总的来说是为了防止控制量和被控量突变
      double dInput = (input - lastInput);
 
      /*Compute PID Output*/
	  // PID 调节算式,这就不需要说明了
      double output = kp * error + ITerm- kd * dInput;

      // 这里做限制和ITerm做限制的作用是一样的。。
	  if(output > outMax) output = outMax;
      else if(output < outMin) output = outMin;
	  *myOutput = output;
	  
      /*Remember some variables for next time*/
      lastInput = input;
      lastTime = now;
	  return true;
   }
   else return false;
}


/* 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
 * 此函数用于设定PID调节参数
 ******************************************************************************/ 
void PID::SetTunings(double Kp, double Ki, double Kd)
{
	// 如果PID参数中有小于0的参数,那么设定失败,直接退出,仍然沿用原来的参数
   if (Kp<0 || Ki<0 || Kd<0) return;
	// 仅做显示用。
   dispKp = Kp; dispKi = Ki; dispKd = Kd;
   
   // 获取采样时间,由ms转为s
   double SampleTimeInSec = ((double)SampleTime)/1000;  
   // 调整PID参数, I 和 D 参数的调节主要是为了满足采样周期改变带导致的影响,
   // 主要是 积分项和 微分项是和时间有关的参数,所以采样周期改变会导致这两项需要重新计算,这里为了减少这些工作,将采样周期变换转换我I D参数变化
   // 至于为什么可以这么做,是因为前面做了特殊处理,修改了PID标准表达式,使每一次计算对历史依赖较小
   kp = Kp;
   ki = Ki * SampleTimeInSec;
   kd = Kd / SampleTimeInSec;
 
	//  设定PID调节方向
  if(controllerDirection ==REVERSE)
   {
      kp = (0 - kp);
      ki = (0 - ki);
      kd = (0 - kd);
   }
}
  
/* SetSampleTime(...) *********************************************************
 * sets the period, in Milliseconds, at which the calculation is performed	
 ******************************************************************************/
//更新新的采样时间,同时按照比例更新ID参数
void PID::SetSampleTime(int NewSampleTime)
{
   if (NewSampleTime > 0)
   {
      double ratio  = (double)NewSampleTime
                      / (double)SampleTime;
      ki *= ratio;
      kd /= ratio;
      SampleTime = (unsigned long)NewSampleTime;
   }
}
 
/* SetOutputLimits(...)****************************************************
 *     This function will be used far more often than SetInputLimits.  while
 *  the input to the controller will generally be in the 0-1023 range (which is
 *  the default already,)  the output will be a little different.  maybe they'll
 *  be doing a time window and will need 0-8000 or something.  or maybe they'll
 *  want to clamp it from 0-125.  who knows.  at any rate, that can all be done
 *  here.
 * 此函数容易产生控制量的突变,在运行过程中,尽量不要缩小范围
 **************************************************************************/
void PID::SetOutputLimits(double Min, double Max)
{
	// 赋值限制
   if(Min >= Max) return;
   outMin = Min;
   outMax = Max;
 
   if(inAuto)
   {
	   if(*myOutput > outMax) *myOutput = outMax;
	   else if(*myOutput < outMin) *myOutput = outMin;
	 
	   if(ITerm > outMax) ITerm= outMax;
	   else if(ITerm < outMin) ITerm= outMin;
   }
}

/* 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
 ******************************************************************************/ 
void PID::SetMode(int Mode)
{
    bool newAuto = (Mode == AUTOMATIC);
	// 如果模式不一样,那么则重新初始化
    if(newAuto == !inAuto)
    {  /*we just went from manual to auto*/
        PID::Initialize();
    }
    inAuto = newAuto;
}
 
/* Initialize()****************************************************************
 *	does all the things that need to happen to ensure a bumpless transfer
 *  from manual to automatic mode.
 ******************************************************************************/ 
void PID::Initialize()
{
   ITerm = *myOutput;
   lastInput = *myInput;
   if(ITerm > outMax) ITerm = outMax;
   else if(ITerm < outMin) ITerm = outMin;
}

/* 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.)  we need to
 * know which one, because otherwise we may increase the output when we should
 * be decreasing.  This is called from the constructor.
 ******************************************************************************/
void PID::SetControllerDirection(int Direction)
{
   if(inAuto && Direction !=controllerDirection)
   {
	  kp = (0 - kp);
      ki = (0 - ki);
      kd = (0 - kd);
   }   
   controllerDirection = Direction;
}

/* Status Funcions*************************************************************
 * Just because you set the Kp=-1 doesn't mean it actually happened.  these
 * functions query the internal state of the PID.  they're here for display 
 * purposes.  this are the functions the PID Front-end uses for example
 ******************************************************************************/
double PID::GetKp(){ return  dispKp; }
double PID::GetKi(){ return  dispKi;}
double PID::GetKd(){ return  dispKd;}
int PID::GetMode(){ return  inAuto ? AUTOMATIC : MANUAL;}
int PID::GetDirection(){ return controllerDirection;}

(这里代码过长,提供下载地址)。

上述代码提供对PID库的必要注释,其中有些注释无法一两句话就能说清,特别是针对上述7个问题的解决方案,具体的代码分析,请参考下一章节。

如有不足之处请告知,^.^

下一章节将分析采样时间变化对PID控制的影响

NEXT

PS:转载请注明出处:欧阳天华

转载于:https://my.oschina.net/u/3162997/blog/809733

评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值