Initial Commit To Git Hub
There are 3 changes: - All code changes will now be here instead of on Google Code - The license has been changed to GPLv3 - Support for Arduino 1.0 was added
This commit is contained in:
53
PID_v1/Examples/PID_AdaptiveTunings/PID_AdaptiveTunings.pde
Normal file
53
PID_v1/Examples/PID_AdaptiveTunings/PID_AdaptiveTunings.pde
Normal file
@ -0,0 +1,53 @@
|
||||
/********************************************************
|
||||
* PID Adaptive Tuning Example
|
||||
* One of the benefits of the PID library is that you can
|
||||
* change the tuning parameters at any time. this can be
|
||||
* helpful if we want the controller to be agressive at some
|
||||
* times, and conservative at others. in the example below
|
||||
* we set the controller to use Conservative Tuning Parameters
|
||||
* when we're near setpoint and more agressive Tuning
|
||||
* Parameters when we're farther away.
|
||||
********************************************************/
|
||||
|
||||
#include <PID_v1.h>
|
||||
|
||||
//Define Variables we'll be connecting to
|
||||
double Setpoint, Input, Output;
|
||||
|
||||
//Define the aggressive and conservative Tuning Parameters
|
||||
double aggKp=4, aggKi=0.2, aggKd=1;
|
||||
double consKp=1, consKi=0.05, consKd=0.25;
|
||||
|
||||
//Specify the links and initial tuning parameters
|
||||
PID myPID(&Input, &Output, &Setpoint, consKp, consKi, consKd, DIRECT);
|
||||
|
||||
void setup()
|
||||
{
|
||||
//initialize the variables we're linked to
|
||||
Input = analogRead(0);
|
||||
Setpoint = 100;
|
||||
|
||||
//turn the PID on
|
||||
myPID.SetMode(AUTOMATIC);
|
||||
}
|
||||
|
||||
void loop()
|
||||
{
|
||||
Input = analogRead(0);
|
||||
|
||||
double gap = abs(Setpoint-Input); //distance away from setpoint
|
||||
if(gap<10)
|
||||
{ //we're close to setpoint, use conservative tuning parameters
|
||||
myPID.SetTunings(consKp, consKi, consKd);
|
||||
}
|
||||
else
|
||||
{
|
||||
//we're far from setpoint, use aggressive tuning parameters
|
||||
myPID.SetTunings(aggKp, aggKi, aggKd);
|
||||
}
|
||||
|
||||
myPID.Compute();
|
||||
analogWrite(3,Output);
|
||||
}
|
||||
|
||||
|
31
PID_v1/Examples/PID_Basic/PID_Basic.pde
Normal file
31
PID_v1/Examples/PID_Basic/PID_Basic.pde
Normal file
@ -0,0 +1,31 @@
|
||||
/********************************************************
|
||||
* PID Basic Example
|
||||
* Reading analog input 0 to control analog PWM output 3
|
||||
********************************************************/
|
||||
|
||||
#include <PID_v1.h>
|
||||
|
||||
//Define Variables we'll be connecting to
|
||||
double Setpoint, Input, Output;
|
||||
|
||||
//Specify the links and initial tuning parameters
|
||||
PID myPID(&Input, &Output, &Setpoint,2,5,1, DIRECT);
|
||||
|
||||
void setup()
|
||||
{
|
||||
//initialize the variables we're linked to
|
||||
Input = analogRead(0);
|
||||
Setpoint = 100;
|
||||
|
||||
//turn the PID on
|
||||
myPID.SetMode(AUTOMATIC);
|
||||
}
|
||||
|
||||
void loop()
|
||||
{
|
||||
Input = analogRead(0);
|
||||
myPID.Compute();
|
||||
analogWrite(3,Output);
|
||||
}
|
||||
|
||||
|
60
PID_v1/Examples/PID_RelayOutput/PID_RelayOutput.pde
Normal file
60
PID_v1/Examples/PID_RelayOutput/PID_RelayOutput.pde
Normal file
@ -0,0 +1,60 @@
|
||||
/********************************************************
|
||||
* PID RelayOutput Example
|
||||
* Same as basic example, except that this time, the output
|
||||
* is going to a digital pin which (we presume) is controlling
|
||||
* a relay. the pid is designed to Output an analog value,
|
||||
* but the relay can only be On/Off.
|
||||
*
|
||||
* to connect them together we use "time proportioning
|
||||
* control" it's essentially a really slow version of PWM.
|
||||
* first we decide on a window size (5000mS say.) we then
|
||||
* set the pid to adjust its output between 0 and that window
|
||||
* size. lastly, we add some logic that translates the PID
|
||||
* output into "Relay On Time" with the remainder of the
|
||||
* window being "Relay Off Time"
|
||||
********************************************************/
|
||||
|
||||
#include <PID_v1.h>
|
||||
#define RelayPin 6
|
||||
|
||||
//Define Variables we'll be connecting to
|
||||
double Setpoint, Input, Output;
|
||||
|
||||
//Specify the links and initial tuning parameters
|
||||
PID myPID(&Input, &Output, &Setpoint,2,5,1, DIRECT);
|
||||
|
||||
int WindowSize = 5000;
|
||||
unsigned long windowStartTime;
|
||||
void setup()
|
||||
{
|
||||
windowStartTime = millis();
|
||||
|
||||
//initialize the variables we're linked to
|
||||
Setpoint = 100;
|
||||
|
||||
//tell the PID to range between 0 and the full window size
|
||||
myPID.SetOutputLimits(0, WindowSize);
|
||||
|
||||
//turn the PID on
|
||||
myPID.SetMode(AUTOMATIC);
|
||||
}
|
||||
|
||||
void loop()
|
||||
{
|
||||
Input = analogRead(0);
|
||||
myPID.Compute();
|
||||
|
||||
/************************************************
|
||||
* turn the output pin on/off based on pid output
|
||||
************************************************/
|
||||
if(millis() - windowStartTime>WindowSize)
|
||||
{ //time to shift the Relay Window
|
||||
windowStartTime += WindowSize;
|
||||
}
|
||||
if(Output < millis() - windowStartTime) digitalWrite(RelayPin,HIGH);
|
||||
else digitalWrite(RelayPin,LOW);
|
||||
|
||||
}
|
||||
|
||||
|
||||
|
Reference in New Issue
Block a user