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
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
|
Index: process_g_code.pde
===================================================================
--- process_g_code.pde (revision 3145)
+++ process_g_code.pde (working copy)
@@ -214,6 +214,19 @@
{
last_gcode_g = gc.G; /* remember this for future instructions */
fp = where_i_am;
+#ifdef MODIFIER_PIN
+ modifier = analogRead(MODIFIER_PIN); // Erik
+if(((modifier - modifier_old) > 3) || ((modifier - modifier_old) < -3))
+{
+ Serial.print("Modifier: ");
+ Serial.println(modifier);
+ modifier_old = modifier;
+}
+#endif
+ // Debug Erik:
+ //Serial.print("Modifier: ");
+ //Serial.println(modifier/512);
+
if (abs_mode)
{
if (gc.seen & GCODE_X)
@@ -223,7 +236,28 @@
if (gc.seen & GCODE_Z)
fp.z = gc.Z;
if (gc.seen & GCODE_E)
- fp.e = gc.E;
+#ifdef MODIFIER_PIN
+if(gc.E<0)
+{
+ Serial.print("Reversing: ");
+ Serial.print(gc.E);
+ Serial.print(", extr pos bef: ");
+ Serial.print(fp.e);
+ fp.e += gc.E*(modifier/512); // Erik
+ Serial.print(", extr pos after: ");
+ Serial.println(fp.e);
+} else
+{
+ fp.e += gc.E*(modifier/512); // Erik
+ Serial.print("fp.e is: ");
+ Serial.println(fp.e);
+}
+ // Erik: Make forced incremental
+#else
+ fp.e += gc.E; // Erik
+// fp.e += gc.E; //ERIK: normaal niet aditive!
+
+#endif
}
else
{
@@ -234,13 +268,20 @@
if (gc.seen & GCODE_Z)
fp.z += gc.Z;
if (gc.seen & GCODE_E)
- fp.e += gc.E;
+#ifndef MODIFIER_PIN
+ fp.e += gc.E;
+#else
+ fp.e += gc.E*(modifier/512); // Erik
+#endif
}
// Get feedrate if supplied - feedrates are always absolute???
if ( gc.seen & GCODE_F )
- fp.f = gc.F;
-
+//#ifdef MODIFIER_PIN
+ fp.f = gc.F*(modifier_speed/512); // ERIK
+////#else
+// fp.f = gc.F;
+//#endif
// Process the buffered move commands first
// If we get one, return immediately
Index: FiveD_GCode_Interpreter.pde
===================================================================
--- FiveD_GCode_Interpreter.pde (revision 3145)
+++ FiveD_GCode_Interpreter.pde (working copy)
@@ -18,7 +18,6 @@
#include "cartesian_dda.h"
// Inline interrupt control functions
-
inline void enableTimerInterrupt()
{
TIMSK1 |= (1<<OCIE1A);
@@ -38,7 +37,6 @@
{
TCNT2 = 0;
}
-
char debugstring[COMMAND_SIZE];
// Maintain a list of extruders...
@@ -68,7 +66,6 @@
// Our interrupt function
-
SIGNAL(SIG_OUTPUT_COMPARE1A)
{
disableTimerInterrupt();
@@ -81,9 +78,18 @@
enableTimerInterrupt();
}
+//ERIK
+#ifdef MODIFIER_PIN
+double modifier = 500.0;
+double modifier_old = 1.0;
+#endif
+double modifier_speed = 512.0; //ERIK
+
void setup()
{
+
disableTimerInterrupt();
+ // This screws with PWM :(
setupTimerInterrupt();
debugstring[0] = 0;
extruder_in_use = 0;
@@ -105,12 +111,39 @@
where_i_am.e = 0.0;
where_i_am.f = SLOW_XY_FEEDRATE;
- Serial.begin(19200);
+ Serial.begin(57600);
Serial.println("start");
setTimer(DEFAULT_TICK);
enableTimerInterrupt();
+
+ // ERIK:
+#ifdef MODIFIER_PIN
+ pinMode(MODIFIER_PIN,INPUT);
+#endif
+
}
+byte softPWMduty = 0;
+byte softPWMcount = 0;
+int PWMstate = HIGH;
+static void softPWM()
+{
+ if(softPWMduty == softPWMcount)
+ {
+ PWMstate = LOW;
+ }
+ digitalWrite(12,PWMstate);
+
+ if(softPWMcount<254)
+ softPWMcount++;
+ else
+ {
+ PWMstate = HIGH;
+ softPWMcount=0;
+ }
+}
+
+
void loop()
{
manage_all_extruders();
@@ -177,7 +210,6 @@
//******************************************************************************************
// Interrupt functions
-
void setupTimerInterrupt()
{
//clear the registers
@@ -199,7 +231,7 @@
TCCR1A &= ~(1<<COM1B0);
//start off with a slow frequency.
- setTimerResolution(4);
+ setTimerResolution(5);
setTimerCeiling(65535);
}
Index: cartesian_dda.pde
===================================================================
--- cartesian_dda.pde (revision 3145)
+++ cartesian_dda.pde (working copy)
@@ -188,6 +188,10 @@
do
{
+ // ERIK NEW:
+ softPWM();
+
+
x_can_step = can_step(X_MIN_PIN, X_MAX_PIN, current_steps.x, target_steps.x, x_direction);
y_can_step = can_step(Y_MIN_PIN, Y_MAX_PIN, current_steps.y, target_steps.y, y_direction);
z_can_step = can_step(Z_MIN_PIN, Z_MAX_PIN, current_steps.z, target_steps.z, z_direction);
@@ -335,6 +339,7 @@
#else
digitalWrite(Z_DIR_PIN, z_direction);
#endif
+delayMicroseconds(110);//ERIK: FIXME Dit kost misschien te veel tijd maar nu voldoen we wel aan de specs van de driver IC.
if(e_direction)
ext->set_direction(1);
else
@@ -343,7 +348,6 @@
//turn on steppers to start moving =)
enable_steppers();
-
// extcount = 0;
setTimer(DEFAULT_TICK);
@@ -391,11 +395,15 @@
{
#ifdef SANGUINO
if(delta_steps.x)
- digitalWrite(X_ENABLE_PIN, ENABLE_ON);
+ digitalWrite(X_ENABLE_PIN, LOW);// ERIK: dit is een inverted boardje.
if(delta_steps.y)
- digitalWrite(Y_ENABLE_PIN, ENABLE_ON);
+ digitalWrite(Y_ENABLE_PIN, LOW);// ERIK dit zelfbouw board luistert niet, maar toch...
if(delta_steps.z)
+//#ifdef MOTHERBOARD_ERIK2
+// digitalWrite(Z_ENABLE_PIN, ENABLE_ON);
+//#else
digitalWrite(Z_ENABLE_PIN, ENABLE_ON);
+//#endif
if(delta_steps.e)
ext->enableStep();
#endif
@@ -407,8 +415,9 @@
{
#ifdef SANGUINO
//disable our steppers
- digitalWrite(X_ENABLE_PIN, !ENABLE_ON);
- digitalWrite(Y_ENABLE_PIN, !ENABLE_ON);
+ // ERIK: let op: X_ENABLE_PIN == Y_ENABLE_PIN
+ //digitalWrite(X_ENABLE_PIN, ENABLE_ON);// ERIK: dit is een inverted board
+ //digitalWrite(Y_ENABLE_PIN, ENABLE_ON);// ERIK: dit is een inverted board, luistert alleen niet naar enable..
digitalWrite(Z_ENABLE_PIN, !ENABLE_ON);
// Disabling the extrude stepper causes the backpressure to
Index: extruder.pde
===================================================================
--- extruder.pde (revision 3145)
+++ extruder.pde (working copy)
@@ -1,4 +1,3 @@
-
#include "parameters.h"
#include "pins.h"
#include "ThermistorTable.h"
@@ -24,20 +23,21 @@
//setup our pins
pinMode(motor_dir_pin, OUTPUT);
pinMode(motor_speed_pin, OUTPUT);
- pinMode(heater_pin, OUTPUT);
+ //NOT NEEDED: pinMode(heater_pin, OUTPUT);
pinMode(temp_pin, INPUT);
- pinMode(valve_dir_pin, OUTPUT);
- pinMode(valve_en_pin, OUTPUT);
+ //pinMode(valve_dir_pin, OUTPUT);
+ //pinMode(valve_en_pin, OUTPUT);
//initialize values
digitalWrite(motor_dir_pin, EXTRUDER_FORWARD);
-
- analogWrite(heater_pin, 0);
- analogWrite(motor_speed_pin, 0);
- digitalWrite(valve_dir_pin, false);
- digitalWrite(valve_en_pin, 0);
+ analogWrite(heater_pin, 64);
+ //digitalWrite(heater_pin, LOW);//ERIK: changed to digital, LOW
+ digitalWrite(motor_speed_pin, 0);// ERIK: changed to digital
+ //digitalWrite(valve_dir_pin, false);
+ ///digitalWrite(valve_en_pin, 0);
+
// The step enable pin and the fan pin are the same...
// We can have one, or the other, but not both
@@ -51,12 +51,26 @@
analogWrite(fan_pin, 0);
}
- //these our the default values for the extruder.
+// From makerbot branch:
+#if TEMP_PID
+ temp_iState = 0;
+ temp_dState = 0;
+ temp_pGain = TEMP_PID_PGAIN;
+ temp_iGain = TEMP_PID_IGAIN;
+ temp_dGain = TEMP_PID_DGAIN;
+
+ temp_pid_update_windup();
+#endif
+
+ temp_control_enabled = true;
+ current_temperature = 0;
+ target_temperature = 100; // target_celcius
+ max_temperature = 0; // max_celcius
+
+ //these our the default values for the extruder.
e_speed = 0;
- target_celsius = 0;
- max_celsius = 0;
- heater_low = 64;
- heater_high = 255;
+ byte heater_low = 64;
+ byte heater_high = 255;
heater_current = 0;
valve_open = false;
@@ -69,7 +83,7 @@
e_direction = EXTRUDER_FORWARD;
//default to cool
- set_temperature(target_celsius);
+ set_temperature(target_temperature);
}
@@ -77,7 +91,7 @@
{
count = 0;
oldT = get_temperature();
- while (get_temperature() < target_celsius - HALF_DEAD_ZONE)
+ while (get_temperature() < target_temperature - HALF_DEAD_ZONE)
{
manage_all_extruders();
count++;
@@ -95,32 +109,8 @@
return 0;
}
-/*
-byte extruder::wait_till_cool()
-{
- count = 0;
- oldT = get_temperature();
- while (get_temperature() > target_celsius + HALF_DEAD_ZONE)
- {
- manage_all_extruders();
- count++;
- if(count > 20)
- {
- newT = get_temperature();
- if(newT < oldT)
- oldT = newT;
- else
- return 1;
- count = 0;
- }
- delay(1000);
- }
- return 0;
-}
-*/
-
void extruder::valve_set(bool open, int millis)
{
wait_for_temperature();
@@ -134,11 +124,11 @@
void extruder::set_temperature(int temp)
{
- target_celsius = temp;
- max_celsius = (temp*11)/10;
+ target_temperature = temp;
+ max_temperature = (temp*11)/10;
// If we've turned the heat off, we might as well disable the extrude stepper
- if(target_celsius < 1)
+ if(target_temperature < 0)
ex[extruder_in_use]->disableStep();
}
@@ -199,82 +189,140 @@
return raw;
}
+
+#if TEMP_PID
+int extruder::temp_update(int dt)
+{
+ int output;
+ int error;
+ float pTerm, iTerm, dTerm;
+
+ if (temp_control_enabled) {
+ error = target_temperature - current_temperature;
+
+ pTerm = temp_pGain * error;
+
+ temp_iState += error;
+ temp_iState = constrain(temp_iState, temp_iState_min, temp_iState_max);
+ iTerm = temp_iGain * temp_iState;
+
+ dTerm = temp_dGain * (current_temperature - temp_dState);
+ temp_dState = current_temperature;
+
+ output = pTerm + iTerm - dTerm;
+ output = constrain(output, 0, 255);
+ } else {
+ output = 0;
+ }
+ return output;
+}
+
+void extruder::temp_pid_update_windup()
+{
+ temp_iState_min = -TEMP_PID_INTEGRAL_DRIVE_MAX/temp_iGain;
+ temp_iState_max = TEMP_PID_INTEGRAL_DRIVE_MAX/temp_iGain;
+}
+
+#else
+
+int extruder::temp_update(int dt)
+{
+ int output;
+
+ if (temp_control_enabled) {
+ //put the heater into high mode if we're not at our target.
+ if (current_temperature < target_temperature)
+ output = heater_high;
+ //put the heater on low if we're at our target.
+ else if (current_temperature < max_temperature)
+ output = heater_low;
+ //turn the heater off if we're above our max.
+ else
+ output = 0;
+ } else {
+ output = 0;
+ }
+ return output;
+}
+#endif /* TEMP_PID */
+
+
+/*void extruder::manage()
+{
+ //int output = random(255);
+// analogWrite(12,128);
+ //
+ //digitalWrite(12,(output > 64)?HIGH:LOW);
+ //Serial.print("!");
+ //delay(200);
+}
+*/
/*!
+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
+*/
+// NEW
+void extruder::manage()
+{
+ int output, dt;
+ unsigned long time;
+
+ //make sure we know what our temp is.
+ current_temperature = get_temperature();
+
+ // ignoring millis rollover for now
+ time = millis();
+ dt = time - temp_prev_time;
+
+ if (dt > TEMP_UPDATE_INTERVAL)
+ {
+ temp_prev_time = time;
+ output = temp_update(dt);
+ //digitalWrite(DEBUG_PIN, (output > 0)?HIGH:LOW);
+// analogWrite(12, output);
+// delay(200);
+ digitalWrite(heater_pin, (output > 128)?HIGH:LOW);
+ softPWMduty = output;
+// softPWM(); // deze moet gewoon aan of uit...
+ }
+}
+
+
+/*!
Manages extruder functions to keep temps, speeds etc
at the set levels. Should be called only by manage_all_extruders(),
which should be called in all non-trivial loops.
o If temp is too low, don't start the motor
o Adjust the heater power to keep the temperature at the target
*/
+// OLD
+/*
void extruder::manage()
{
//make sure we know what our temp is.
int current_celsius = get_temperature();
- byte newheat = 0;
+ int newheat = 0;
//put the heater into high mode if we're not at our target.
if (current_celsius < target_celsius)
- newheat = heater_high;
+ newheat = 255;
//put the heater on low if we're at our target.
else if (current_celsius < max_celsius)
- newheat = heater_low;
+ newheat = 64;
// Only update heat if it changed
if (heater_current != newheat) {
heater_current = newheat;
- analogWrite(heater_pin, heater_current);
+// analogWrite(heater_pin, newheat); // STandard
+ analogWrite(12, newheat); // STandard
+// digitalWrite(heater_pin, heater_current);//ERIK
}
}
+*/
-#if 0
-void extruder::set_speed(float sp)
-{
- // DC motor?
- if(step_en_pin < 0)
- {
- e_speed = (byte)sp;
- if(e_speed > 0)
- wait_for_temperature();
- analogWrite(motor_speed_pin, e_speed);
- return;
- }
-
- // No - stepper
- disableTimerInterrupt();
-
- if(sp <= 1.0e-4)
- {
- disableStep();
- e_speed = 0; // Just use this as a flag
- return;
- } else
- {
- wait_for_temperature();
- enableStep();
- e_speed = 1;
- }
-
- extrude_step_count = 0;
-
- float milliseconds_per_step = 60000.0/(E_STEPS_PER_MM*sp);
- long thousand_ticks_per_step = 4*(long)(milliseconds_per_step);
- setupTimerInterrupt();
- setTimer(thousand_ticks_per_step);
- enableTimerInterrupt();
-}
-void extruder::interrupt()
-{
- if(!e_speed)
- return;
- extrude_step_count++;
- if(extrude_step_count > 1000)
- {
- step();
- extrude_step_count = 0;
- }
-}
+// NOT USED
-#endif
Index: ThermistorTable.h
===================================================================
--- ThermistorTable.h (revision 3145)
+++ ThermistorTable.h (working copy)
@@ -4,8 +4,6 @@
// Uncomment the next line if you are using a thermistor; leave it if you have a thermocouple
//#define USE_THERMISTOR
-// How many temperature samples to take for an average. each sample takes about 100 usecs.
-#define TEMPERATURE_SAMPLES 3
// How accurately do we maintain the temperature?
#define HALF_DEAD_ZONE 5
|