Browse Source

Rework change to incorporate CONTROLLERFAN

Also refactor extruder auto fan logic to simplify further and now only
check every 2.5 seconds
Robert F-C 11 years ago
parent
commit
d5ad7a0814
3 changed files with 98 additions and 86 deletions
  1. 5
    2
      Marlin/Configuration_adv.h
  2. 16
    33
      Marlin/Marlin_main.cpp
  3. 77
    51
      Marlin/temperature.cpp

+ 5
- 2
Marlin/Configuration_adv.h View File

@@ -63,14 +63,16 @@
63 63
 //This is for controlling a fan to cool down the stepper drivers
64 64
 //it will turn on when any driver is enabled
65 65
 //and turn off after the set amount of seconds from last driver being disabled again
66
-//#define CONTROLLERFAN_PIN 23 //Pin used for the fan to cool controller, comment out to disable this function
67
-#define CONTROLLERFAN_SEC 60 //How many seconds, after all motors were disabled, the fan should run
66
+#define CONTROLLERFAN_PIN -1 //Pin used for the fan to cool controller (-1 to disable)
67
+#define CONTROLLERFAN_SECS 60 //How many seconds, after all motors were disabled, the fan should run
68
+#define CONTROLLERFAN_SPEED 255  // == full speed
68 69
 
69 70
 // When first starting the main fan, run it at full speed for the
70 71
 // given number of milliseconds.  This gets the fan spinning reliably
71 72
 // before setting a PWM value. (Does not work with software PWM for fan on Sanguinololu)
72 73
 //#define FAN_KICKSTART_TIME 100
73 74
 
75
+// Extruder cooling fans
74 76
 // Configure fan pin outputs to automatically turn on/off when the associated
75 77
 // extruder temperature is above/below EXTRUDER_AUTO_FAN_TEMPERATURE.
76 78
 // Multiple extruders can be assigned to the same pin in which case 
@@ -81,6 +83,7 @@
81 83
 #define EXTRUDER_AUTO_FAN_TEMPERATURE 50
82 84
 #define EXTRUDER_AUTO_FAN_SPEED   255  // == full speed
83 85
 
86
+
84 87
 //===========================================================================
85 88
 //=============================Mechanical Settings===========================
86 89
 //===========================================================================

+ 16
- 33
Marlin/Marlin_main.cpp View File

@@ -374,13 +374,9 @@ void setup()
374 374
   
375 375
   lcd_init();
376 376
   
377
-  #ifdef CONTROLLERFAN_PIN
377
+  #if CONTROLLERFAN_PIN > 0
378 378
     SET_OUTPUT(CONTROLLERFAN_PIN); //Set pin used for driver cooling fan
379
-  #endif
380
-  
381
-  #ifdef EXTRUDERFAN_PIN
382
-    SET_OUTPUT(EXTRUDERFAN_PIN); //Set pin used for extruder cooling fan
383
-  #endif
379
+  #endif 
384 380
 }
385 381
 
386 382
 
@@ -1963,7 +1959,12 @@ void prepare_arc_move(char isclockwise) {
1963 1959
   previous_millis_cmd = millis();
1964 1960
 }
1965 1961
 
1966
-#ifdef CONTROLLERFAN_PIN
1962
+#if CONTROLLERFAN_PIN > 0
1963
+
1964
+#if CONTROLLERFAN_PIN == FAN_PIN 
1965
+   #error "You cannot set CONTROLLERFAN_PIN equal to FAN_PIN"
1966
+#endif
1967
+
1967 1968
 unsigned long lastMotor = 0; //Save the time for when a motor was turned on last
1968 1969
 unsigned long lastMotorCheck = 0;
1969 1970
 
@@ -1985,34 +1986,16 @@ void controllerFan()
1985 1986
       lastMotor = millis(); //... set time to NOW so the fan will turn on
1986 1987
     }
1987 1988
     
1988
-    if ((millis() - lastMotor) >= (CONTROLLERFAN_SEC*1000UL) || lastMotor == 0) //If the last time any driver was enabled, is longer since than CONTROLLERSEC...   
1989
-    {
1990
-      WRITE(CONTROLLERFAN_PIN, LOW); //... turn the fan off
1991
-    }
1992
-    else
1989
+    if ((millis() - lastMotor) >= (CONTROLLERFAN_SECS*1000UL) || lastMotor == 0) //If the last time any driver was enabled, is longer since than CONTROLLERSEC...   
1993 1990
     {
1994
-      WRITE(CONTROLLERFAN_PIN, HIGH); //... turn the fan on
1995
-    }
1996
-  }
1997
-}
1998
-#endif
1999
-
2000
-#ifdef EXTRUDERFAN_PIN
2001
-unsigned long lastExtruderCheck = 0;
2002
-
2003
-void extruderFan()
2004
-{
2005
-  if ((millis() - lastExtruderCheck) >= 2500) //Not a time critical function, so we only check every 2500ms
2006
-  {
2007
-    lastExtruderCheck = millis();
2008
-           
2009
-    if (degHotend(active_extruder) < EXTRUDERFAN_DEC)
2010
-    {
2011
-      WRITE(EXTRUDERFAN_PIN, LOW); //... turn the fan off
1991
+        digitalWrite(CONTROLLERFAN_PIN, 0); 
1992
+        analogWrite(CONTROLLERFAN_PIN, 0); 
2012 1993
     }
2013 1994
     else
2014 1995
     {
2015
-      WRITE(EXTRUDERFAN_PIN, HIGH); //... turn the fan on
1996
+        // allows digital or PWM fan output to be used (see M42 handling)
1997
+        digitalWrite(CONTROLLERFAN_PIN, CONTROLLERFAN_SPEED);
1998
+        analogWrite(CONTROLLERFAN_PIN, CONTROLLERFAN_SPEED); 
2016 1999
     }
2017 2000
   }
2018 2001
 }
@@ -2036,11 +2019,11 @@ void manage_inactivity()
2036 2019
       }
2037 2020
     }
2038 2021
   }
2039
-  #if( KILL_PIN>-1 )
2022
+  #if KILL_PIN > 0
2040 2023
     if( 0 == READ(KILL_PIN) )
2041 2024
       kill();
2042 2025
   #endif
2043
-  #ifdef CONTROLLERFAN_PIN
2026
+  #if CONTROLLERFAN_PIN > 0
2044 2027
     controllerFan(); //Check if fan should be turned on to cool stepper drivers down
2045 2028
   #endif
2046 2029
   #ifdef EXTRUDER_RUNOUT_PREVENT

+ 77
- 51
Marlin/temperature.cpp View File

@@ -99,8 +99,8 @@ static volatile bool temp_meas_ready = false;
99 99
 #ifdef FAN_SOFT_PWM
100 100
   static unsigned char soft_pwm_fan;
101 101
 #endif
102
-#if EXTRUDER_0_AUTO_FAN_PIN > -1 || EXTRUDER_1_AUTO_FAN_PIN > -1 || EXTRUDER_2_AUTO_FAN_PIN > -1
103
-  static uint8_t extruderAutoFanState = 0; // extruder auto fan state stored as bitmap
102
+#if EXTRUDER_0_AUTO_FAN_PIN > 0 || EXTRUDER_1_AUTO_FAN_PIN > 0 || EXTRUDER_2_AUTO_FAN_PIN > 0
103
+  static unsigned long extruder_autofan_last_check;
104 104
 #endif  
105 105
   
106 106
 #if EXTRUDERS > 3
@@ -307,6 +307,73 @@ int getHeaterPower(int heater) {
307 307
   return soft_pwm[heater];
308 308
 }
309 309
 
310
+#if EXTRUDER_0_AUTO_FAN_PIN > 0 || EXTRUDER_1_AUTO_FAN_PIN > 0 || EXTRUDER_2_AUTO_FAN_PIN > 0
311
+
312
+void setExtruderAutoFanState(int pin, bool state)
313
+{
314
+  unsigned char newFanSpeed = (state != 0) ? EXTRUDER_AUTO_FAN_SPEED : 0;
315
+  // this idiom allows both digital and PWM fan outputs (see M42 handling).
316
+  pinMode(pin, OUTPUT);
317
+  digitalWrite(pin, newFanSpeed);
318
+  analogWrite(pin, newFanSpeed);
319
+}
320
+
321
+void checkExtruderAutoFans()
322
+{
323
+  uint8_t fanState = 0;
324
+
325
+  // which fan pins need to be turned on?      
326
+  #if EXTRUDER_0_AUTO_FAN_PIN > 0
327
+    #if EXTRUDER_0_AUTO_FAN_PIN == FAN_PIN 
328
+       #error "You cannot set EXTRUDER_0_AUTO_FAN_PIN equal to FAN_PIN"
329
+    #endif
330
+    if (current_temperature[0] > EXTRUDER_AUTO_FAN_TEMPERATURE) 
331
+      fanState |= 1;
332
+  #endif
333
+  #if EXTRUDER_1_AUTO_FAN_PIN > 0
334
+    #if EXTRUDER_1_AUTO_FAN_PIN == FAN_PIN 
335
+       #error "You cannot set EXTRUDER_1_AUTO_FAN_PIN equal to FAN_PIN"
336
+    #endif
337
+    if (current_temperature[1] > EXTRUDER_AUTO_FAN_TEMPERATURE) 
338
+    {
339
+      if (EXTRUDER_1_AUTO_FAN_PIN == EXTRUDER_0_AUTO_FAN_PIN) 
340
+        fanState |= 1;
341
+      else
342
+        fanState |= 2;
343
+    }
344
+  #endif
345
+  #if EXTRUDER_2_AUTO_FAN_PIN > 0
346
+    #if EXTRUDER_2_AUTO_FAN_PIN == FAN_PIN 
347
+       #error "You cannot set EXTRUDER_2_AUTO_FAN_PIN equal to FAN_PIN"
348
+    #endif
349
+    if (current_temperature[2] > EXTRUDER_AUTO_FAN_TEMPERATURE) 
350
+    {
351
+      if (EXTRUDER_2_AUTO_FAN_PIN == EXTRUDER_0_AUTO_FAN_PIN) 
352
+        fanState |= 1;
353
+      else if (EXTRUDER_2_AUTO_FAN_PIN == EXTRUDER_1_AUTO_FAN_PIN) 
354
+        fanState |= 2;
355
+      else
356
+        fanState |= 4;
357
+    }
358
+  #endif
359
+  
360
+  // update extruder auto fan states
361
+  #if EXTRUDER_0_AUTO_FAN_PIN > 0
362
+    setExtruderAutoFanState(EXTRUDER_0_AUTO_FAN_PIN, (fanState & 1) != 0);
363
+  #endif 
364
+  #if EXTRUDER_1_AUTO_FAN_PIN > 0
365
+    if (EXTRUDER_1_AUTO_FAN_PIN != EXTRUDER_0_AUTO_FAN_PIN) 
366
+      setExtruderAutoFanState(EXTRUDER_1_AUTO_FAN_PIN, (fanState & 2) != 0);
367
+  #endif 
368
+  #if EXTRUDER_2_AUTO_FAN_PIN > 0
369
+    if (EXTRUDER_2_AUTO_FAN_PIN != EXTRUDER_0_AUTO_FAN_PIN 
370
+        && EXTRUDER_2_AUTO_FAN_PIN != EXTRUDER_1_AUTO_FAN_PIN)
371
+      setExtruderAutoFanState(EXTRUDER_2_AUTO_FAN_PIN, (fanState & 4) != 0);
372
+  #endif 
373
+}
374
+
375
+#endif // any extruder auto fan pins set
376
+
310 377
 void manage_heater()
311 378
 {
312 379
   float pid_input;
@@ -399,56 +466,15 @@ void manage_heater()
399 466
     #endif
400 467
 
401 468
   } // End extruder for loop
402
-  
403
-  #if EXTRUDER_0_AUTO_FAN_PIN > -1 || EXTRUDER_1_AUTO_FAN_PIN > -1 || EXTRUDER_2_AUTO_FAN_PIN > -1
404
-    bool newFanState;
405
-    #if EXTRUDER_0_AUTO_FAN_PIN > -1
406
-    // check the extruder 0 setting (and any ganged auto fan outputs)
407
-    newFanState = (current_temperature[0] > EXTRUDER_AUTO_FAN_TEMPERATURE || 
408
-            (EXTRUDER_0_AUTO_FAN_PIN == EXTRUDER_1_AUTO_FAN_PIN && current_temperature[1] > EXTRUDER_AUTO_FAN_TEMPERATURE) || 
409
-            (EXTRUDER_0_AUTO_FAN_PIN == EXTRUDER_2_AUTO_FAN_PIN && current_temperature[2] > EXTRUDER_AUTO_FAN_TEMPERATURE));
410
-    if ((extruderAutoFanState & 1) != newFanState) // store state in first bit
411
-    {
412
-        int newFanSpeed = (newFanState ? EXTRUDER_AUTO_FAN_SPEED : 0);
413
-        if (EXTRUDER_0_AUTO_FAN_PIN == FAN_PIN) 
414
-            fanSpeed = newFanSpeed;
415
-        pinMode(EXTRUDER_0_AUTO_FAN_PIN, OUTPUT);
416
-        digitalWrite(EXTRUDER_0_AUTO_FAN_PIN, newFanSpeed);
417
-        analogWrite(EXTRUDER_0_AUTO_FAN_PIN, newFanSpeed);
418
-        extruderAutoFanState = newFanState | (extruderAutoFanState & ~1);
419
-    }
420
-    #endif //EXTRUDER_0_AUTO_FAN_PIN > -1
421
-    #if EXTRUDER_1_AUTO_FAN_PIN > -1 && EXTRUDER_1_AUTO_FAN_PIN != EXTRUDER_0_AUTO_FAN_PIN
422
-    // check the extruder 1 setting (except when extruder 1 is the same as 0)
423
-    newFanState = (current_temperature[1] > EXTRUDER_AUTO_FAN_TEMPERATURE ||
424
-            (EXTRUDER_1_AUTO_FAN_PIN == EXTRUDER_2_AUTO_FAN_PIN && current_temperature[2] > EXTRUDER_AUTO_FAN_TEMPERATURE));
425
-    if ((extruderAutoFanState & 2) != (newFanState<<1)) // use second bit
426
-    {
427
-        int newFanSpeed = (newFanState ? EXTRUDER_AUTO_FAN_SPEED : 0);
428
-        if (EXTRUDER_1_AUTO_FAN_PIN == FAN_PIN) 
429
-            fanSpeed = newFanSpeed;
430
-        pinMode(EXTRUDER_1_AUTO_FAN_PIN, OUTPUT);
431
-        digitalWrite(EXTRUDER_1_AUTO_FAN_PIN, newFanSpeed);
432
-        analogWrite(EXTRUDER_1_AUTO_FAN_PIN, newFanSpeed);
433
-        extruderAutoFanState = (newFanState<<1) | (extruderAutoFanState & ~2);
434
-    }
435
-    #endif //EXTRUDER_1_AUTO_FAN_PIN > -1
436
-    #if EXTRUDER_2_AUTO_FAN_PIN > -1 && EXTRUDER_2_AUTO_FAN_PIN != EXTRUDER_0_AUTO_FAN_PIN && EXTRUDER_2_AUTO_FAN_PIN != EXTRUDER_1_AUTO_FAN_PIN
437
-    // check the extruder 2 setting (except when extruder 2 is the same as 1 or 0)
438
-    newFanState = (current_temperature[2] > EXTRUDER_AUTO_FAN_TEMPERATURE);
439
-    if ((extruderAutoFanState & 4) != (newFanState<<2)) // use third bit
440
-    {
441
-        int newFanSpeed = (newFanState ? EXTRUDER_AUTO_FAN_SPEED : 0);
442
-        if (EXTRUDER_2_AUTO_FAN_PIN == FAN_PIN) 
443
-            fanSpeed = newFanSpeed;
444
-        pinMode(EXTRUDER_2_AUTO_FAN_PIN, OUTPUT);
445
-        digitalWrite(EXTRUDER_2_AUTO_FAN_PIN, newFanSpeed);
446
-        analogWrite(EXTRUDER_2_AUTO_FAN_PIN, newFanSpeed);
447
-        extruderAutoFanState = (newFanState<<2) | (extruderAutoFanState & ~4);
448
-    }
449
-    #endif //EXTRUDER_2_AUTO_FAN_PIN > -1
450
-  #endif // any AUTO_FAN_PIN enabled  
451 469
 
470
+  #if EXTRUDER_0_AUTO_FAN_PIN > 0 || EXTRUDER_1_AUTO_FAN_PIN > 0 || EXTRUDER_2_AUTO_FAN_PIN > 0
471
+  if(millis() - extruder_autofan_last_check > 2500)  // only need to check fan state very infrequently
472
+  {
473
+    checkExtruderAutoFans();
474
+    extruder_autofan_last_check = millis();
475
+  }  
476
+  #endif       
477
+  
452 478
   #ifndef PIDTEMPBED
453 479
   if(millis() - previous_millis_bed_heater < BED_CHECK_INTERVAL)
454 480
     return;

Loading…
Cancel
Save