blob: 68cdf8e4efc2fe66d0cdb85944bbdf55cf28038f (
plain)
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
|
/*
* This controld the heated bed (if any).
* In a standard Mendel (MOTHERBOARD == 2) this
* is done by an extruder controller.
*/
#if MOTHERBOARD != 2
static PIDcontrol bPID(BED_HEATER_PIN, BED_TEMPERATURE_PIN, true);
bed::bed(byte heat, byte temp)
{
heater_pin = heat;
temp_pin = temp;
manageCount = 0;
bedPID = &bPID;
//setup our pins
pinMode(heater_pin, OUTPUT);
pinMode(temp_pin, INPUT);
analogWrite(heater_pin, 0);
setTemperature(0);
}
void bed::controlTemperature()
{
bedPID->pidCalculation();
}
void bed::waitForTemperature()
{
byte seconds = 0;
bool warming = true;
count = 0;
newT = 0;
oldT = newT;
while (true)
{
newT += getTemperature();
count++;
if(count > 5)
{
newT = newT/5;
if(newT >= bedPID->getTarget() - HALF_DEAD_ZONE)
{
warming = false;
if(seconds > WAIT_AT_TEMPERATURE)
return;
else
seconds++;
}
if(warming)
{
if(newT > oldT)
oldT = newT;
else
{
// Temp isn't increasing - extruder hardware error
temperatureError();
return;
}
}
newT = 0;
count = 0;
}
for(int i = 0; i < 1000; i++)
{
manage();
delay(1);
}
}
}
// This is a fatal error - something is wrong with the heater.
void bed::temperatureError()
{
sprintf(talkToHost.string(), "Bed temperature not rising - hard fault.");
talkToHost.setFatal();
}
#endif
|