浏览代码

Fixes and improvements for PWM pins (#13383)

Scott Lahteine 6 年前
父节点
当前提交
f89b375fb9
没有帐户链接到提交者的电子邮件

+ 29
- 25
Marlin/src/HAL/HAL_AVR/fastio_AVR.h 查看文件

@@ -94,6 +94,8 @@
94 94
   #define extDigitalRead(IO)    digitalRead(IO)
95 95
 #endif
96 96
 
97
+#define ANALOG_WRITE(IO,V)    analogWrite(IO,V)
98
+
97 99
 #define READ(IO)              _READ(IO)
98 100
 #define WRITE(IO,V)           _WRITE(IO,V)
99 101
 #define TOGGLE(IO)            _TOGGLE(IO)
@@ -102,6 +104,8 @@
102 104
 #define SET_INPUT_PULLUP(IO)  do{ _SET_INPUT(IO); _WRITE(IO, HIGH); }while(0)
103 105
 #define SET_OUTPUT(IO)        _SET_OUTPUT(IO)
104 106
 
107
+#define SET_PWM(IO)           SET_OUTPUT(IO)
108
+
105 109
 #define GET_INPUT(IO)         _GET_INPUT(IO)
106 110
 #define GET_OUTPUT(IO)        _GET_OUTPUT(IO)
107 111
 #define GET_TIMER(IO)         _GET_TIMER(IO)
@@ -279,75 +283,75 @@ enum ClockSource2 : char {
279 283
 
280 284
 // Determine which harware PWMs are already in use
281 285
 #if PIN_EXISTS(CONTROLLER_FAN)
282
-  #define PWM_CHK_FAN_B(p) (p == CONTROLLER_FAN_PIN || p == E0_AUTO_FAN_PIN || p == E1_AUTO_FAN_PIN || p == E2_AUTO_FAN_PIN || p == E3_AUTO_FAN_PIN || p == E4_AUTO_FAN_PIN || p == E5_AUTO_FAN_PIN || p == CHAMBER_AUTO_FAN_PIN)
286
+  #define PWM_CHK_FAN_B(P) (P == CONTROLLER_FAN_PIN || P == E0_AUTO_FAN_PIN || P == E1_AUTO_FAN_PIN || P == E2_AUTO_FAN_PIN || P == E3_AUTO_FAN_PIN || P == E4_AUTO_FAN_PIN || P == E5_AUTO_FAN_PIN || P == CHAMBER_AUTO_FAN_PIN)
283 287
 #else
284
-  #define PWM_CHK_FAN_B(p) (p == E0_AUTO_FAN_PIN || p == E1_AUTO_FAN_PIN || p == E2_AUTO_FAN_PIN || p == E3_AUTO_FAN_PIN || p == E4_AUTO_FAN_PIN || p == E5_AUTO_FAN_PIN || p == CHAMBER_AUTO_FAN_PIN)
288
+  #define PWM_CHK_FAN_B(P) (P == E0_AUTO_FAN_PIN || P == E1_AUTO_FAN_PIN || P == E2_AUTO_FAN_PIN || P == E3_AUTO_FAN_PIN || P == E4_AUTO_FAN_PIN || P == E5_AUTO_FAN_PIN || P == CHAMBER_AUTO_FAN_PIN)
285 289
 #endif
286 290
 
287 291
 #if PIN_EXISTS(FAN) || PIN_EXISTS(FAN1) || PIN_EXISTS(FAN2)
288 292
   #if PIN_EXISTS(FAN2)
289
-    #define PWM_CHK_FAN_A(p) (p == FAN_PIN || p == FAN1_PIN || p == FAN2_PIN)
293
+    #define PWM_CHK_FAN_A(P) (P == FAN_PIN || P == FAN1_PIN || P == FAN2_PIN)
290 294
   #elif PIN_EXISTS(FAN1)
291
-    #define PWM_CHK_FAN_A(p) (p == FAN_PIN || p == FAN1_PIN)
295
+    #define PWM_CHK_FAN_A(P) (P == FAN_PIN || P == FAN1_PIN)
292 296
   #else
293
-    #define PWM_CHK_FAN_A(p) (p == FAN_PIN)
297
+    #define PWM_CHK_FAN_A(P) (P == FAN_PIN)
294 298
   #endif
295 299
 #else
296
-  #define PWM_CHK_FAN_A(p) false
300
+  #define PWM_CHK_FAN_A(P) false
297 301
 #endif
298 302
 
299 303
 #if HAS_MOTOR_CURRENT_PWM
300 304
   #if PIN_EXISTS(MOTOR_CURRENT_PWM_XY)
301
-    #define PWM_CHK_MOTOR_CURRENT(p) (p == MOTOR_CURRENT_PWM_E || p == MOTOR_CURRENT_PWM_Z || p == MOTOR_CURRENT_PWM_XY)
305
+    #define PWM_CHK_MOTOR_CURRENT(P) (P == MOTOR_CURRENT_PWM_E || P == MOTOR_CURRENT_PWM_Z || P == MOTOR_CURRENT_PWM_XY)
302 306
   #elif PIN_EXISTS(MOTOR_CURRENT_PWM_Z)
303
-    #define PWM_CHK_MOTOR_CURRENT(p) (p == MOTOR_CURRENT_PWM_E || p == MOTOR_CURRENT_PWM_Z)
307
+    #define PWM_CHK_MOTOR_CURRENT(P) (P == MOTOR_CURRENT_PWM_E || P == MOTOR_CURRENT_PWM_Z)
304 308
   #else
305
-    #define PWM_CHK_MOTOR_CURRENT(p) (p == MOTOR_CURRENT_PWM_E)
309
+    #define PWM_CHK_MOTOR_CURRENT(P) (P == MOTOR_CURRENT_PWM_E)
306 310
   #endif
307 311
 #else
308
-  #define PWM_CHK_MOTOR_CURRENT(p) false
312
+  #define PWM_CHK_MOTOR_CURRENT(P) false
309 313
 #endif
310 314
 
311 315
 #ifdef NUM_SERVOS
312 316
   #if AVR_ATmega2560_FAMILY
313
-    #define PWM_CHK_SERVO(p) (p == 5 || (NUM_SERVOS > 12 && p == 6) || (NUM_SERVOS > 24 && p == 46))  // PWMS 3A, 4A & 5A
317
+    #define PWM_CHK_SERVO(P) (P == 5 || (NUM_SERVOS > 12 && P == 6) || (NUM_SERVOS > 24 && P == 46))  // PWMS 3A, 4A & 5A
314 318
   #elif AVR_ATmega2561_FAMILY
315
-    #define PWM_CHK_SERVO(p)   (p == 5)  // PWM3A
319
+    #define PWM_CHK_SERVO(P)   (P == 5)  // PWM3A
316 320
   #elif AVR_ATmega1284_FAMILY
317
-    #define PWM_CHK_SERVO(p)   false
321
+    #define PWM_CHK_SERVO(P)   false
318 322
   #elif AVR_AT90USB1286_FAMILY
319
-    #define PWM_CHK_SERVO(p)   (p == 16) // PWM3A
323
+    #define PWM_CHK_SERVO(P)   (P == 16) // PWM3A
320 324
   #elif AVR_ATmega328_FAMILY
321
-    #define PWM_CHK_SERVO(p)   false
325
+    #define PWM_CHK_SERVO(P)   false
322 326
   #endif
323 327
 #else
324
-  #define PWM_CHK_SERVO(p) false
328
+  #define PWM_CHK_SERVO(P) false
325 329
 #endif
326 330
 
327 331
 #if ENABLED(BARICUDA)
328 332
   #if HAS_HEATER_1 && HAS_HEATER_2
329
-    #define PWM_CHK_HEATER(p) (p == HEATER_1_PIN || p == HEATER_2_PIN)
333
+    #define PWM_CHK_HEATER(P) (P == HEATER_1_PIN || P == HEATER_2_PIN)
330 334
   #elif HAS_HEATER_1
331
-    #define PWM_CHK_HEATER(p) (p == HEATER_1_PIN)
335
+    #define PWM_CHK_HEATER(P) (P == HEATER_1_PIN)
332 336
   #endif
333 337
 #else
334
-    #define PWM_CHK_HEATER(p) false
338
+    #define PWM_CHK_HEATER(P) false
335 339
 #endif
336 340
 
337
-#define PWM_CHK(p) (PWM_CHK_HEATER(p) || PWM_CHK_SERVO(p) || PWM_CHK_MOTOR_CURRENT(p) || PWM_CHK_FAN_A(p) || PWM_CHK_FAN_B(p))
341
+#define PWM_CHK(P) (PWM_CHK_HEATER(P) || PWM_CHK_SERVO(P) || PWM_CHK_MOTOR_CURRENT(P) || PWM_CHK_FAN_A(P) || PWM_CHK_FAN_B(P))
338 342
 
339 343
 // define which hardware PWMs are available for the current CPU
340 344
 // all timer 1 PWMS deleted from this list because they are never available
341 345
 #if AVR_ATmega2560_FAMILY
342
-  #define PWM_PIN(p)  ((p >= 2 && p <= 10) || p == 13 || p == 44 || p == 45 || p == 46)
346
+  #define PWM_PIN(P)  ((P >= 2 && P <= 10) || P == 13 || P == 44 || P == 45 || P == 46)
343 347
 #elif AVR_ATmega2561_FAMILY
344
-  #define PWM_PIN(p)  ((p >= 2 && p <= 6) || p == 9)
348
+  #define PWM_PIN(P)  ((P >= 2 && P <= 6) || P == 9)
345 349
 #elif AVR_ATmega1284_FAMILY
346
-  #define PWM_PIN(p)  (p == 3 || p == 4 || p == 14 || p == 15)
350
+  #define PWM_PIN(P)  (P == 3 || P == 4 || P == 14 || P == 15)
347 351
 #elif AVR_AT90USB1286_FAMILY
348
-  #define PWM_PIN(p)  (p == 0 || p == 1 || p == 14 || p == 15 || p == 16 || p == 24)
352
+  #define PWM_PIN(P)  (P == 0 || P == 1 || P == 14 || P == 15 || P == 16 || P == 24)
349 353
 #elif AVR_ATmega328_FAMILY
350
-  #define PWM_PIN(p)  (p == 3 || p == 5 || p == 6 || p == 11)
354
+  #define PWM_PIN(P)  (P == 3 || P == 5 || P == 6 || P == 11)
351 355
 #else
352 356
   #error "unknown CPU"
353 357
 #endif

+ 6
- 1
Marlin/src/HAL/HAL_DUE/fastio_Due.h 查看文件

@@ -45,7 +45,8 @@
45 45
 
46 46
 // Due has 12 PWMs assigned to logical pins 2-13.
47 47
 // 6, 7, 8 & 9 come from the PWM controller. The others come from the timers.
48
-#define USEABLE_HARDWARE_PWM(p) WITHIN(p, 2, 13)
48
+#define PWM_PIN(P)              WITHIN(P, 2, 13)
49
+#define USEABLE_HARDWARE_PWM(P) PWM_PIN(P)
49 50
 
50 51
 #ifndef MASK
51 52
   #define MASK(PIN) (1 << PIN)
@@ -172,6 +173,8 @@
172 173
 #define SET_INPUT_PULLUP(IO) do{ _SET_INPUT(IO); _PULLUP(IO, HIGH); }while(0)
173 174
 // Set pin as output (wrapper) -  reads the pin and sets the output to that value
174 175
 #define SET_OUTPUT(IO)       _SET_OUTPUT(IO)
176
+// Set pin as PWM
177
+#define SET_PWM(IO)           SET_OUTPUT(IO)
175 178
 
176 179
 // Check if pin is an input
177 180
 #define GET_INPUT(IO)        ((digitalPinToPort(IO)->PIO_OSR & digitalPinToBitMask(IO)) == 0)
@@ -187,6 +190,8 @@
187 190
 #define extDigitalRead(IO)    digitalRead(IO)
188 191
 #define extDigitalWrite(IO,V) digitalWrite(IO,V)
189 192
 
193
+#define ANALOG_WRITE(IO,V)    analogWrite(IO,V)
194
+
190 195
 /**
191 196
  * Ports and functions
192 197
  * Added as necessary or if I feel like it- not a comprehensive list!

+ 20
- 11
Marlin/src/HAL/HAL_ESP32/fastio_ESP32.h 查看文件

@@ -28,34 +28,43 @@
28 28
  */
29 29
 
30 30
 // Set pin as input
31
-#define _SET_INPUT(IO)        pinMode(IO, INPUT)
31
+#define _SET_INPUT(IO)          pinMode(IO, INPUT)
32 32
 
33 33
 // Set pin as output
34
-#define _SET_OUTPUT(IO)       pinMode(IO, OUTPUT)
34
+#define _SET_OUTPUT(IO)         pinMode(IO, OUTPUT)
35 35
 
36 36
 // Set pin as input with pullup mode
37
-#define _PULLUP(IO, v)        pinMode(IO, v ? INPUT_PULLUP : INPUT)
37
+#define _PULLUP(IO, v)          pinMode(IO, v ? INPUT_PULLUP : INPUT)
38 38
 
39 39
 // Read a pin wrapper
40
-#define READ(IO)              digitalRead(IO)
40
+#define READ(IO)                digitalRead(IO)
41 41
 
42 42
 // Write to a pin wrapper
43
-#define WRITE(IO, v)          (TEST(IO, 7) ? i2s_write(IO & 0x7F, v) : digitalWrite(IO, v))
43
+#define WRITE(IO, v)            (TEST(IO, 7) ? i2s_write(IO & 0x7F, v) : digitalWrite(IO, v))
44 44
 
45 45
 // Set pin as input wrapper
46
-#define SET_INPUT(IO)         _SET_INPUT(IO)
46
+#define SET_INPUT(IO)           _SET_INPUT(IO)
47 47
 
48 48
 // Set pin as input with pullup wrapper
49
-#define SET_INPUT_PULLUP(IO)  do{ _SET_INPUT(IO); _PULLUP(IO, HIGH); }while(0)
49
+#define SET_INPUT_PULLUP(IO)    do{ _SET_INPUT(IO); _PULLUP(IO, HIGH); }while(0)
50 50
 
51 51
 // Set pin as output wrapper
52
-#define SET_OUTPUT(IO)        do{ _SET_OUTPUT(IO); WRITE(IO, LOW); }while(0)
52
+#define SET_OUTPUT(IO)          do{ _SET_OUTPUT(IO); }while(0)
53 53
 
54
-#define OUT_WRITE(IO,V)       do{ _SET_OUTPUT(IO); WRITE(IO,V); }while(0)
54
+// Set pin as PWM
55
+#define SET_PWM(IO)             SET_OUTPUT(IO)
56
+
57
+// Set pin as output and init
58
+#define OUT_WRITE(IO,V)         do{ _SET_OUTPUT(IO); WRITE(IO,V); }while(0)
55 59
 
56 60
 // digitalRead/Write wrappers
57
-#define extDigitalRead(IO)    digitalRead(IO)
58
-#define extDigitalWrite(IO,V) digitalWrite(IO,V)
61
+#define extDigitalRead(IO)      digitalRead(IO)
62
+#define extDigitalWrite(IO,V)   digitalWrite(IO,V)
63
+
64
+#define ANALOG_WRITE(IO,V)      analogWrite(IO,V)
65
+
66
+#define PWM_PIN(P)              true
67
+#define USEABLE_HARDWARE_PWM(P) PWM_PIN(P)
59 68
 
60 69
 //
61 70
 // Ports and functions

+ 6
- 2
Marlin/src/HAL/HAL_LINUX/fastio.h 查看文件

@@ -28,8 +28,6 @@
28 28
 #include <Arduino.h>
29 29
 #include <pinmapping.h>
30 30
 
31
-#define USEABLE_HARDWARE_PWM(pin) false
32
-
33 31
 #define SET_DIR_INPUT(IO)     Gpio::setDir(IO, 1)
34 32
 #define SET_DIR_OUTPUT(IO)    Gpio::setDir(IO, 0)
35 33
 
@@ -110,6 +108,8 @@
110 108
 #define SET_INPUT_PULLDOWN(IO) do{ _SET_INPUT(IO); _PULLDOWN(IO, HIGH); }while(0)
111 109
 /// set pin as output wrapper  -  reads the pin and sets the output to that value
112 110
 #define SET_OUTPUT(IO)        do{ _WRITE(IO, _READ(IO)); _SET_OUTPUT(IO); }while(0)
111
+// set pin as PWM
112
+#define SET_PWM(IO)           SET_OUTPUT(IO)
113 113
 
114 114
 /// check if pin is an input wrapper
115 115
 #define GET_INPUT(IO)        _GET_INPUT(IO)
@@ -125,3 +125,7 @@
125 125
 // digitalRead/Write wrappers
126 126
 #define extDigitalRead(IO)    digitalRead(IO)
127 127
 #define extDigitalWrite(IO,V) digitalWrite(IO,V)
128
+
129
+#define ANALOG_WRITE(IO,V)    analogWrite(IO,V)
130
+
131
+#define USEABLE_HARDWARE_PWM(P) PWM_PIN(P)

+ 4
- 0
Marlin/src/HAL/HAL_LPC1768/fastio.h 查看文件

@@ -111,6 +111,8 @@
111 111
 #define SET_INPUT_PULLDOWN(IO) do{ _SET_INPUT(IO); _PULLDOWN(IO, HIGH); }while(0)
112 112
 /// set pin as output wrapper  -  reads the pin and sets the output to that value
113 113
 #define SET_OUTPUT(IO)        do{ _WRITE(IO, _READ(IO)); _SET_OUTPUT(IO); }while(0)
114
+// set pin as PWM
115
+#define SET_PWM(IO)           SET_OUTPUT(IO)
114 116
 
115 117
 /// check if pin is an input wrapper
116 118
 #define GET_INPUT(IO)         _GET_INPUT(IO)
@@ -126,3 +128,5 @@
126 128
 // digitalRead/Write wrappers
127 129
 #define extDigitalRead(IO)    digitalRead(IO)
128 130
 #define extDigitalWrite(IO,V) digitalWrite(IO,V)
131
+
132
+#define ANALOG_WRITE(IO,V)    analogWrite(IO,V)

+ 5
- 2
Marlin/src/HAL/HAL_STM32/fastio_STM32.h 查看文件

@@ -72,14 +72,17 @@ void FastIO_init(); // Must be called before using fast io macros
72 72
 #define SET_INPUT_PULLUP(IO)    _SET_MODE(IO, INPUT_PULLUP)                       /*!< Input with Pull-up activation         */
73 73
 #define SET_INPUT_PULLDOWN(IO)  _SET_MODE(IO, INPUT_PULLDOWN)                     /*!< Input with Pull-down activation       */
74 74
 #define SET_OUTPUT(IO)          OUT_WRITE(IO, LOW)
75
+#define SET_PWM(IO)             _SET_MODE(IO, PWM)
75 76
 
76 77
 #define GET_INPUT(IO)
77 78
 #define GET_OUTPUT(IO)
78 79
 #define GET_TIMER(IO)
79 80
 
80
-#define PWM_PIN(p)              digitalPinHasPWM(p)
81
-#define USEABLE_HARDWARE_PWM(p) PWM_PIN(p)
81
+#define PWM_PIN(P)              digitalPinHasPWM(P)
82
+#define USEABLE_HARDWARE_PWM(P) PWM_PIN(P)
82 83
 
83 84
 // digitalRead/Write wrappers
84 85
 #define extDigitalRead(IO)    digitalRead(IO)
85 86
 #define extDigitalWrite(IO,V) digitalWrite(IO,V)
87
+
88
+#define ANALOG_WRITE(IO,V)    analogWrite(IO,V)

+ 5
- 2
Marlin/src/HAL/HAL_STM32F1/fastio_STM32F1.h 查看文件

@@ -43,14 +43,17 @@
43 43
 #define SET_INPUT(IO)         _SET_MODE(IO, GPIO_INPUT_FLOATING)
44 44
 #define SET_INPUT_PULLUP(IO)  _SET_MODE(IO, GPIO_INPUT_PU)
45 45
 #define SET_OUTPUT(IO)        OUT_WRITE(IO, LOW)
46
+#define SET_PWM(IO)           pinMode(IO, PWM)    // do{ gpio_set_mode(PIN_MAP[pin].gpio_device, PIN_MAP[pin].gpio_bit, GPIO_AF_OUTPUT_PP); timer_set_mode(PIN_MAP[pin].timer_device, PIN_MAP[pin].timer_channel, TIMER_PWM); }while(0)
46 47
 
47 48
 #define GET_INPUT(IO)         (_GET_MODE(IO) == GPIO_INPUT_FLOATING || _GET_MODE(IO) == GPIO_INPUT_ANALOG || _GET_MODE(IO) == GPIO_INPUT_PU || _GET_MODE(IO) == GPIO_INPUT_PD)
48 49
 #define GET_OUTPUT(IO)        (_GET_MODE(IO) == GPIO_OUTPUT_PP)
49 50
 #define GET_TIMER(IO)         (PIN_MAP[IO].timer_device != NULL)
50 51
 
51
-#define PWM_PIN(p) true
52
-#define USEABLE_HARDWARE_PWM(p) PWM_PIN(p)
52
+#define PWM_PIN(P)              digitalPinHasPWM(P)
53
+#define USEABLE_HARDWARE_PWM(P) PWM_PIN(P)
53 54
 
54 55
 // digitalRead/Write wrappers
55 56
 #define extDigitalRead(IO)    digitalRead(IO)
56 57
 #define extDigitalWrite(IO,V) digitalWrite(IO,V)
58
+
59
+#define ANALOG_WRITE(IO,V)    analogWrite(IO,(V)*65535/255)

+ 5
- 2
Marlin/src/HAL/HAL_STM32F4/fastio_STM32F4.h 查看文件

@@ -44,6 +44,7 @@
44 44
 #define SET_INPUT_PULLUP(IO)    _SET_MODE(IO, INPUT_PULLUP)                       /*!< Input with Pull-up activation         */
45 45
 #define SET_INPUT_PULLDOWN(IO)  _SET_MODE(IO, INPUT_PULLDOWN)                     /*!< Input with Pull-down activation       */
46 46
 #define SET_OUTPUT(IO)          OUT_WRITE(IO, LOW)
47
+#define SET_PWM(IO)             pinMode(IO, PWM)
47 48
 
48 49
 #define TOGGLE(IO)              OUT_WRITE(IO, !READ(IO))
49 50
 
@@ -51,13 +52,15 @@
51 52
 #define GET_OUTPUT(IO)
52 53
 #define GET_TIMER(IO)
53 54
 
54
-#define PWM_PIN(p) true
55
-#define USEABLE_HARDWARE_PWM(p) PWM_PIN(p)
55
+#define PWM_PIN(P)              true
56
+#define USEABLE_HARDWARE_PWM(P) PWM_PIN(P)
56 57
 
57 58
 // digitalRead/Write wrappers
58 59
 #define extDigitalRead(IO)    digitalRead(IO)
59 60
 #define extDigitalWrite(IO,V) digitalWrite(IO,V)
60 61
 
62
+#define ANALOG_WRITE(IO,V)    analogWrite(IO,(V)*65535/255)
63
+
61 64
 //
62 65
 // Pins Definitions
63 66
 //

+ 5
- 2
Marlin/src/HAL/HAL_STM32F7/fastio_STM32F7.h 查看文件

@@ -43,6 +43,7 @@
43 43
 #define SET_INPUT_PULLUP(IO)    _SET_MODE(IO, INPUT_PULLUP)                       /*!< Input with Pull-up activation         */
44 44
 #define SET_INPUT_PULLDOWN(IO)  _SET_MODE(IO, INPUT_PULLDOWN)                     /*!< Input with Pull-down activation       */
45 45
 #define SET_OUTPUT(IO)          OUT_WRITE(IO, LOW)
46
+#define SET_PWM(IO)             _SET_MODE(IO, PWM)
46 47
 
47 48
 #define TOGGLE(IO)              OUT_WRITE(IO, !READ(IO))
48 49
 
@@ -50,13 +51,15 @@
50 51
 #define GET_OUTPUT(IO)
51 52
 #define GET_TIMER(IO)
52 53
 
53
-#define PWM_PIN(p)              true
54
-#define USEABLE_HARDWARE_PWM(p) PWM_PIN(p)
54
+#define PWM_PIN(P)              true
55
+#define USEABLE_HARDWARE_PWM(P) PWM_PIN(P)
55 56
 
56 57
 // digitalRead/Write wrappers
57 58
 #define extDigitalRead(IO)    digitalRead(IO)
58 59
 #define extDigitalWrite(IO,V) digitalWrite(IO,V)
59 60
 
61
+#define ANALOG_WRITE(IO,V)    analogWrite(IO,(V)*65535/255)
62
+
60 63
 //
61 64
 // Pins Definitions
62 65
 //

+ 7
- 1
Marlin/src/HAL/HAL_TEENSY31_32/fastio_Teensy.h 查看文件

@@ -43,7 +43,7 @@
43 43
  * Why double up on these macros? see http://gcc.gnu.org/onlinedocs/cpp/Stringification.html
44 44
  */
45 45
 
46
-#define _READ(p) bool(CORE_PIN ## p ## _PINREG & CORE_PIN ## p ## _BITMASK)
46
+#define _READ(P) bool(CORE_PIN ## P ## _PINREG & CORE_PIN ## P ## _BITMASK)
47 47
 
48 48
 #define _WRITE(P,V) do{ \
49 49
   if (V) CORE_PIN ## P ## _PORTSET = CORE_PIN ## P ## _BITMASK; \
@@ -79,6 +79,7 @@
79 79
 #define SET_INPUT(IO)         _SET_INPUT(IO)
80 80
 #define SET_INPUT_PULLUP(IO)  _SET_INPUT_PULLUP(IO)
81 81
 #define SET_OUTPUT(IO)        _SET_OUTPUT(IO)
82
+#define SET_PWM(IO)            SET_OUTPUT(IO)
82 83
 
83 84
 #define GET_INPUT(IO)         _GET_INPUT(IO)
84 85
 #define GET_OUTPUT(IO)        _GET_OUTPUT(IO)
@@ -89,6 +90,11 @@
89 90
 #define extDigitalRead(IO)    digitalRead(IO)
90 91
 #define extDigitalWrite(IO,V) digitalWrite(IO,V)
91 92
 
93
+#define ANALOG_WRITE(IO,V)    analogWrite(IO,V)
94
+
95
+#define PWM_PIN(P)            digitalPinHasPWM(P)
96
+#define USEABLE_HARDWARE_PWM(P) PWM_PIN(P)
97
+
92 98
 /**
93 99
  * Ports, functions, and pins
94 100
  */

+ 7
- 1
Marlin/src/HAL/HAL_TEENSY35_36/fastio_Teensy.h 查看文件

@@ -42,7 +42,7 @@
42 42
  * Why double up on these macros? see http://gcc.gnu.org/onlinedocs/cpp/Stringification.html
43 43
  */
44 44
 
45
-#define _READ(p) bool(CORE_PIN ## p ## _PINREG & CORE_PIN ## p ## _BITMASK)
45
+#define _READ(P) bool(CORE_PIN ## P ## _PINREG & CORE_PIN ## P ## _BITMASK)
46 46
 
47 47
 #define _WRITE(P,V) do{ \
48 48
   if (V) CORE_PIN ## P ## _PORTSET = CORE_PIN ## P ## _BITMASK; \
@@ -78,6 +78,7 @@
78 78
 #define SET_INPUT(IO)         _SET_INPUT(IO)
79 79
 #define SET_INPUT_PULLUP(IO)  _SET_INPUT_PULLUP(IO)
80 80
 #define SET_OUTPUT(IO)        _SET_OUTPUT(IO)
81
+#define SET_PWM(IO)            SET_OUTPUT(IO)
81 82
 
82 83
 #define GET_INPUT(IO)         _GET_INPUT(IO)
83 84
 #define GET_OUTPUT(IO)        _GET_OUTPUT(IO)
@@ -88,6 +89,11 @@
88 89
 #define extDigitalRead(IO)    digitalRead(IO)
89 90
 #define extDigitalWrite(IO,V) digitalWrite(IO,V)
90 91
 
92
+#define ANALOG_WRITE(IO,V)    analogWrite(IO,V)
93
+
94
+#define PWM_PIN(P)            digitalPinHasPWM(P)
95
+#define USEABLE_HARDWARE_PWM(P) PWM_PIN(P)
96
+
91 97
 /**
92 98
  * Ports, functions, and pins
93 99
  */

+ 3
- 3
Marlin/src/Marlin.cpp 查看文件

@@ -975,8 +975,8 @@ void setup() {
975 975
       OUT_WRITE(SPINDLE_DIR_PIN, SPINDLE_INVERT_DIR ? 255 : 0);  // init rotation to clockwise (M3)
976 976
     #endif
977 977
     #if ENABLED(SPINDLE_LASER_PWM) && defined(SPINDLE_LASER_PWM_PIN) && SPINDLE_LASER_PWM_PIN >= 0
978
-      SET_OUTPUT(SPINDLE_LASER_PWM_PIN);
979
-      analogWrite(SPINDLE_LASER_PWM_PIN, SPINDLE_LASER_PWM_INVERT ? 255 : 0);  // set to lowest speed
978
+      SET_PWM(SPINDLE_LASER_PWM_PIN);
979
+      ANALOG_WRITE(SPINDLE_LASER_PWM_PIN, SPINDLE_LASER_PWM_INVERT ? 255 : 0);  // set to lowest speed
980 980
     #endif
981 981
   #endif
982 982
 
@@ -1022,7 +1022,7 @@ void setup() {
1022 1022
 
1023 1023
   #if HAS_CASE_LIGHT
1024 1024
     #if DISABLED(CASE_LIGHT_USE_NEOPIXEL)
1025
-      SET_OUTPUT(CASE_LIGHT_PIN);
1025
+      if (PWM_PIN(CASE_LIGHT_PIN)) SET_PWM(CASE_LIGHT_PIN); else SET_OUTPUT(CASE_LIGHT_PIN);
1026 1026
     #endif
1027 1027
     update_case_light();
1028 1028
   #endif

+ 2
- 2
Marlin/src/feature/caselight.cpp 查看文件

@@ -69,8 +69,8 @@ void update_case_light() {
69 69
 
70 70
   #else // !CASE_LIGHT_USE_NEOPIXEL
71 71
 
72
-    if (USEABLE_HARDWARE_PWM(CASE_LIGHT_PIN))
73
-      analogWrite(CASE_LIGHT_PIN, n10ct);
72
+    if (PWM_PIN(CASE_LIGHT_PIN))
73
+      ANALOG_WRITE(CASE_LIGHT_PIN, n10ct);
74 74
     else {
75 75
       const bool s = case_light_on ? !INVERT_CASE_LIGHT : INVERT_CASE_LIGHT;
76 76
       WRITE(CASE_LIGHT_PIN, s ? HIGH : LOW);

+ 1
- 1
Marlin/src/feature/controllerfan.cpp 查看文件

@@ -81,7 +81,7 @@ void controllerfan_update() {
81 81
 
82 82
     // allows digital or PWM fan output to be used (see M42 handling)
83 83
     WRITE(CONTROLLER_FAN_PIN, speed);
84
-    analogWrite(CONTROLLER_FAN_PIN, speed);
84
+    ANALOG_WRITE(CONTROLLER_FAN_PIN, speed);
85 85
   }
86 86
 }
87 87
 

+ 9
- 13
Marlin/src/feature/leds/leds.cpp 查看文件

@@ -61,11 +61,11 @@ LEDLights leds;
61 61
 
62 62
 void LEDLights::setup() {
63 63
   #if ENABLED(RGB_LED) || ENABLED(RGBW_LED)
64
-    SET_OUTPUT(RGB_LED_R_PIN);
65
-    SET_OUTPUT(RGB_LED_G_PIN);
66
-    SET_OUTPUT(RGB_LED_B_PIN);
64
+    if (PWM_PIN(RGB_LED_R_PIN)) SET_PWM(RGB_LED_R_PIN); else SET_OUTPUT(RGB_LED_R_PIN);
65
+    if (PWM_PIN(RGB_LED_G_PIN)) SET_PWM(RGB_LED_G_PIN); else SET_OUTPUT(RGB_LED_G_PIN);
66
+    if (PWM_PIN(RGB_LED_B_PIN)) SET_PWM(RGB_LED_B_PIN); else SET_OUTPUT(RGB_LED_B_PIN);
67 67
     #if ENABLED(RGBW_LED)
68
-      SET_OUTPUT(RGB_LED_W_PIN);
68
+      if (PWM_PIN(RGB_LED_W_PIN)) SET_PWM(RGB_LED_W_PIN); else SET_OUTPUT(RGB_LED_W_PIN);
69 69
     #endif
70 70
   #endif
71 71
   #if ENABLED(NEOPIXEL_LED)
@@ -112,16 +112,12 @@ void LEDLights::set_color(const LEDColor &incol
112 112
 
113 113
     // This variant uses 3-4 separate pins for the RGB(W) components.
114 114
     // If the pins can do PWM then their intensity will be set.
115
-    WRITE(RGB_LED_R_PIN, incol.r ? HIGH : LOW);
116
-    WRITE(RGB_LED_G_PIN, incol.g ? HIGH : LOW);
117
-    WRITE(RGB_LED_B_PIN, incol.b ? HIGH : LOW);
118
-    analogWrite(RGB_LED_R_PIN, incol.r);
119
-    analogWrite(RGB_LED_G_PIN, incol.g);
120
-    analogWrite(RGB_LED_B_PIN, incol.b);
121
-
115
+    #define UPDATE_RGBW(C,c) do{ if (PWM_PIN(RGB_LED_##C##_PIN)) ANALOG_WRITE(RGB_LED_##C##_PIN, incol.r); else WRITE(RGB_LED_##C##_PIN, incol.c ? HIGH : LOW); }while(0)
116
+    UPDATE_RGBW(R,r);
117
+    UPDATE_RGBW(G,g);
118
+    UPDATE_RGBW(B,b);
122 119
     #if ENABLED(RGBW_LED)
123
-      WRITE(RGB_LED_W_PIN, incol.w ? HIGH : LOW);
124
-      analogWrite(RGB_LED_W_PIN, incol.w);
120
+      UPDATE_RGBW(W,w);
125 121
     #endif
126 122
 
127 123
   #endif

+ 2
- 2
Marlin/src/gcode/control/M3-M5.cpp 查看文件

@@ -74,7 +74,7 @@ inline void delay_for_power_down() { safe_delay(SPINDLE_LASER_POWERDOWN_DELAY);
74 74
 
75 75
 inline void set_spindle_laser_ocr(const uint8_t ocr) {
76 76
   WRITE(SPINDLE_LASER_ENABLE_PIN, SPINDLE_LASER_ENABLE_INVERT); // turn spindle on (active low)
77
-  analogWrite(SPINDLE_LASER_PWM_PIN, (SPINDLE_LASER_PWM_INVERT) ? 255 - ocr : ocr);
77
+  ANALOG_WRITE(SPINDLE_LASER_PWM_PIN, (SPINDLE_LASER_PWM_INVERT) ? 255 - ocr : ocr);
78 78
 }
79 79
 
80 80
 #if ENABLED(SPINDLE_LASER_PWM)
@@ -82,7 +82,7 @@ inline void set_spindle_laser_ocr(const uint8_t ocr) {
82 82
   void update_spindle_laser_power() {
83 83
     if (spindle_laser_power == 0) {
84 84
       WRITE(SPINDLE_LASER_ENABLE_PIN, !SPINDLE_LASER_ENABLE_INVERT);                      // turn spindle off (active low)
85
-      analogWrite(SPINDLE_LASER_PWM_PIN, SPINDLE_LASER_PWM_INVERT ? 255 : 0);             // only write low byte
85
+      ANALOG_WRITE(SPINDLE_LASER_PWM_PIN, SPINDLE_LASER_PWM_INVERT ? 255 : 0);             // only write low byte
86 86
       delay_for_power_down();
87 87
     }
88 88
     else {                                                                                // Convert RPM to PWM duty cycle

+ 1
- 1
Marlin/src/gcode/control/M42.cpp 查看文件

@@ -51,7 +51,7 @@ void GcodeSuite::M42() {
51 51
 
52 52
   pinMode(pin, OUTPUT);
53 53
   extDigitalWrite(pin, pin_status);
54
-  analogWrite(pin, pin_status);
54
+  ANALOG_WRITE(pin, pin_status);
55 55
 
56 56
   #if FAN_COUNT > 0
57 57
     switch (pin) {

+ 1
- 1
Marlin/src/gcode/feature/caselight/M355.cpp 查看文件

@@ -57,7 +57,7 @@
57 57
       SERIAL_ECHOLNPGM("Case light: off");
58 58
     }
59 59
     else {
60
-      if (!USEABLE_HARDWARE_PWM(CASE_LIGHT_PIN)) SERIAL_ECHOLNPGM("Case light: on");
60
+      if (!PWM_PIN(CASE_LIGHT_PIN)) SERIAL_ECHOLNPGM("Case light: on");
61 61
       else SERIAL_ECHOLNPAIR("Case light: ", case_light_brightness);
62 62
     }
63 63
   }

+ 1
- 1
Marlin/src/gcode/host/M115.cpp 查看文件

@@ -125,7 +125,7 @@ void GcodeSuite::M115() {
125 125
     );
126 126
     cap_line(PSTR("CASE_LIGHT_BRIGHTNESS")
127 127
       #if HAS_CASE_LIGHT
128
-        , USEABLE_HARDWARE_PWM(CASE_LIGHT_PIN)
128
+        , PWM_PIN(CASE_LIGHT_PIN)
129 129
       #endif
130 130
     );
131 131
 

+ 0
- 21
Marlin/src/inc/Conditionals_post.h 查看文件

@@ -958,27 +958,6 @@
958 958
 #define HAS_AUTO_FAN_5 (HOTENDS > 5 && PIN_EXISTS(E5_AUTO_FAN))
959 959
 #define HAS_AUTO_CHAMBER_FAN (PIN_EXISTS(CHAMBER_AUTO_FAN))
960 960
 #define HAS_AUTO_FAN (HAS_AUTO_FAN_0 || HAS_AUTO_FAN_1 || HAS_AUTO_FAN_2 || HAS_AUTO_FAN_3 || HAS_AUTO_FAN_4 || HAS_AUTO_FAN_5 || HAS_AUTO_CHAMBER_FAN)
961
-#define AUTO_1_IS_0 (E1_AUTO_FAN_PIN == E0_AUTO_FAN_PIN)
962
-#define AUTO_2_IS_0 (E2_AUTO_FAN_PIN == E0_AUTO_FAN_PIN)
963
-#define AUTO_2_IS_1 (E2_AUTO_FAN_PIN == E1_AUTO_FAN_PIN)
964
-#define AUTO_3_IS_0 (E3_AUTO_FAN_PIN == E0_AUTO_FAN_PIN)
965
-#define AUTO_3_IS_1 (E3_AUTO_FAN_PIN == E1_AUTO_FAN_PIN)
966
-#define AUTO_3_IS_2 (E3_AUTO_FAN_PIN == E2_AUTO_FAN_PIN)
967
-#define AUTO_4_IS_0 (E4_AUTO_FAN_PIN == E0_AUTO_FAN_PIN)
968
-#define AUTO_4_IS_1 (E4_AUTO_FAN_PIN == E1_AUTO_FAN_PIN)
969
-#define AUTO_4_IS_2 (E4_AUTO_FAN_PIN == E2_AUTO_FAN_PIN)
970
-#define AUTO_4_IS_3 (E4_AUTO_FAN_PIN == E3_AUTO_FAN_PIN)
971
-#define AUTO_5_IS_0 (E5_AUTO_FAN_PIN == E0_AUTO_FAN_PIN)
972
-#define AUTO_5_IS_1 (E5_AUTO_FAN_PIN == E1_AUTO_FAN_PIN)
973
-#define AUTO_5_IS_2 (E5_AUTO_FAN_PIN == E2_AUTO_FAN_PIN)
974
-#define AUTO_5_IS_3 (E5_AUTO_FAN_PIN == E3_AUTO_FAN_PIN)
975
-#define AUTO_5_IS_4 (E5_AUTO_FAN_PIN == E4_AUTO_FAN_PIN)
976
-#define AUTO_CHAMBER_IS_0 (CHAMBER_AUTO_FAN_PIN == E0_AUTO_FAN_PIN)
977
-#define AUTO_CHAMBER_IS_1 (CHAMBER_AUTO_FAN_PIN == E1_AUTO_FAN_PIN)
978
-#define AUTO_CHAMBER_IS_2 (CHAMBER_AUTO_FAN_PIN == E2_AUTO_FAN_PIN)
979
-#define AUTO_CHAMBER_IS_3 (CHAMBER_AUTO_FAN_PIN == E3_AUTO_FAN_PIN)
980
-#define AUTO_CHAMBER_IS_4 (CHAMBER_AUTO_FAN_PIN == E4_AUTO_FAN_PIN)
981
-#define AUTO_CHAMBER_IS_5 (CHAMBER_AUTO_FAN_PIN == E5_AUTO_FAN_PIN)
982 961
 
983 962
 // Other fans
984 963
 #define HAS_FAN0 (PIN_EXISTS(FAN))

+ 4
- 4
Marlin/src/inc/SanityCheck.h 查看文件

@@ -1700,13 +1700,13 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS
1700 1700
 #if HAS_AUTO_FAN && EXTRUDER_AUTO_FAN_SPEED != 255
1701 1701
   #define AF_ERR_SUFF "_AUTO_FAN_PIN is not a PWM pin. Set EXTRUDER_AUTO_FAN_SPEED to 255."
1702 1702
   #if HAS_AUTO_FAN_0
1703
-    static_assert(GET_TIMER(E0_AUTO_FAN_PIN), "E0" AF_ERR_SUFF);
1703
+    static_assert(PWM_PIN(E0_AUTO_FAN_PIN), "E0" AF_ERR_SUFF);
1704 1704
   #elif HAS_AUTO_FAN_1
1705
-    static_assert(GET_TIMER(E1_AUTO_FAN_PIN), "E1" AF_ERR_SUFF);
1705
+    static_assert(PWM_PIN(E1_AUTO_FAN_PIN), "E1" AF_ERR_SUFF);
1706 1706
   #elif HAS_AUTO_FAN_2
1707
-    static_assert(GET_TIMER(E2_AUTO_FAN_PIN), "E2" AF_ERR_SUFF);
1707
+    static_assert(PWM_PIN(E2_AUTO_FAN_PIN), "E2" AF_ERR_SUFF);
1708 1708
   #elif HAS_AUTO_FAN_3
1709
-    static_assert(GET_TIMER(E3_AUTO_FAN_PIN), "E3" AF_ERR_SUFF);
1709
+    static_assert(PWM_PIN(E3_AUTO_FAN_PIN), "E3" AF_ERR_SUFF);
1710 1710
   #endif
1711 1711
 #endif
1712 1712
 

+ 1
- 1
Marlin/src/lcd/menu/menu_configuration.cpp 查看文件

@@ -299,7 +299,7 @@ void menu_configuration() {
299 299
   // Set Case light on/off/brightness
300 300
   //
301 301
   #if ENABLED(MENU_ITEM_CASE_LIGHT)
302
-    if (USEABLE_HARDWARE_PWM(CASE_LIGHT_PIN))
302
+    if (PWM_PIN(CASE_LIGHT_PIN))
303 303
       MENU_ITEM(submenu, MSG_CASE_LIGHT, menu_case_light);
304 304
     else
305 305
       MENU_ITEM_EDIT_CALLBACK(bool, MSG_CASE_LIGHT, (bool*)&case_light_on, update_case_light);

+ 1
- 1
Marlin/src/module/endstops.cpp 查看文件

@@ -886,7 +886,7 @@ void Endstops::update() {
886 886
         ES_REPORT_CHANGE(Z3_MAX);
887 887
       #endif
888 888
       SERIAL_ECHOLNPGM("\n");
889
-      analogWrite(LED_PIN, local_LED_status);
889
+      ANALOG_WRITE(LED_PIN, local_LED_status);
890 890
       local_LED_status ^= 255;
891 891
       old_live_state_local = live_state_local;
892 892
     }

+ 5
- 5
Marlin/src/module/planner.cpp 查看文件

@@ -1290,13 +1290,13 @@ void Planner::check_axes_activity() {
1290 1290
     #else
1291 1291
 
1292 1292
       #if HAS_FAN0
1293
-        analogWrite(FAN_PIN, CALC_FAN_SPEED(0));
1293
+        ANALOG_WRITE(FAN_PIN, CALC_FAN_SPEED(0));
1294 1294
       #endif
1295 1295
       #if HAS_FAN1
1296
-        analogWrite(FAN1_PIN, CALC_FAN_SPEED(1));
1296
+        ANALOG_WRITE(FAN1_PIN, CALC_FAN_SPEED(1));
1297 1297
       #endif
1298 1298
       #if HAS_FAN2
1299
-        analogWrite(FAN2_PIN, CALC_FAN_SPEED(2));
1299
+        ANALOG_WRITE(FAN2_PIN, CALC_FAN_SPEED(2));
1300 1300
       #endif
1301 1301
     #endif
1302 1302
 
@@ -1308,10 +1308,10 @@ void Planner::check_axes_activity() {
1308 1308
 
1309 1309
   #if ENABLED(BARICUDA)
1310 1310
     #if HAS_HEATER_1
1311
-      analogWrite(HEATER_1_PIN, tail_valve_pressure);
1311
+      ANALOG_WRITE(HEATER_1_PIN, tail_valve_pressure);
1312 1312
     #endif
1313 1313
     #if HAS_HEATER_2
1314
-      analogWrite(HEATER_2_PIN, tail_e_to_p_pressure);
1314
+      ANALOG_WRITE(HEATER_2_PIN, tail_e_to_p_pressure);
1315 1315
     #endif
1316 1316
   #endif
1317 1317
 }

+ 8
- 8
Marlin/src/module/stepper.cpp 查看文件

@@ -2510,7 +2510,7 @@ void Stepper::report_positions() {
2510 2510
         if (WITHIN(driver, 0, COUNT(motor_current_setting) - 1))
2511 2511
           motor_current_setting[driver] = current; // update motor_current_setting
2512 2512
 
2513
-        #define _WRITE_CURRENT_PWM(P) analogWrite(MOTOR_CURRENT_PWM_## P ##_PIN, 255L * current / (MOTOR_CURRENT_PWM_RANGE))
2513
+        #define _WRITE_CURRENT_PWM(P) ANALOG_WRITE(MOTOR_CURRENT_PWM_## P ##_PIN, 255L * current / (MOTOR_CURRENT_PWM_RANGE))
2514 2514
         switch (driver) {
2515 2515
           case 0:
2516 2516
             #if PIN_EXISTS(MOTOR_CURRENT_PWM_X)
@@ -2560,25 +2560,25 @@ void Stepper::report_positions() {
2560 2560
       #elif HAS_MOTOR_CURRENT_PWM
2561 2561
 
2562 2562
         #if PIN_EXISTS(MOTOR_CURRENT_PWM_X)
2563
-          SET_OUTPUT(MOTOR_CURRENT_PWM_X_PIN);
2563
+          SET_PWM(MOTOR_CURRENT_PWM_X_PIN);
2564 2564
         #endif
2565 2565
         #if PIN_EXISTS(MOTOR_CURRENT_PWM_Y)
2566
-          SET_OUTPUT(MOTOR_CURRENT_PWM_Y_PIN);
2566
+          SET_PWM(MOTOR_CURRENT_PWM_Y_PIN);
2567 2567
         #endif
2568 2568
         #if PIN_EXISTS(MOTOR_CURRENT_PWM_XY)
2569
-          SET_OUTPUT(MOTOR_CURRENT_PWM_XY_PIN);
2569
+          SET_PWM(MOTOR_CURRENT_PWM_XY_PIN);
2570 2570
         #endif
2571 2571
         #if PIN_EXISTS(MOTOR_CURRENT_PWM_Z)
2572
-          SET_OUTPUT(MOTOR_CURRENT_PWM_Z_PIN);
2572
+          SET_PWM(MOTOR_CURRENT_PWM_Z_PIN);
2573 2573
         #endif
2574 2574
         #if PIN_EXISTS(MOTOR_CURRENT_PWM_E)
2575
-          SET_OUTPUT(MOTOR_CURRENT_PWM_E_PIN);
2575
+          SET_PWM(MOTOR_CURRENT_PWM_E_PIN);
2576 2576
         #endif
2577 2577
         #if PIN_EXISTS(MOTOR_CURRENT_PWM_E0)
2578
-          SET_OUTPUT(MOTOR_CURRENT_PWM_E0_PIN);
2578
+          SET_PWM(MOTOR_CURRENT_PWM_E0_PIN);
2579 2579
         #endif
2580 2580
         #if PIN_EXISTS(MOTOR_CURRENT_PWM_E1)
2581
-          SET_OUTPUT(MOTOR_CURRENT_PWM_E1_PIN);
2581
+          SET_PWM(MOTOR_CURRENT_PWM_E1_PIN);
2582 2582
         #endif
2583 2583
 
2584 2584
         refresh_motor_power();

+ 58
- 80
Marlin/src/module/temperature.cpp 查看文件

@@ -610,6 +610,28 @@ int Temperature::getHeaterPower(const int heater) {
610 610
 
611 611
 #if HAS_AUTO_FAN
612 612
 
613
+  #define AUTO_1_IS_0 (E1_AUTO_FAN_PIN == E0_AUTO_FAN_PIN)
614
+  #define AUTO_2_IS_0 (E2_AUTO_FAN_PIN == E0_AUTO_FAN_PIN)
615
+  #define AUTO_2_IS_1 (E2_AUTO_FAN_PIN == E1_AUTO_FAN_PIN)
616
+  #define AUTO_3_IS_0 (E3_AUTO_FAN_PIN == E0_AUTO_FAN_PIN)
617
+  #define AUTO_3_IS_1 (E3_AUTO_FAN_PIN == E1_AUTO_FAN_PIN)
618
+  #define AUTO_3_IS_2 (E3_AUTO_FAN_PIN == E2_AUTO_FAN_PIN)
619
+  #define AUTO_4_IS_0 (E4_AUTO_FAN_PIN == E0_AUTO_FAN_PIN)
620
+  #define AUTO_4_IS_1 (E4_AUTO_FAN_PIN == E1_AUTO_FAN_PIN)
621
+  #define AUTO_4_IS_2 (E4_AUTO_FAN_PIN == E2_AUTO_FAN_PIN)
622
+  #define AUTO_4_IS_3 (E4_AUTO_FAN_PIN == E3_AUTO_FAN_PIN)
623
+  #define AUTO_5_IS_0 (E5_AUTO_FAN_PIN == E0_AUTO_FAN_PIN)
624
+  #define AUTO_5_IS_1 (E5_AUTO_FAN_PIN == E1_AUTO_FAN_PIN)
625
+  #define AUTO_5_IS_2 (E5_AUTO_FAN_PIN == E2_AUTO_FAN_PIN)
626
+  #define AUTO_5_IS_3 (E5_AUTO_FAN_PIN == E3_AUTO_FAN_PIN)
627
+  #define AUTO_5_IS_4 (E5_AUTO_FAN_PIN == E4_AUTO_FAN_PIN)
628
+  #define AUTO_CHAMBER_IS_0 (CHAMBER_AUTO_FAN_PIN == E0_AUTO_FAN_PIN)
629
+  #define AUTO_CHAMBER_IS_1 (CHAMBER_AUTO_FAN_PIN == E1_AUTO_FAN_PIN)
630
+  #define AUTO_CHAMBER_IS_2 (CHAMBER_AUTO_FAN_PIN == E2_AUTO_FAN_PIN)
631
+  #define AUTO_CHAMBER_IS_3 (CHAMBER_AUTO_FAN_PIN == E3_AUTO_FAN_PIN)
632
+  #define AUTO_CHAMBER_IS_4 (CHAMBER_AUTO_FAN_PIN == E4_AUTO_FAN_PIN)
633
+  #define AUTO_CHAMBER_IS_5 (CHAMBER_AUTO_FAN_PIN == E5_AUTO_FAN_PIN)
634
+
613 635
   void Temperature::checkExtruderAutoFans() {
614 636
     static const uint8_t fanBit[] PROGMEM = {
615 637
                     0,
@@ -633,11 +655,11 @@ int Temperature::getHeaterPower(const int heater) {
633 655
         SBI(fanState, pgm_read_byte(&fanBit[6]));
634 656
     #endif
635 657
 
636
-    #define _UPDATE_AUTO_FAN(P,D,A) do{           \
637
-      if (USEABLE_HARDWARE_PWM(P##_AUTO_FAN_PIN)) \
638
-        analogWrite(P##_AUTO_FAN_PIN, A);         \
639
-      else                                        \
640
-        WRITE(P##_AUTO_FAN_PIN, D);               \
658
+    #define _UPDATE_AUTO_FAN(P,D,A) do{                               \
659
+      if (PWM_PIN(P##_AUTO_FAN_PIN) && EXTRUDER_AUTO_FAN_SPEED < 255) \
660
+        ANALOG_WRITE(P##_AUTO_FAN_PIN, A);                            \
661
+      else                                                            \
662
+        WRITE(P##_AUTO_FAN_PIN, D);                                   \
641 663
     }while(0)
642 664
 
643 665
     uint8_t fanDone = 0;
@@ -1280,6 +1302,25 @@ void Temperature::updateTemperaturesFromRawValues() {
1280 1302
   SPIclass<MAX6675_DO_PIN, MOSI_PIN, MAX6675_SCK_PIN> max6675_spi;
1281 1303
 #endif
1282 1304
 
1305
+// Init fans according to whether they're native PWM or Software PWM
1306
+#define _INIT_SOFT_FAN(P) OUT_WRITE(P, FAN_INVERTING ? LOW : HIGH)
1307
+#if ENABLED(FAN_SOFT_PWM)
1308
+  #define _INIT_FAN_PIN(P) _INIT_SOFT_FAN(P)
1309
+#else
1310
+  #define _INIT_FAN_PIN(P) do{ if (PWM_PIN(P)) SET_PWM(P); else _INIT_SOFT_FAN(P); }while(0)
1311
+#endif
1312
+#if ENABLED(FAST_PWM_FAN)
1313
+  #define SET_FAST_PWM_FREQ(P) set_pwm_frequency(P, FAST_PWM_FAN_FREQUENCY)
1314
+#else
1315
+  #define SET_FAST_PWM_FREQ(P) NOOP
1316
+#endif
1317
+#define INIT_FAN_PIN(P) do{ _INIT_FAN_PIN(P); SET_FAST_PWM_FREQ(P); }while(0)
1318
+#if EXTRUDER_AUTO_FAN_SPEED != 255
1319
+  #define INIT_AUTO_FAN_PIN(P) do{ if (P == FAN1_PIN || P == FAN2_PIN) { SET_PWM(P); SET_FAST_PWM_FREQ(FAST_PWM_FAN_FREQUENCY); } else SET_OUTPUT(P); }while(0)
1320
+#else
1321
+  #define INIT_AUTO_FAN_PIN(P) SET_OUTPUT(P)
1322
+#endif
1323
+
1283 1324
 /**
1284 1325
  * Initialize the temperature manager
1285 1326
  * The manager is implemented by periodic calls to manage_heater()
@@ -1329,32 +1370,18 @@ void Temperature::init() {
1329 1370
   #if HAS_HEATED_CHAMBER
1330 1371
     OUT_WRITE(HEATER_CHAMBER_PIN, HEATER_CHAMBER_INVERTING);
1331 1372
   #endif
1373
+
1332 1374
   #if HAS_FAN0
1333
-    SET_OUTPUT(FAN_PIN);
1334
-    #if ENABLED(FAST_PWM_FAN)
1335
-      set_pwm_frequency(FAN_PIN, FAST_PWM_FAN_FREQUENCY);
1336
-    #endif
1375
+    INIT_FAN_PIN(FAN_PIN);
1337 1376
   #endif
1338
-
1339 1377
   #if HAS_FAN1
1340
-    SET_OUTPUT(FAN1_PIN);
1341
-    #if ENABLED(FAST_PWM_FAN)
1342
-      set_pwm_frequency(FAN1_PIN, FAST_PWM_FAN_FREQUENCY);
1343
-    #endif
1378
+    INIT_FAN_PIN(FAN1_PIN);
1344 1379
   #endif
1345
-
1346 1380
   #if HAS_FAN2
1347
-    SET_OUTPUT(FAN2_PIN);
1348
-    #if ENABLED(FAST_PWM_FAN)
1349
-      set_pwm_frequency(FAN2_PIN, FAST_PWM_FAN_FREQUENCY);
1350
-    #endif
1381
+    INIT_FAN_PIN(FAN2_PIN);
1351 1382
   #endif
1352
-
1353 1383
   #if ENABLED(USE_CONTROLLER_FAN)
1354
-    SET_OUTPUT(CONTROLLER_FAN_PIN);
1355
-    #if ENABLED(FAST_PWM_FAN)
1356
-      set_pwm_frequency(CONTROLLER_FAN_PIN, FAST_PWM_FAN_FREQUENCY);
1357
-    #endif
1384
+    INIT_FAN_PIN(CONTROLLER_FAN_PIN);
1358 1385
   #endif
1359 1386
 
1360 1387
   #if MAX6675_SEPARATE_SPI
@@ -1408,74 +1435,25 @@ void Temperature::init() {
1408 1435
   ENABLE_TEMPERATURE_INTERRUPT();
1409 1436
 
1410 1437
   #if HAS_AUTO_FAN_0
1411
-    #if E0_AUTO_FAN_PIN == FAN1_PIN
1412
-      SET_OUTPUT(E0_AUTO_FAN_PIN);
1413
-      #if ENABLED(FAST_PWM_FAN)
1414
-        set_pwm_frequency(E0_AUTO_FAN_PIN, FAST_PWM_FAN_FREQUENCY);
1415
-      #endif
1416
-    #else
1417
-      SET_OUTPUT(E0_AUTO_FAN_PIN);
1418
-    #endif
1438
+    INIT_AUTO_FAN_PIN(E0_AUTO_FAN_PIN);
1419 1439
   #endif
1420 1440
   #if HAS_AUTO_FAN_1 && !AUTO_1_IS_0
1421
-    #if E1_AUTO_FAN_PIN == FAN1_PIN
1422
-      SET_OUTPUT(E1_AUTO_FAN_PIN);
1423
-      #if ENABLED(FAST_PWM_FAN)
1424
-        set_pwm_frequency(E1_AUTO_FAN_PIN, FAST_PWM_FAN_FREQUENCY);
1425
-      #endif
1426
-    #else
1427
-      SET_OUTPUT(E1_AUTO_FAN_PIN);
1428
-    #endif
1441
+    INIT_AUTO_FAN_PIN(E1_AUTO_FAN_PIN);
1429 1442
   #endif
1430 1443
   #if HAS_AUTO_FAN_2 && !(AUTO_2_IS_0 || AUTO_2_IS_1)
1431
-    #if E2_AUTO_FAN_PIN == FAN1_PIN
1432
-      SET_OUTPUT(E2_AUTO_FAN_PIN);
1433
-      #if ENABLED(FAST_PWM_FAN)
1434
-        set_pwm_frequency(E2_AUTO_FAN_PIN, FAST_PWM_FAN_FREQUENCY);
1435
-      #endif
1436
-    #else
1437
-      SET_OUTPUT(E2_AUTO_FAN_PIN);
1438
-    #endif
1444
+    INIT_AUTO_FAN_PIN(E2_AUTO_FAN_PIN);
1439 1445
   #endif
1440 1446
   #if HAS_AUTO_FAN_3 && !(AUTO_3_IS_0 || AUTO_3_IS_1 || AUTO_3_IS_2)
1441
-    #if E3_AUTO_FAN_PIN == FAN1_PIN
1442
-      SET_OUTPUT(E3_AUTO_FAN_PIN);
1443
-      #if ENABLED(FAST_PWM_FAN)
1444
-        set_pwm_frequency(E3_AUTO_FAN_PIN, FAST_PWM_FAN_FREQUENCY);
1445
-      #endif
1446
-    #else
1447
-      SET_OUTPUT(E3_AUTO_FAN_PIN);
1448
-    #endif
1447
+    INIT_AUTO_FAN_PIN(E3_AUTO_FAN_PIN);
1449 1448
   #endif
1450 1449
   #if HAS_AUTO_FAN_4 && !(AUTO_4_IS_0 || AUTO_4_IS_1 || AUTO_4_IS_2 || AUTO_4_IS_3)
1451
-    #if E4_AUTO_FAN_PIN == FAN1_PIN
1452
-      SET_OUTPUT(E4_AUTO_FAN_PIN);
1453
-      #if ENABLED(FAST_PWM_FAN)
1454
-        set_pwm_frequency(E4_AUTO_FAN_PIN, FAST_PWM_FAN_FREQUENCY);
1455
-      #endif
1456
-    #else
1457
-      SET_OUTPUT(E4_AUTO_FAN_PIN);
1458
-    #endif
1450
+    INIT_AUTO_FAN_PIN(E4_AUTO_FAN_PIN);
1459 1451
   #endif
1460 1452
   #if HAS_AUTO_FAN_5 && !(AUTO_5_IS_0 || AUTO_5_IS_1 || AUTO_5_IS_2 || AUTO_5_IS_3 || AUTO_5_IS_4)
1461
-    #if E5_AUTO_FAN_PIN == FAN1_PIN
1462
-      SET_OUTPUT(E5_AUTO_FAN_PIN);
1463
-      #if ENABLED(FAST_PWM_FAN)
1464
-        set_pwm_frequency(E5_AUTO_FAN_PIN, FAST_PWM_FAN_FREQUENCY);
1465
-      #endif
1466
-    #else
1467
-      SET_OUTPUT(E5_AUTO_FAN_PIN);
1468
-    #endif
1453
+    INIT_AUTO_FAN_PIN(E5_AUTO_FAN_PIN);
1469 1454
   #endif
1470 1455
   #if HAS_AUTO_CHAMBER_FAN && !(AUTO_CHAMBER_IS_0 || AUTO_CHAMBER_IS_1 || AUTO_CHAMBER_IS_2 || AUTO_CHAMBER_IS_3 || AUTO_CHAMBER_IS_4 || AUTO_CHAMBER_IS_5)
1471
-    #if CHAMBER_AUTO_FAN_PIN == FAN1_PIN
1472
-      SET_OUTPUT(CHAMBER_AUTO_FAN_PIN);
1473
-      #if ENABLED(FAST_PWM_FAN)
1474
-        set_pwm_frequency(CHAMBER_AUTO_FAN_PIN, FAST_PWM_FAN_FREQUENCY);
1475
-      #endif
1476
-    #else
1477
-      SET_OUTPUT(CHAMBER_AUTO_FAN_PIN);
1478
-    #endif
1456
+    INIT_AUTO_FAN_PIN(CHAMBER_AUTO_FAN_PIN);
1479 1457
   #endif
1480 1458
 
1481 1459
   // Wait for temperature measurement to settle

正在加载...
取消
保存