summaryrefslogtreecommitdiff
path: root/trunk/users/bruce/GCode_Interpreter_SD/extruder.pde
blob: 8456b4aaa83f6073526fd94102bb6114d63462c8 (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
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
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
/* -*- mode: c++; c-basic-offset: 8; indent-tabs-mode: t -*- */

#include "ThermistorTable.h"

#define EXTRUDER_FORWARD true
#define EXTRUDER_REVERSE false

//these our the default values for the extruder.
int extruder_speed = 128;
int extruder_target_celsius = 0;
int extruder_max_celsius = 0;
byte extruder_heater_low = 64;
byte extruder_heater_high = 255;
byte extruder_heater_current = 0;

//this is for doing encoder based extruder control
int extruder_rpm = 0;
long extruder_delay = 0;
int extruder_error = 0;
int last_extruder_error = 0;
int extruder_error_delta = 0;
bool extruder_direction = EXTRUDER_FORWARD;

void init_extruder()
{
	//default to room temp.
	extruder_set_temperature(21);
	
	//setup our pins
	pinMode(EXTRUDER_MOTOR_DIR_PIN, OUTPUT);
	pinMode(EXTRUDER_MOTOR_SPEED_PIN, OUTPUT);
	pinMode(EXTRUDER_HEATER_PIN, OUTPUT);
	pinMode(EXTRUDER_FAN_PIN, OUTPUT);
	
	//initialize values
	digitalWrite(EXTRUDER_MOTOR_DIR_PIN, EXTRUDER_FORWARD);
	analogWrite(EXTRUDER_FAN_PIN, 0);
	analogWrite(EXTRUDER_HEATER_PIN, 0);
	analogWrite(EXTRUDER_MOTOR_SPEED_PIN, 0);
}

void extruder_set_direction(bool direction)
{
	extruder_direction = direction;
	digitalWrite(EXTRUDER_MOTOR_DIR_PIN, direction);
}

void extruder_set_speed(byte speed)
{
	analogWrite(EXTRUDER_MOTOR_SPEED_PIN, speed);
}

void extruder_set_cooler(byte speed)
{
	analogWrite(EXTRUDER_FAN_PIN, speed);
}

void extruder_set_temperature(int temp)
{
	extruder_target_celsius = temp;
	extruder_max_celsius = (int)((float)temp * 1.1);
}

/**
 *  Samples the temperature and converts it to degrees celsius.
 *  Returns degrees celsius.
 */
int extruder_get_temperature()
{
#if EXTRUDER_THERMISTOR_PIN >= 0
	return extruder_read_thermistor();
#elif EXTRUDER_THERMOCOUPLE_PIN >= 0
	return extruder_read_thermocouple();
#endif
}

/*
 * This function gives us the temperature from the thermistor in Celsius
 */
int extruder_read_thermistor()
{
	int raw = extruder_sample_temperature(EXTRUDER_THERMISTOR_PIN);

	int celsius = 0;
	byte i;

	for (i=1; i<NUMTEMPS; i++)
	{
			if (temptable[i][0] > raw)
			{
					celsius  = temptable[i-1][1] + 
						(raw - temptable[i-1][0]) * 
						(temptable[i][1] - temptable[i-1][1]) /
						(temptable[i][0] - temptable[i-1][0]);

					break;
			}
	}

	// Overflow: Set to last value in the table
	if (i == NUMTEMPS) celsius = temptable[i-1][1];
	// Clamp to byte
	if (celsius > 255) celsius = 255; 
	else if (celsius < 0) celsius = 0; 

	return celsius;
}


#if EXTRUDER_THERMOCOUPLE_PIN >= 0
/*
 * This function gives us the temperature from the thermocouple in Celsius
 */
int extruder_read_thermocouple()
{
	return ( 5.0 * extruder_sample_temperature(EXTRUDER_THERMOCOUPLE_PIN) * 100.0) / 1024.0;
}
#endif

/*
 * This function gives us an averaged sample of the analog temperature pin.
 */
int extruder_sample_temperature(byte pin)
{
	int raw = 0;
	
	//read in a certain number of samples
	for (byte i=0; i<TEMPERATURE_SAMPLES; i++)
		raw += analogRead(pin);
		
	//average the samples
	raw = raw/TEMPERATURE_SAMPLES;

	//send it back.
	return raw;
}

/*!
  Manages motor and heater based on measured temperature:
  o If temp is too low, don't start the motor
  o Adjust the heater power to keep the temperature at the target
*/
void extruder_manage_temperature()
{
	static long lastread = 0;

	if (millis() - lastread > 200)
	{
		lastread = millis();

		//make sure we know what our temp is.
		int current_celsius = extruder_get_temperature();
		byte newheat = 0;
    
		//put the heater into high mode if we're not at our target.
		if (current_celsius < extruder_target_celsius)
			newheat = extruder_heater_high;
		//put the heater on low if we're at our target.
		else if (current_celsius < extruder_max_celsius)
			newheat = extruder_heater_low;
    
		// Only update heat if it changed
		if (extruder_heater_current != newheat)
		{
			extruder_heater_current = newheat;
			analogWrite(EXTRUDER_HEATER_PIN, extruder_heater_current);
		}
	}
}