1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
|
#include "pid.h"
#if MOTHERBOARD != 2
// Based on the excellent Wikipedia PID control article.
// See http://en.wikipedia.org/wiki/PID_controller
PIDcontrol::PIDcontrol(byte hp, byte tp, bool b)
{
heat_pin = hp;
temp_pin = tp;
doingBed = b;
if(doingBed)
{
pGain = B_TEMP_PID_PGAIN;
iGain = B_TEMP_PID_IGAIN;
dGain = B_TEMP_PID_DGAIN;
} else
{
pGain = E_TEMP_PID_PGAIN;
iGain = E_TEMP_PID_IGAIN;
dGain = E_TEMP_PID_DGAIN;
}
currentTemperature = 0;
setTarget(0);
pinMode(heat_pin, OUTPUT);
pinMode(temp_pin, INPUT);
}
/*
Set the target temperature. This also
resets the PID to, for example, remove accumulated integral error from
a long period when the heater was off and the requested temperature was 0 (which it
won't go down to, even with the heater off, so the integral error grows).
*/
void PIDcontrol::setTarget(int t)
{
targetTemperature = t;
previousTime = millis();
previousError = 0;
integral = 0;
}
/*
Temperature reading function
With thanks to: Ryan Mclaughlin - http://www.arduino.cc/cgi-bin/yabb2/YaBB.pl?num=1230859336
for the MAX6675 code
*/
void PIDcontrol::internalTemperature(short table[][2])
{
#ifdef USE_THERMISTOR
int raw = 0;
for(int i = 0; i < 3; i++)
raw += analogRead(temp_pin);
raw = raw/3;
byte i;
// TODO: This should do a binary chop
for (i=1; i<NUMTEMPS; i++)
{
if (table[i][0] > raw)
{
currentTemperature = table[i-1][1] +
(raw - table[i-1][0]) *
(table[i][1] - table[i-1][1]) /
(table[i][0] - table[i-1][0]);
break;
}
}
// Overflow: Set to last value in the table
if (i >= NUMTEMPS) currentTemperature = table[i-1][1];
// Clamp to byte
//if (celsius > 255) celsius = 255;
//else if (celsius < 0) celsius = 0;
#endif
#ifdef AD595_THERMOCOUPLE
currentTemperature = ( 5.0 * analogRead(pin* 100.0) / 1024.0; //(int)(((long)500*(long)analogRead(TEMP_PIN))/(long)1024);
#endif
#ifdef MAX6675_THERMOCOUPLE
int value = 0;
byte error_tc;
digitalWrite(TC_0, 0); // Enable device
/* Cycle the clock for dummy bit 15 */
digitalWrite(SCK,1);
digitalWrite(SCK,0);
/* Read bits 14-3 from MAX6675 for the Temp
Loop for each bit reading the value
*/
for (int i=11; i>=0; i--)
{
digitalWrite(SCK,1); // Set Clock to HIGH
value += digitalRead(SO) << i; // Read data and add it to our variable
digitalWrite(SCK,0); // Set Clock to LOW
}
/* Read the TC Input inp to check for TC Errors */
digitalWrite(SCK,1); // Set Clock to HIGH
error_tc = digitalRead(SO); // Read data
digitalWrite(SCK,0); // Set Clock to LOW
digitalWrite(TC_0, 1); //Disable Device
if(error_tc)
currentTemperature = 2000;
else
currentTemperature = value/4;
#endif
}
void PIDcontrol::pidCalculation()
{
if(doingBed)
internalTemperature(bedtemptable);
else
internalTemperature(temptable);
time = millis();
float dt = 0.001*(float)(time - previousTime);
previousTime = time;
if (dt <= 0) // Don't do it when millis() has rolled over
return;
float error = (float)(targetTemperature - currentTemperature);
integral += error*dt;
float derivative = (error - previousError)/dt;
previousError = error;
int output = (int)(error*pGain + integral*iGain + derivative*dGain);
if(!doingBed && cdda[tail]->extruding())
output += EXTRUDING_INCREASE;
output = constrain(output, 0, 255);
analogWrite(heat_pin, output);
}
#endif
|