Posts Tagged ‘PID’

Arduino PID Autotune Library

Saturday, January 28th, 2012

At long last, I’ve released an Autotune Library to compliment the Arduino PID Library. When I released the current version of the PID Library, I did an insanely extensive series of posts to get people comfortable with what was going on inside.

While not nearly as in-depth, that’s the goal of this post. I’ll explain what the Autotune Library is trying to accomplish, and how it goes about its business.

Attribution

For A couple years I’ve wanted to have an Autotune Library, but due to an agreement with my employer, I wasn’t able to write one. BUT! when I found the AutotunerPID Toolkit by William Spinelli I was good to go; My company had no problem with me porting and augmenting and existing open source project.

I converted the code from matlab, made some tweaks to the peak identification code, and switched it from the Standard form (Kc, Ti, Td) to the Ideal form (Kp, Ki, Kd.) Other than that, all credit goes to Mr. Spinelli.

The Theory

The best tuning parameters (Kp, Ki, Kd,) for a PID controller are going to depend on what that controller is driving. The best tunings for a toaster oven are going to be different than the best tunings for a sous-vide cooker.

Autotuners attempt to figure out the nature of what the controller is driving, then back-calculate tuning parameters from that. There are various methods of doing this, but most involve changing the PID Output in some way then observing how the Input responds.

The method used in the library is known as the relay method. here’s how it works:

Starting at steady state (both Input and Output are steady,) the Output is stepped in one direction by some distance D. When the Input crosses a trigger line, the output changes to the other direction by distance D.

By analyzing how far apart the peaks are, and how big they are in relation to the output changes, the Autotuner can tell the difference between one type of process and another. As a result, different systems will get custom tuning parameters:

The Implementation

This works well in theory, but real-world data isn’t very cooperative. The input signal is usually noisy, which causes two main problems.

Problem #1: When to step?

Since a noisy signal is choppy, it’s likely that the trigger line will be crossed several times as the Input moves past it. This can cause mild chatter in the output, or if severe, can completely destroy things:


The way I chose to side-step this issue was to have the user specify a noise band. In effect, this creates two trigger lines. Since the distance between them is equal to the noise (if properly set) it’s less likely that multiple crossings will occur due to signal chatter.

Problem #2: Peak Identification

In a simulated world, identifying the peaks is easy: when the Input signal changes direction, that’s a minimum or a maximum (depending an which change occured.) In a noisy world however, this method fails:

Every noise blip is a direction change. To deal with this issue I added a “look-back time” parameter. It’s an awful name. If you can think of something better let me know.

At any rate, the user defines some window, say 10 seconds. The Library then compares the current point to the last ten seconds of data. If it is a min or a max, it gets flagged as a possible peak.

When the flagged point switches from being a max to a min, or vice versa, the previously flagged point is confirmed as a peak.

Another way of explaining the look-back time is that a point will be identified as a peak if it is the largest (or smallest) value within one look-back into the future or past. Like I said: awful name.

You should also know…

  • The number of cycles performed will vary between 3 and 10. The algorithm waits until the last 3 maxima have been within 5% of each other. This is trying to ensure that we’ve reached a stable oscillation and there’s no external strangeness happening. This leads me to…
  • I’m not the biggest fan of Autotune. I’ve often said, and still believe, that a moderately trained person will beat an Autotuner every day of the week. There’s just so much that can go wrong without the algorithm knowing about it. That being said, Autotune is a valuable tool to help the novice get into the ballpark.

flattr this!

Introducing the osPID

Tuesday, January 3rd, 2012

About 5 months ago I sent an out-of-the-blue email to RocketScream electronics asking if they wanted to help me build an open source PID controller. It’s been far more challenging than I expected, but today I get to announce the release of my first open source hardware project: the osPID!

(pause for applause)

The goal was to make an open equivalent to the PID controllers you can currently buy. To do this we combined the Arduino, my PID library, some open-source auto-tune code, and RocketScream’s Reflow Oven Controller Shield.

In some areas we fell short: The case, for example, isn’t nema rated. If this thing becomes popular however, there’s no reason we couldn’t fix that.

In some areas we hit our mark: form factor, interchangable I/O cards, Autotune, onboard user interface.

…And in some cases we hit out of the park: It has a java trending/configuration Application, and it costs… wait for it… $85.

I’m really proud of the work we’ve done, and there’s more to come. Let me leave you with some videos I created to help introduce this release.

Beginner:

Intermediate:

Hacker:

For more information check out the (slightly rough) website we’ve created at osPID.com/blog.

Enjoy!

flattr this!

PID Library moved to GitHub

Wednesday, December 14th, 2011

As per the request by the Arduino Team, I’ve moved the Arduino PID Library to GitHub. I’ve also used this opportunity to:

  • Make the Library Arduino 1.0 compliant
  • Release the Library under a GPLv3 License

The google code site will still be there, but there will no longer be updates.

flattr this!

A Little Teaser

Thursday, September 15th, 2011

I haven’t done many PID posts in the last couple months. Rest assured I haven’t been sleeping on that front. I’ve been working closely with RocketScream on an OSHW project that should be released soon. Here are a couple teaser pictures to (hopefully) get you drooling.

As I post this I’m on my way to Makerfaire NYC. I’ll have this with me if you’d like a closer look.

flattr this!

Sousvide-O-Mator [PID Showcase]

Wednesday, August 17th, 2011

Sous-vide BabyTop

There have been many sous vide projects floating around the tubes recently. The one I’m showcasing here was first brought to my attention by the Adafruit blog. I found out from the developer that he was in the midst of a full write-up, so I held off on posting. Now that the write-up is done, we can see that he’s put together an impressive little project.

Great documentation, excellent implementation of the PID Library, delicious, delicious meat? What’s not to love? I’m also looking forward to subsequent posts, where he promises to show “how to calibrate the beast :)

flattr this!

Reflow Oven Shield [PID Showcase]

Friday, July 22nd, 2011

The reason I created the PID library was to make it easier for people to integrate PID control into their projects. Surprisingly, it’s actually happening! I’m starting to see a lot of really cool implementations out there. As a result, I’ve decided to start a new category of post: the PID Showcase. These are projects that make me feel that all that work was worth it.

So… here’s the first one: the Reflow Oven Controller Shield from RocketScream.com
Reflow Oven Sheild

It integrates all the components necessary to turn a toaster oven into a reflow oven. Thermocouple Chip… LCD… buzzer… awesome. But the part that I love is how they completely owned the PID part of this project. Look at this reflow curve:

reflow

They made use of setpoint ramping to get the heating rates just right. The output is phenomenal. This came out of a toaster oven:

wow

Excellent work!

flattr this!

PID Q&A Group

Monday, April 25th, 2011

Over the past week I’ve had several great conversations regarding the new PID Library, and regarding PID in general. Of course those are all in my email, so you can’t see them.

This highlights another problem with the previous version of the library. The main place for online Q&A was an unwieldy thread on the Arduino forum. You could (and can) email me of course, but that’s not how some people operate.

Google Groups
DIY PID Control

So I’m trying a little experiment. I’ve created a google group in an attempt to make the Q&A experience better for everyone. If you’ve got a question, shoot! If you’ve successfully implemented a PID, please share!

(if you hurry you can be the first person, IN THE WORLD, to post on the group)First-post prize goes to Eric Miller, who gets bonus points for not saying “first!”

flattr this!

How Fast is the Arduino PID Library?

Wednesday, April 20th, 2011

A couple people have asked me about speed since v1 was released. Since I had no idea, I decided I should do a little benchmarking. (Tests were done on a Duemilanove with the ATMega168.)

The Test

#include <PID_v1.h>

double Setpoint, Input, Output;
PID myPID(&Input, &Output, &Setpoint,2,5,1, DIRECT);

void setup()
{
  Input = analogRead(0);
  Setpoint = 100;

  myPID.SetMode(AUTOMATIC);
  Serial.begin(9600);
}

void loop()
{
  unsigned long startTime = millis();
/*Do a PID calculation 10000 times*/
  for(int i=0;i<10000;i++)
  {
  Input = analogRead(0);
  myPID.Compute();
  analogWrite(3,Output);
  }
/*print the elapsed time*/
  Serial.println(millis()-startTime);
}

The code above is a modification of the Basic PID example. Rather than do the pid stuff once though, it calls it 10000 times in a row. Dividing the resulting elapsed time by 10000 gives us precision down into the microsecond range.

Not pictured in this code, I also went into PID_v1.cpp and made SampleTime=0. That ensured that every time Compute() was called, the PID equation was evaluated.

One last note. Notice that analogRead and analogWrite are in the for loop. I couldn’t think of a situation where you’d have a PID without also having those functions somewhere in the loop, so I included them in the test.

The Results

2088 mSec / 10000 = 0.21 mSec
Ok. Pretty fast. Now just for fun, I commented out the read and write code (lines 21 & 23) to see how much of the 0.21 was due to the Compute function:


826mSec / 10000 = 0.08 mSec
So the PID was only responsible for about a third of the total time. Unless I’m missing something (please tell me if I am,) it looks like the Compute function is only slightly slower than an analog read or an analog write!

Some Closing Thoughts

Looking at these results, your first inclination might be to make the sample time as small as possible (1 mSec.) After all, that’s WAY bigger than the 0.08 mSec required. 2 things to remember:

  1. There’s other code in your program. All together it may add up to more than 1mSec
  2. Even if your loop time is less than 1 mSec (say it’s 0.7 mSec,) Compute only gets called once per loop, so the pid will actually be evaluated every 1.4 mSec.

Bottom line, if you’re looking to evaluate the pid really quickly, you need to be careful to avoid weird performance.

flattr this!

Improving the Beginner’s PID: Direction

Friday, April 15th, 2011

(This is the last modification in a larger series on writing a solid PID algorithm)

The Problem

The processes the PID will be connected to fall into two groups: direct acting and reverse acting. All the examples I’ve shown so far have been direct acting. That is, an increase in the output causes an increase in the input. For reverse acting processes the opposite is true. In a refrigerator for example, an increase in cooling causes the temperature to go down. To make the beginner PID work with a reverse process, the signs of kp, ki, and kd all must be negative.

This isn’t a problem per se, but the user must choose the correct sign, and make sure that all the parameters have the same sign.

The Solution

To make the process a little simpler, I require that kp, ki, and kd all be >=0. If the user is connected to a reverse process, they specify that separately using the SetControllerDirection function. this ensures that the parameters all have the same sign, and hopefully makes things more intuitive.

The Code

/*working variables*/
unsigned long lastTime;
double Input, Output, Setpoint;
double ITerm, lastInput;
double kp, ki, kd;
int SampleTime = 1000; //1 sec
double outMin, outMax;
bool inAuto = false;

#define MANUAL 0
#define AUTOMATIC 1

#define DIRECT 0
#define REVERSE 1
int controllerDirection = DIRECT;

void Compute()
{
   if(!inAuto) return;
   unsigned long now = millis();
   int timeChange = (now - lastTime);
   if(timeChange>=SampleTime)
   {
      /*Compute all the working error variables*/
      double error = Setpoint - Input;
      ITerm+= (ki * error);
      if(ITerm > outMax) ITerm= outMax;
      else if(ITerm < outMin) ITerm= outMin;
      double dInput = (Input - lastInput);

      /*Compute PID Output*/
      Output = kp * error + ITerm- kd * dInput;
      if(Output > outMax) Output = outMax;
      else if(Output < outMin) Output = outMin;

      /*Remember some variables for next time*/
      lastInput = Input;
      lastTime = now;
   }
}

void SetTunings(double Kp, double Ki, double Kd)
{
   if (Kp<0 || Ki<0|| Kd<0) return;

  double SampleTimeInSec = ((double)SampleTime)/1000;
   kp = Kp;
   ki = Ki * SampleTimeInSec;
   kd = Kd / SampleTimeInSec;

  if(controllerDirection ==REVERSE)
   {
      kp = (0 - kp);
      ki = (0 - ki);
      kd = (0 - kd);
   }
}

void SetSampleTime(int NewSampleTime)
{
   if (NewSampleTime > 0)
   {
      double ratio  = (double)NewSampleTime
                      / (double)SampleTime;
      ki *= ratio;
      kd /= ratio;
      SampleTime = (unsigned long)NewSampleTime;
   }
}

void SetOutputLimits(double Min, double Max)
{
   if(Min > Max) return;
   outMin = Min;
   outMax = Max;

   if(Output > outMax) Output = outMax;
   else if(Output < outMin) Output = outMin;

   if(ITerm > outMax) ITerm= outMax;
   else if(ITerm < outMin) ITerm= outMin;
}

void SetMode(int Mode)
{
	bool newAuto = (Mode == AUTOMATIC);
	if(newAuto == !inAuto)
	{  /*we just went from manual to auto*/
		Initialize();
	}
	inAuto = newAuto;
}

void Initialize()
{
   lastInput = Input;
   ITerm = Output;
   if(ITerm > outMax) ITerm= outMax;
   else if(ITerm < outMin) ITerm= outMin;
}

void SetControllerDirection(int Direction)
{
   controllerDirection = Direction;
}

PID COMPLETE

And that about wraps it up. We’ve turned “The Beginner’s PID” into the most robust controller I know how to make at this time. For those readers that were looking for a detailed explanation of the PID Library, I hope you got what you came for. For those of you writing your own PID, I hope you were able to glean a few ideas that save you some cycles down the road.

Two Final Notes:

  1. If something in this series looks wrong please let me know. I may have missed something, or might just need to be clearer in my explanation. Either way I’d like to know.
  2. This is just a basic PID. There are many other issues that I intentionally left out in the name of simplicity. Off the top of my head: feed forward, reset tiebacks, integer math, different pid forms, using velocity instead of position. If there’s interest in having me explore these topics please let me know.

Creative Commons License

flattr this!

Improving the Beginner’s PID: Initialization

Friday, April 15th, 2011

(This is Modification #6 in a larger series on writing a solid PID algorithm)

The Problem

In the last section we implemented the ability to turn the PID off and on. We turned it off, but now let’s look at what happens when we turn it back on:

Yikes! The PID jumps back to the last Output value it sent, then starts adjusting from there. This results in an Input bump that we’d rather not have.

The Solution

This one is pretty easy to fix. Since we now know when we’re turning on (going from Manual to Automatic,) we just have to initialize things for a smooth transition. That means massaging the 2 stored working variables (ITerm & lastInput) to keep the output from jumping.

The Code

/*working variables*/
unsigned long lastTime;
double Input, Output, Setpoint;
double ITerm, lastInput;
double kp, ki, kd;
int SampleTime = 1000; //1 sec
double outMin, outMax;
bool inAuto = false;

#define MANUAL 0
#define AUTOMATIC 1

void Compute()
{
   if(!inAuto) return;
   unsigned long now = millis();
   int timeChange = (now - lastTime);
   if(timeChange>=SampleTime)
   {
      /*Compute all the working error variables*/
      double error = Setpoint - Input;
      ITerm+= (ki * error);
      if(ITerm> outMax) ITerm= outMax;
      else if(ITerm< outMin) ITerm= outMin;
      double dInput = (Input - lastInput);

      /*Compute PID Output*/
      Output = kp * error + ITerm- kd * dInput;
      if(Output> outMax) Output = outMax;
      else if(Output < outMin) Output = outMin;

      /*Remember some variables for next time*/
      lastInput = Input;
      lastTime = now;
   }
}

void SetTunings(double Kp, double Ki, double Kd)
{
  double SampleTimeInSec = ((double)SampleTime)/1000;
   kp = Kp;
   ki = Ki * SampleTimeInSec;
   kd = Kd / SampleTimeInSec;
}

void SetSampleTime(int NewSampleTime)
{
   if (NewSampleTime > 0)
   {
      double ratio  = (double)NewSampleTime
                      / (double)SampleTime;
      ki *= ratio;
      kd /= ratio;
      SampleTime = (unsigned long)NewSampleTime;
   }
}

void SetOutputLimits(double Min, double Max)
{
   if(Min > Max) return;
   outMin = Min;
   outMax = Max;

   if(Output > outMax) Output = outMax;
   else if(Output < outMin) Output = outMin;

   if(ITerm> outMax) ITerm= outMax;
   else if(ITerm< outMin) ITerm= outMin;
}

void SetMode(int Mode)
{
	bool newAuto = (Mode == AUTOMATIC);
	if(newAuto && !inAuto)
	{  /*we just went from manual to auto*/
		Initialize();
	}
	inAuto = newAuto;
}

void Initialize()
{
   lastInput = Input;
   ITerm = Output;
   if(ITerm> outMax) ITerm= outMax;
   else if(ITerm< outMin) ITerm= outMin;
}

We modified SetMode(…) to detect the transition from manual to automatic, and we added our initialization function. It sets ITerm=Output to take care of the integral term, and lastInput = Input to keep the derivative from spiking. The proportional term doesn’t rely on any information from the past, so it doesn’t need any initialization.

The Result

We see from the above graph that proper initialization results in a bumpless transfer from manual to automatic: exactly what we were after.
Next >>



Creative Commons License

flattr this!