Browse Source

Support for multiple PWM fans

Scott Lahteine 8 years ago
parent
commit
4bbea5124d

+ 26
- 2
Marlin/Conditionals.h View File

@@ -465,7 +465,9 @@
465 465
   #define HAS_AUTO_FAN_2 (PIN_EXISTS(EXTRUDER_2_AUTO_FAN))
466 466
   #define HAS_AUTO_FAN_3 (PIN_EXISTS(EXTRUDER_3_AUTO_FAN))
467 467
   #define HAS_AUTO_FAN (HAS_AUTO_FAN_0 || HAS_AUTO_FAN_1 || HAS_AUTO_FAN_2 || HAS_AUTO_FAN_3)
468
-  #define HAS_FAN (PIN_EXISTS(FAN))
468
+  #define HAS_FAN0 (PIN_EXISTS(FAN))
469
+  #define HAS_FAN1 (PIN_EXISTS(FAN1) && CONTROLLERFAN_PIN != FAN1_PIN && EXTRUDER_0_AUTO_FAN_PIN != FAN1_PIN && EXTRUDER_1_AUTO_FAN_PIN != FAN1_PIN && EXTRUDER_2_AUTO_FAN_PIN != FAN1_PIN)
470
+  #define HAS_FAN2 (PIN_EXISTS(FAN2) && CONTROLLERFAN_PIN != FAN2_PIN && EXTRUDER_0_AUTO_FAN_PIN != FAN2_PIN && EXTRUDER_1_AUTO_FAN_PIN != FAN2_PIN && EXTRUDER_2_AUTO_FAN_PIN != FAN2_PIN)
469 471
   #define HAS_CONTROLLERFAN (PIN_EXISTS(CONTROLLERFAN))
470 472
   #define HAS_SERVOS (defined(NUM_SERVOS) && NUM_SERVOS > 0)
471 473
   #define HAS_SERVO_0 (PIN_EXISTS(SERVO0))
@@ -550,9 +552,31 @@
550 552
   #if HAS_HEATER_BED
551 553
     #define WRITE_HEATER_BED(v) WRITE(HEATER_BED_PIN, v)
552 554
   #endif
553
-  #if HAS_FAN
555
+
556
+  /**
557
+   * Up to 3 PWM fans
558
+   */
559
+  #if HAS_FAN2
560
+    #define FAN_COUNT 3
561
+  #elif HAS_FAN1
562
+    #define FAN_COUNT 2
563
+  #elif HAS_FAN0
564
+    #define FAN_COUNT 1
565
+  #else
566
+    #define FAN_COUNT 0
567
+  #endif
568
+
569
+  #if HAS_FAN0
554 570
     #define WRITE_FAN(v) WRITE(FAN_PIN, v)
571
+    #define WRITE_FAN0(v) WRITE_FAN(v)
572
+  #endif
573
+  #if HAS_FAN1
574
+    #define WRITE_FAN1(v) WRITE(FAN1_PIN, v)
575
+  #endif
576
+  #if HAS_FAN2
577
+    #define WRITE_FAN2(v) WRITE(FAN2_PIN, v)
555 578
   #endif
579
+  #define WRITE_FAN_N(n, v) WRITE_FAN##n(v)
556 580
 
557 581
   #define HAS_BUZZER (PIN_EXISTS(BEEPER) || defined(LCD_USE_I2C_BUZZER))
558 582
 

+ 3
- 5
Marlin/Marlin.h View File

@@ -306,17 +306,15 @@ extern bool axis_homed[3]; // axis[n].is_homed
306 306
   extern float extrude_min_temp;
307 307
 #endif
308 308
 
309
-extern int fanSpeed;
309
+#if FAN_COUNT > 0
310
+  extern int fanSpeeds[FAN_COUNT];
311
+#endif
310 312
 
311 313
 #if ENABLED(BARICUDA)
312 314
   extern int ValvePressure;
313 315
   extern int EtoPPressure;
314 316
 #endif
315 317
 
316
-#if ENABLED(FAN_SOFT_PWM)
317
-  extern unsigned char fanSpeedSoftPwm;
318
-#endif
319
-
320 318
 #if ENABLED(FILAMENT_SENSOR)
321 319
   extern float filament_width_nominal;  //holds the theoretical filament diameter i.e., 3.00 or 1.75
322 320
   extern bool filament_sensor;  //indicates that filament sensor readings should control extrusion

+ 38
- 10
Marlin/Marlin_main.cpp View File

@@ -267,8 +267,11 @@ float home_offset[3] = { 0 };
267 267
 float min_pos[3] = { X_MIN_POS, Y_MIN_POS, Z_MIN_POS };
268 268
 float max_pos[3] = { X_MAX_POS, Y_MAX_POS, Z_MAX_POS };
269 269
 
270
+#if FAN_COUNT > 0
271
+  int fanSpeeds[FAN_COUNT] = { 0 };
272
+#endif
273
+
270 274
 uint8_t active_extruder = 0;
271
-int fanSpeed = 0;
272 275
 bool cancel_heatup = false;
273 276
 
274 277
 const char errormagic[] PROGMEM = "Error:";
@@ -3597,8 +3600,16 @@ inline void gcode_M42() {
3597 3600
       }
3598 3601
     }
3599 3602
 
3600
-    #if HAS_FAN
3601
-      if (pin_number == FAN_PIN) fanSpeed = pin_status;
3603
+    #if HAS_FAN0
3604
+      if (pin_number == FAN_PIN)  fanSpeeds[0] = pin_status;
3605
+    #endif
3606
+
3607
+    #if HAS_FAN1
3608
+      if (pin_number == FAN1_PIN) fanSpeeds[1] = pin_status;
3609
+    #endif
3610
+
3611
+    #if HAS_FAN2
3612
+      if (pin_number == FAN2_PIN) fanSpeeds[2] = pin_status;
3602 3613
     #endif
3603 3614
 
3604 3615
     if (pin_number > -1) {
@@ -3968,19 +3979,30 @@ inline void gcode_M105() {
3968 3979
   SERIAL_EOL;
3969 3980
 }
3970 3981
 
3971
-#if HAS_FAN
3982
+#if FAN_COUNT > 0
3972 3983
 
3973 3984
   /**
3974 3985
    * M106: Set Fan Speed
3986
+   *
3987
+   *  S<int>   Speed between 0-255
3988
+   *  P<index> Fan index, if more than one fan
3975 3989
    */
3976
-  inline void gcode_M106() { fanSpeed = code_seen('S') ? constrain(code_value_short(), 0, 255) : 255; }
3990
+  inline void gcode_M106() {
3991
+    uint16_t s = code_seen('S') ? code_value_short() : 255,
3992
+             p = code_seen('P') ? code_value_short() : 0;
3993
+    NOMORE(s, 255);
3994
+    if (p < FAN_COUNT) fanSpeeds[p] = s;
3995
+  }
3977 3996
 
3978 3997
   /**
3979 3998
    * M107: Fan Off
3980 3999
    */
3981
-  inline void gcode_M107() { fanSpeed = 0; }
4000
+  inline void gcode_M107() {
4001
+    uint16_t p = code_seen('P') ? code_value_short() : 0;
4002
+    if (p < FAN_COUNT) fanSpeeds[p] = 0;
4003
+  }
3982 4004
 
3983
-#endif // HAS_FAN
4005
+#endif // FAN_COUNT > 0
3984 4006
 
3985 4007
 /**
3986 4008
  * M109: Sxxx Wait for extruder(s) to reach temperature. Waits only when heating.
@@ -4261,7 +4283,13 @@ inline void gcode_M140() {
4261 4283
 inline void gcode_M81() {
4262 4284
   disable_all_heaters();
4263 4285
   finishAndDisableSteppers();
4264
-  fanSpeed = 0;
4286
+  #if FAN_COUNT > 0
4287
+    #if FAN_COUNT > 1
4288
+      for (uint8_t i = 0; i < FAN_COUNT; i++) fanSpeeds[i] = 0;
4289
+    #else
4290
+      fanSpeeds[0] = 0;
4291
+    #endif
4292
+  #endif
4265 4293
   delay(1000); // Wait 1 second before switching off
4266 4294
   #if HAS_SUICIDE
4267 4295
     st_synchronize();
@@ -6015,14 +6043,14 @@ void process_next_command() {
6015 6043
           break;
6016 6044
       #endif // HAS_TEMP_BED
6017 6045
 
6018
-      #if HAS_FAN
6046
+      #if FAN_COUNT > 0
6019 6047
         case 106: // M106: Fan On
6020 6048
           gcode_M106();
6021 6049
           break;
6022 6050
         case 107: // M107: Fan Off
6023 6051
           gcode_M107();
6024 6052
           break;
6025
-      #endif // HAS_FAN
6053
+      #endif // FAN_COUNT > 0
6026 6054
 
6027 6055
       #if ENABLED(BARICUDA)
6028 6056
         // PWM for HEATER_1_PIN

+ 24
- 10
Marlin/SanityCheck.h View File

@@ -264,22 +264,36 @@
264 264
 /**
265 265
  * Make sure auto fan pins don't conflict with the fan pin
266 266
  */
267
-#if HAS_AUTO_FAN && HAS_FAN
268
-  #if EXTRUDER_0_AUTO_FAN_PIN == FAN_PIN
269
-    #error You cannot set EXTRUDER_0_AUTO_FAN_PIN equal to FAN_PIN.
270
-  #elif EXTRUDER_1_AUTO_FAN_PIN == FAN_PIN
271
-    #error You cannot set EXTRUDER_1_AUTO_FAN_PIN equal to FAN_PIN.
272
-  #elif EXTRUDER_2_AUTO_FAN_PIN == FAN_PIN
273
-    #error You cannot set EXTRUDER_2_AUTO_FAN_PIN equal to FAN_PIN.
274
-  #elif EXTRUDER_3_AUTO_FAN_PIN == FAN_PIN
275
-    #error You cannot set EXTRUDER_3_AUTO_FAN_PIN equal to FAN_PIN.
267
+#if HAS_AUTO_FAN
268
+  #if HAS_FAN0
269
+    #if EXTRUDER_0_AUTO_FAN_PIN == FAN_PIN
270
+      #error You cannot set EXTRUDER_0_AUTO_FAN_PIN equal to FAN_PIN.
271
+    #elif EXTRUDER_1_AUTO_FAN_PIN == FAN_PIN
272
+      #error You cannot set EXTRUDER_1_AUTO_FAN_PIN equal to FAN_PIN.
273
+    #elif EXTRUDER_2_AUTO_FAN_PIN == FAN_PIN
274
+      #error You cannot set EXTRUDER_2_AUTO_FAN_PIN equal to FAN_PIN.
275
+    #elif EXTRUDER_3_AUTO_FAN_PIN == FAN_PIN
276
+      #error You cannot set EXTRUDER_3_AUTO_FAN_PIN equal to FAN_PIN.
277
+    #endif
276 278
   #endif
277 279
 #endif
278 280
 
279
-#if HAS_FAN && CONTROLLERFAN_PIN == FAN_PIN
281
+#if HAS_FAN0 && CONTROLLERFAN_PIN == FAN_PIN
280 282
   #error You cannot set CONTROLLERFAN_PIN equal to FAN_PIN.
281 283
 #endif
282 284
 
285
+#if HAS_CONTROLLERFAN
286
+  #if EXTRUDER_0_AUTO_FAN_PIN == CONTROLLERFAN_PIN
287
+    #error You cannot set EXTRUDER_0_AUTO_FAN_PIN equal to CONTROLLERFAN_PIN.
288
+  #elif EXTRUDER_1_AUTO_FAN_PIN == CONTROLLERFAN_PIN
289
+    #error You cannot set EXTRUDER_1_AUTO_FAN_PIN equal to CONTROLLERFAN_PIN.
290
+  #elif EXTRUDER_2_AUTO_FAN_PIN == CONTROLLERFAN_PIN
291
+    #error You cannot set EXTRUDER_2_AUTO_FAN_PIN equal to CONTROLLERFAN_PIN.
292
+  #elif EXTRUDER_3_AUTO_FAN_PIN == CONTROLLERFAN_PIN
293
+    #error You cannot set EXTRUDER_3_AUTO_FAN_PIN equal to CONTROLLERFAN_PIN.
294
+  #endif
295
+#endif
296
+
283 297
 /**
284 298
  * Test Heater, Temp Sensor, and Extruder Pins; Sensor Type must also be set.
285 299
  */

+ 3
- 3
Marlin/dogm_lcd_implementation.h View File

@@ -283,7 +283,7 @@ static void lcd_implementation_status_screen() {
283 283
   u8g.setColorIndex(1); // black on white
284 284
 
285 285
   // Symbols menu graphics, animated fan
286
-  u8g.drawBitmapP(9,1,STATUS_SCREENBYTEWIDTH,STATUS_SCREENHEIGHT, (blink % 2) && fanSpeed ? status_screen0_bmp : status_screen1_bmp);
286
+  u8g.drawBitmapP(9,1,STATUS_SCREENBYTEWIDTH,STATUS_SCREENHEIGHT, (blink % 2) && fanSpeeds[0] ? status_screen0_bmp : status_screen1_bmp);
287 287
 
288 288
   #if ENABLED(SDSUPPORT)
289 289
     // SD Card Symbol
@@ -324,8 +324,8 @@ static void lcd_implementation_status_screen() {
324 324
   // Fan
325 325
   lcd_setFont(FONT_STATUSMENU);
326 326
   u8g.setPrintPos(104, 27);
327
-  #if HAS_FAN
328
-    int per = ((fanSpeed + 1) * 100) / 256;
327
+  #if HAS_FAN0
328
+    int per = ((fanSpeeds[0] + 1) * 100) / 256;
329 329
     if (per) {
330 330
       lcd_print(itostr3(per));
331 331
       lcd_print('%');

+ 1
- 1
Marlin/pins_MEGACONTROLLER.h View File

@@ -49,7 +49,7 @@
49 49
 #define FAN1_PIN 35
50 50
 #define FAN2_PIN 36
51 51
 #define FAN_SOFT_PWM
52
-#define CONTROLLERFAN_PIN 36
52
+#define CONTROLLERFAN_PIN FAN2_PIN
53 53
 #define PS_ON_PIN -1
54 54
 #define KILL_PIN -1
55 55
 

+ 75
- 24
Marlin/planner.cpp View File

@@ -93,6 +93,10 @@ unsigned long axis_steps_per_sqr_second[NUM_AXIS];
93 93
   bool autotemp_enabled = false;
94 94
 #endif
95 95
 
96
+#if ENABLED(FAN_SOFT_PWM)
97
+  extern unsigned char fanSpeedSoftPwm[FAN_COUNT];
98
+#endif
99
+
96 100
 //===========================================================================
97 101
 //============ semi-private variables, used in inline functions =============
98 102
 //===========================================================================
@@ -399,7 +403,12 @@ void plan_init() {
399 403
 
400 404
 void check_axes_activity() {
401 405
   unsigned char axis_active[NUM_AXIS] = { 0 },
402
-                tail_fan_speed = fanSpeed;
406
+                tail_fan_speed[FAN_COUNT];
407
+
408
+  #if FAN_COUNT > 0
409
+    for (uint8_t i = 0; i < FAN_COUNT; i++) tail_fan_speed[i] = fanSpeeds[i];
410
+  #endif
411
+
403 412
   #if ENABLED(BARICUDA)
404 413
     unsigned char tail_valve_pressure = ValvePressure,
405 414
                   tail_e_to_p_pressure = EtoPPressure;
@@ -408,13 +417,19 @@ void check_axes_activity() {
408 417
   block_t* block;
409 418
 
410 419
   if (blocks_queued()) {
420
+
411 421
     uint8_t block_index = block_buffer_tail;
412
-    tail_fan_speed = block_buffer[block_index].fan_speed;
422
+
423
+    #if FAN_COUNT > 0
424
+      for (uint8_t i = 0; i < FAN_COUNT; i++) tail_fan_speed[i] = block_buffer[block_index].fan_speed[i];
425
+    #endif
426
+
413 427
     #if ENABLED(BARICUDA)
414 428
       block = &block_buffer[block_index];
415 429
       tail_valve_pressure = block->valve_pressure;
416 430
       tail_e_to_p_pressure = block->e_to_p_pressure;
417 431
     #endif
432
+
418 433
     while (block_index != block_buffer_head) {
419 434
       block = &block_buffer[block_index];
420 435
       for (int i = 0; i < NUM_AXIS; i++) if (block->steps[i]) axis_active[i]++;
@@ -439,32 +454,65 @@ void check_axes_activity() {
439 454
     }
440 455
   #endif
441 456
 
442
-  #if HAS_FAN
457
+  #if FAN_COUNT > 0
458
+
459
+    #if defined(FAN_MIN_PWM)
460
+      #define CALC_FAN_SPEED(f) (tail_fan_speed[f] ? ( FAN_MIN_PWM + (tail_fan_speed[f] * (255 - FAN_MIN_PWM)) / 255 ) : 0)
461
+    #else
462
+      #define CALC_FAN_SPEED(f) tail_fan_speed[f]
463
+    #endif
464
+
443 465
     #ifdef FAN_KICKSTART_TIME
444
-      static millis_t fan_kick_end = 0;
445
-      if (tail_fan_speed) {
446
-        millis_t ms = millis();
447
-        if (fan_kick_end == 0) {
448
-          fan_kick_end = ms + FAN_KICKSTART_TIME;
449
-          tail_fan_speed = 255; // Starting up.
466
+
467
+      static millis_t fan_kick_end[FAN_COUNT] = { 0 }, ms = millis();
468
+
469
+      #define KICKSTART_FAN(f) \
470
+        if (tail_fan_speed[f]) { \
471
+          if (fan_kick_end[f] == 0) { \
472
+            fan_kick_end[f] = ms + FAN_KICKSTART_TIME; \
473
+            tail_fan_speed[f] = 255; \
474
+          } \
475
+          else if (fan_kick_end[f] > ms) \
476
+            tail_fan_speed[f] = 255; \
477
+          else \
478
+            fan_kick_end[f] = 0; \
450 479
         }
451
-        else if (ms < fan_kick_end)
452
-          tail_fan_speed = 255; // Still spinning up.
453
-        else
454
-          fan_kick_end = 0;
455
-      }
480
+
481
+      #if HAS_FAN0
482
+        KICKSTART_FAN(0);
483
+      #endif
484
+      #if HAS_FAN1
485
+        KICKSTART_FAN(1);
486
+      #endif
487
+      #if HAS_FAN2
488
+        KICKSTART_FAN(2);
489
+      #endif
490
+
456 491
     #endif //FAN_KICKSTART_TIME
457
-    #if defined(FAN_MIN_PWM)
458
-      #define CALC_FAN_SPEED (tail_fan_speed ? ( FAN_MIN_PWM + (tail_fan_speed * (255 - (FAN_MIN_PWM))) / 255 ) : 0)
459
-    #else
460
-      #define CALC_FAN_SPEED tail_fan_speed
461
-    #endif // FAN_MIN_PWM
492
+
462 493
     #if ENABLED(FAN_SOFT_PWM)
463
-      fanSpeedSoftPwm = CALC_FAN_SPEED;
494
+      #if HAS_FAN0
495
+        fanSpeedSoftPwm[0] = CALC_FAN_SPEED(0);
496
+      #endif
497
+      #if HAS_FAN1
498
+        fanSpeedSoftPwm[1] = CALC_FAN_SPEED(1);
499
+      #endif
500
+      #if HAS_FAN2
501
+        fanSpeedSoftPwm[2] = CALC_FAN_SPEED(2);
502
+      #endif
464 503
     #else
465
-      analogWrite(FAN_PIN, CALC_FAN_SPEED);
466
-    #endif // FAN_SOFT_PWM
467
-  #endif // HAS_FAN
504
+      #if HAS_FAN0
505
+        analogWrite(FAN_PIN, CALC_FAN_SPEED(0));
506
+      #endif
507
+      #if HAS_FAN1
508
+        analogWrite(FAN1_PIN, CALC_FAN_SPEED(1));
509
+      #endif
510
+      #if HAS_FAN2
511
+        analogWrite(FAN2_PIN, CALC_FAN_SPEED(2));
512
+      #endif
513
+    #endif
514
+
515
+  #endif // FAN_COUNT > 0
468 516
 
469 517
   #if ENABLED(AUTOTEMP)
470 518
     getHighESpeed();
@@ -576,7 +624,10 @@ float junction_deviation = 0.1;
576 624
   // Bail if this is a zero-length block
577 625
   if (block->step_event_count <= dropsegments) return;
578 626
 
579
-  block->fan_speed = fanSpeed;
627
+  #if FAN_COUNT > 0
628
+    for (uint8_t i = 0; i < FAN_COUNT; i++) block->fan_speed[i] = fanSpeeds[i];
629
+  #endif
630
+
580 631
   #if ENABLED(BARICUDA)
581 632
     block->valve_pressure = ValvePressure;
582 633
     block->e_to_p_pressure = EtoPPressure;

+ 7
- 1
Marlin/planner.h View File

@@ -59,12 +59,18 @@ typedef struct {
59 59
   unsigned long initial_rate;                        // The jerk-adjusted step rate at start of block
60 60
   unsigned long final_rate;                          // The minimal rate at exit
61 61
   unsigned long acceleration_st;                     // acceleration steps/sec^2
62
-  unsigned long fan_speed;
62
+
63
+  #if FAN_COUNT > 0
64
+    unsigned long fan_speed[FAN_COUNT];
65
+  #endif
66
+
63 67
   #if ENABLED(BARICUDA)
64 68
     unsigned long valve_pressure;
65 69
     unsigned long e_to_p_pressure;
66 70
   #endif
71
+
67 72
   volatile char busy;
73
+
68 74
 } block_t;
69 75
 
70 76
 #define BLOCK_MOD(n) ((n)&(BLOCK_BUFFER_SIZE-1))

+ 72
- 12
Marlin/temperature.cpp View File

@@ -62,7 +62,7 @@ float current_temperature_bed = 0.0;
62 62
 #endif //PIDTEMPBED
63 63
 
64 64
 #if ENABLED(FAN_SOFT_PWM)
65
-  unsigned char fanSpeedSoftPwm;
65
+  unsigned char fanSpeedSoftPwm[FAN_COUNT];
66 66
 #endif
67 67
 
68 68
 unsigned char soft_pwm_bed;
@@ -130,7 +130,7 @@ static volatile bool temp_meas_ready = false;
130 130
 static unsigned char soft_pwm[EXTRUDERS];
131 131
 
132 132
 #if ENABLED(FAN_SOFT_PWM)
133
-  static unsigned char soft_pwm_fan;
133
+  static unsigned char soft_pwm_fan[FAN_COUNT];
134 134
 #endif
135 135
 #if HAS_AUTO_FAN
136 136
   static millis_t next_auto_fan_check_ms;
@@ -886,17 +886,40 @@ void tp_init() {
886 886
   #if HAS_HEATER_BED
887 887
     SET_OUTPUT(HEATER_BED_PIN);
888 888
   #endif
889
-  #if HAS_FAN
890
-    #if ENABLED(FAST_PWM_FAN) || ENABLED(FAN_SOFT_PWM)
889
+
890
+  #if ENABLED(FAST_PWM_FAN) || ENABLED(FAN_SOFT_PWM)
891
+
892
+    #if HAS_FAN0
891 893
       SET_OUTPUT(FAN_PIN);
892 894
       #if ENABLED(FAST_PWM_FAN)
893 895
         setPwmFrequency(FAN_PIN, 1); // No prescaling. Pwm frequency = F_CPU/256/8
894 896
       #endif
895 897
       #if ENABLED(FAN_SOFT_PWM)
896
-        soft_pwm_fan = fanSpeedSoftPwm / 2;
898
+        soft_pwm_fan[0] = fanSpeedSoftPwm[0] / 2;
899
+      #endif
900
+    #endif
901
+
902
+    #if HAS_FAN1
903
+      SET_OUTPUT(FAN1_PIN);
904
+      #if ENABLED(FAST_PWM_FAN)
905
+        setPwmFrequency(FAN1_PIN, 1); // No prescaling. Pwm frequency = F_CPU/256/8
906
+      #endif
907
+      #if ENABLED(FAN_SOFT_PWM)
908
+        soft_pwm_fan[1] = fanSpeedSoftPwm[1] / 2;
909
+      #endif
910
+    #endif
911
+
912
+    #if HAS_FAN2
913
+      SET_OUTPUT(FAN2_PIN);
914
+      #if ENABLED(FAST_PWM_FAN)
915
+        setPwmFrequency(FAN2_PIN, 1); // No prescaling. Pwm frequency = F_CPU/256/8
916
+      #endif
917
+      #if ENABLED(FAN_SOFT_PWM)
918
+        soft_pwm_fan[2] = fanSpeedSoftPwm[2] / 2;
897 919
       #endif
898 920
     #endif
899
-  #endif
921
+
922
+  #endif // FAST_PWM_FAN || FAN_SOFT_PWM
900 923
 
901 924
   #if ENABLED(HEATER_0_USES_MAX6675)
902 925
 
@@ -1320,9 +1343,20 @@ ISR(TIMER0_COMPB_vect) {
1320 1343
         soft_pwm_BED = soft_pwm_bed;
1321 1344
         WRITE_HEATER_BED(soft_pwm_BED > 0 ? 1 : 0);
1322 1345
       #endif
1346
+
1323 1347
       #if ENABLED(FAN_SOFT_PWM)
1324
-        soft_pwm_fan = fanSpeedSoftPwm / 2;
1325
-        WRITE_FAN(soft_pwm_fan > 0 ? 1 : 0);
1348
+        #if HAS_FAN0
1349
+          soft_pwm_fan[0] = fanSpeedSoftPwm[0] / 2;
1350
+          WRITE_FAN(soft_pwm_fan[0] > 0 ? 1 : 0);
1351
+        #endif
1352
+        #if HAS_FAN1
1353
+          soft_pwm_fan[1] = fanSpeedSoftPwm[1] / 2;
1354
+          WRITE_FAN1(soft_pwm_fan[1] > 0 ? 1 : 0);
1355
+        #endif
1356
+        #if HAS_FAN2
1357
+          soft_pwm_fan[2] = fanSpeedSoftPwm[2] / 2;
1358
+          WRITE_FAN2(soft_pwm_fan[2] > 0 ? 1 : 0);
1359
+        #endif
1326 1360
       #endif
1327 1361
     }
1328 1362
 
@@ -1342,7 +1376,15 @@ ISR(TIMER0_COMPB_vect) {
1342 1376
     #endif
1343 1377
 
1344 1378
     #if ENABLED(FAN_SOFT_PWM)
1345
-      if (soft_pwm_fan < pwm_count) WRITE_FAN(0);
1379
+      #if HAS_FAN0
1380
+        if (soft_pwm_fan[0] < pwm_count) WRITE_FAN(0);
1381
+      #endif
1382
+      #if HAS_FAN1
1383
+        if (soft_pwm_fan[1] < pwm_count) WRITE_FAN1(0);
1384
+      #endif
1385
+      #if HAS_FAN2
1386
+        if (soft_pwm_fan[2] < pwm_count) WRITE_FAN2(0);
1387
+      #endif
1346 1388
     #endif
1347 1389
 
1348 1390
     pwm_count += _BV(SOFT_PWM_SCALE);
@@ -1421,10 +1463,28 @@ ISR(TIMER0_COMPB_vect) {
1421 1463
 
1422 1464
     #if ENABLED(FAN_SOFT_PWM)
1423 1465
       if (pwm_count == 0) {
1424
-        soft_pwm_fan = fanSpeedSoftPwm / 2;
1425
-        WRITE_FAN(soft_pwm_fan > 0 ? 1 : 0);
1466
+        #if HAS_FAN0
1467
+          soft_pwm_fan[0] = fanSpeedSoftPwm[0] / 2;
1468
+          WRITE_FAN(soft_pwm_fan[0] > 0 ? 1 : 0);
1469
+        #endif
1470
+        #if HAS_FAN1
1471
+          soft_pwm_fan[1] = fanSpeedSoftPwm[1] / 2;
1472
+          WRITE_FAN1(soft_pwm_fan[1] > 0 ? 1 : 0);
1473
+        #endif
1474
+        #if HAS_FAN2
1475
+          soft_pwm_fan[2] = fanSpeedSoftPwm[2] / 2;
1476
+          WRITE_FAN2(soft_pwm_fan[2] > 0 ? 1 : 0);
1477
+        #endif
1426 1478
       }
1427
-      if (soft_pwm_fan < pwm_count) WRITE_FAN(0);
1479
+      #if HAS_FAN0
1480
+        if (soft_pwm_fan[0] < pwm_count) WRITE_FAN(0);
1481
+      #endif
1482
+      #if HAS_FAN1
1483
+        if (soft_pwm_fan[1] < pwm_count) WRITE_FAN1(0);
1484
+      #endif
1485
+      #if HAS_FAN2
1486
+        if (soft_pwm_fan[2] < pwm_count) WRITE_FAN2(0);
1487
+      #endif
1428 1488
     #endif //FAN_SOFT_PWM
1429 1489
 
1430 1490
     pwm_count += _BV(SOFT_PWM_SCALE);

+ 42
- 4
Marlin/ultralcd.cpp View File

@@ -614,7 +614,22 @@ static void lcd_tune_menu() {
614 614
   //
615 615
   // Fan Speed:
616 616
   //
617
-  MENU_MULTIPLIER_ITEM_EDIT(int3, MSG_FAN_SPEED, &fanSpeed, 0, 255);
617
+  #if FAN_COUNT > 0
618
+    #if HAS_FAN0
619
+      #if FAN_COUNT > 1
620
+        #define MSG_1ST_FAN_SPEED MSG_FAN_SPEED " 1"
621
+      #else
622
+        #define MSG_1ST_FAN_SPEED MSG_FAN_SPEED
623
+      #endif
624
+      MENU_MULTIPLIER_ITEM_EDIT(int3, MSG_1ST_FAN_SPEED, &fanSpeeds[0], 0, 255);
625
+    #endif
626
+    #if HAS_FAN1
627
+      MENU_MULTIPLIER_ITEM_EDIT(int3, MSG_FAN_SPEED " 2", &fanSpeeds[1], 0, 255);
628
+    #endif
629
+    #if HAS_FAN2
630
+      MENU_MULTIPLIER_ITEM_EDIT(int3, MSG_FAN_SPEED " 3", &fanSpeeds[2], 0, 255);
631
+    #endif
632
+  #endif // FAN_COUNT > 0
618 633
 
619 634
   //
620 635
   // Flow:
@@ -665,7 +680,13 @@ void _lcd_preheat(int endnum, const float temph, const float tempb, const int fa
665 680
   #if TEMP_SENSOR_BED != 0
666 681
     setTargetBed(tempb);
667 682
   #endif
668
-  fanSpeed = fan;
683
+  #if FAN_COUNT > 0
684
+    #if FAN_COUNT > 1
685
+      fanSpeeds[active_extruder < FAN_COUNT ? active_extruder : 0] = fan;
686
+    #else
687
+      fanSpeeds[0] = fan;
688
+    #endif
689
+  #endif
669 690
   lcd_return_to_status();
670 691
 }
671 692
 
@@ -755,8 +776,10 @@ void _lcd_preheat(int endnum, const float temph, const float tempb, const int fa
755 776
 #endif // TEMP_SENSOR_0 && (TEMP_SENSOR_1 || TEMP_SENSOR_2 || TEMP_SENSOR_3 || TEMP_SENSOR_BED)
756 777
 
757 778
 void lcd_cooldown() {
779
+  #if FAN_COUNT > 0
780
+    for (uint8_t i = 0; i < FAN_COUNT; i++) fanSpeeds[i] = 0;
781
+  #endif
758 782
   disable_all_heaters();
759
-  fanSpeed = 0;
760 783
   lcd_return_to_status();
761 784
 }
762 785
 
@@ -1125,7 +1148,22 @@ static void lcd_control_temperature_menu() {
1125 1148
   //
1126 1149
   // Fan Speed:
1127 1150
   //
1128
-  MENU_MULTIPLIER_ITEM_EDIT(int3, MSG_FAN_SPEED, &fanSpeed, 0, 255);
1151
+  #if FAN_COUNT > 0
1152
+    #if HAS_FAN0
1153
+      #if FAN_COUNT > 1
1154
+        #define MSG_1ST_FAN_SPEED MSG_FAN_SPEED " 1"
1155
+      #else
1156
+        #define MSG_1ST_FAN_SPEED MSG_FAN_SPEED
1157
+      #endif
1158
+      MENU_MULTIPLIER_ITEM_EDIT(int3, MSG_1ST_FAN_SPEED, &fanSpeeds[0], 0, 255);
1159
+    #endif
1160
+    #if HAS_FAN1
1161
+      MENU_MULTIPLIER_ITEM_EDIT(int3, MSG_FAN_SPEED " 2", &fanSpeeds[1], 0, 255);
1162
+    #endif
1163
+    #if HAS_FAN2
1164
+      MENU_MULTIPLIER_ITEM_EDIT(int3, MSG_FAN_SPEED " 3", &fanSpeeds[2], 0, 255);
1165
+    #endif
1166
+  #endif // FAN_COUNT > 0
1129 1167
 
1130 1168
   //
1131 1169
   // Autotemp, Min, Max, Fact

+ 19
- 1
Marlin/ultralcd_implementation_hitachi_HD44780.h View File

@@ -873,16 +873,34 @@ void lcd_implementation_drawedit(const char* pstr, char* value) {
873 873
     // Set the LEDS - referred to as backlights by the LiquidTWI2 library
874 874
     static uint8_t ledsprev = 0;
875 875
     uint8_t leds = 0;
876
+
876 877
     if (target_temperature_bed > 0) leds |= LED_A;
878
+
877 879
     if (target_temperature[0] > 0) leds |= LED_B;
878
-    if (fanSpeed) leds |= LED_C;
880
+
881
+    #if FAN_COUNT > 0
882
+      if (0
883
+        #if HAS_FAN0
884
+          || fanSpeeds[0]
885
+        #endif
886
+        #if HAS_FAN1
887
+          || fanSpeeds[1]
888
+        #endif
889
+        #if HAS_FAN2
890
+          || fanSpeeds[2]
891
+        #endif
892
+      ) leds |= LED_C;
893
+    #endif // FAN_COUNT > 0
894
+
879 895
     #if EXTRUDERS > 1
880 896
       if (target_temperature[1] > 0) leds |= LED_C;
881 897
     #endif
898
+
882 899
     if (leds != ledsprev) {
883 900
       lcd.setBacklight(leds);
884 901
       ledsprev = leds;
885 902
     }
903
+
886 904
   }
887 905
 
888 906
 #endif // LCD_HAS_STATUS_INDICATORS

Loading…
Cancel
Save