Преглед на файлове

Distinguish between analog/digital auto fans (#13298)

Scott Lahteine преди 5 години
родител
ревизия
2212da453a
No account linked to committer's email address

+ 6
- 3
Marlin/src/HAL/HAL_AVR/fastio_1280.h Целия файл

@@ -24,9 +24,9 @@
24 24
 /**
25 25
  * Pin mapping for the 1280 and 2560
26 26
  *
27
- *   Hardware Pin  : 02 03 06 07 01 05 15 16 17 18 23 24 25 26 64 63 13 12 46 45 44 43 78 77 76 75 74 73 72 71 60 59 58 57 56 55 54 53 50 70 52 51 42 41 40 39 38 37 36 35 22 21 20 19 97 96 95 94 93 92 91 90 89 88 87 86 85 84 83 82 04 08 09 10 11 14 27 28 29 30 31 32 33 34 47 48 49 61 62 65 66 67 68 69 79 80 81 98 99 100
28
- *   Port          : E0 E1 E4 E5 G5 E3 H3 H4 H5 H6 B4 B5 B6 B7 J1 J0 H1 H0 D3 D2 D1 D0 A0 A1 A2 A3 A4 A5 A6 A7 C7 C6 C5 C4 C3 C2 C1 C0 D7 G2 G1 G0 L7 L6 L5 L4 L3 L2 L1 L0 B3 B2 B1 B0 F0 F1 F2 F3 F4 F5 F6 F7 K0 K1 K2 K3 K4 K5 K6 K7 E2 E6 E7 xx xx H2 H7 G3 G4 xx xx xx xx xx D4 D5 D6 xx xx J2 J3 J4 J5 J6 J7 xx xx xx xx xx
29
- *   Logical Pin   : 00 01 02 03 04 05 06 07 08 09 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 xx xx xx xx xx xx xx xx xx xx xx xx xx xx xx xx xx xx xx xx xx xx xx xx xx xx xx xx xx xx
27
+ *   Hardware Pin  : 02 03 06 07 01 05 15 16 17 18 23 24 25 26 64 63 13 12 46 45 44 43 78 77 76 75 74 73 72 71 60 59 58 57 56 55 54 53 50 70 52 51 42 41 40 39 38 37 36 35 22 21 20 19 97 96 95 94 93 92 91 90 89 88 87 86 85 84 83 82 | 04 08 09 10 11 14 27 28 29 30 31 32 33 34 47 48 49 61 62 65 66 67 68 69 79 80 81 98 99 100
28
+ *   Port          : E0 E1 E4 E5 G5 E3 H3 H4 H5 H6 B4 B5 B6 B7 J1 J0 H1 H0 D3 D2 D1 D0 A0 A1 A2 A3 A4 A5 A6 A7 C7 C6 C5 C4 C3 C2 C1 C0 D7 G2 G1 G0 L7 L6 L5 L4 L3 L2 L1 L0 B3 B2 B1 B0 F0 F1 F2 F3 F4 F5 F6 F7 K0 K1 K2 K3 K4 K5 K6 K7 | E2 E6 E7 xx xx H2 H7 G3 G4 xx xx xx xx xx D4 D5 D6 xx xx J2 J3 J4 J5 J6 J7 xx xx xx xx xx
29
+ *   Logical Pin   : 00 01 02 03 04 05 06 07 08 09 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 | 78 79 80 xx xx 84 85 71 70 xx xx xx xx xx 81 82 83 xx xx 72 72 75 76 77 74 xx xx xx xx xx
30 30
  */
31 31
 
32 32
 #include "fastio_AVR.h"
@@ -487,6 +487,9 @@
487 487
 #define DIO69_DDR   DDRK
488 488
 #define DIO69_PWM   NULL
489 489
 
490
+//#define FASTIO_EXT_START 70
491
+//#define FASTIO_EXT_END   85
492
+
490 493
 #define DIO70_PIN   PING4
491 494
 #define DIO70_RPORT PING
492 495
 #define DIO70_WPORT PORTG

+ 238
- 0
Marlin/src/HAL/HAL_AVR/fastio_AVR.cpp Целия файл

@@ -0,0 +1,238 @@
1
+/**
2
+ * Marlin 3D Printer Firmware
3
+ * Copyright (C) 2019 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
4
+ *
5
+ * Based on Sprinter and grbl.
6
+ * Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
7
+ *
8
+ * This program is free software: you can redistribute it and/or modify
9
+ * it under the terms of the GNU General Public License as published by
10
+ * the Free Software Foundation, either version 3 of the License, or
11
+ * (at your option) any later version.
12
+ *
13
+ * This program is distributed in the hope that it will be useful,
14
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
15
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
16
+ * GNU General Public License for more details.
17
+ *
18
+ * You should have received a copy of the GNU General Public License
19
+ * along with this program.  If not, see <http://www.gnu.org/licenses/>.
20
+ *
21
+ */
22
+
23
+/**
24
+ * Fast I/O for extended pins
25
+ */
26
+
27
+#ifdef __AVR__
28
+
29
+#include "fastio_AVR.h"
30
+
31
+#ifdef FASTIO_EXT_START
32
+
33
+#include <Arduino.h>
34
+
35
+#define _IS_EXT(P) WITHIN(P, FASTIO_EXT_START, FASTIO_EXT_END)
36
+
37
+void extDigitalWrite(const int8_t pin, const uint8_t state) {
38
+  #define _WCASE(N) case N: WRITE(N, state); break
39
+  switch (pin) {
40
+    default: digitalWrite(pin, state);
41
+    #if _IS_EXT(70)
42
+      _WCASE(70);
43
+    #endif
44
+    #if _IS_EXT(71)
45
+      _WCASE(71);
46
+    #endif
47
+    #if _IS_EXT(72)
48
+      _WCASE(72);
49
+    #endif
50
+    #if _IS_EXT(73)
51
+      _WCASE(73);
52
+    #endif
53
+    #if _IS_EXT(74)
54
+      _WCASE(74);
55
+    #endif
56
+    #if _IS_EXT(75)
57
+      _WCASE(75);
58
+    #endif
59
+    #if _IS_EXT(76)
60
+      _WCASE(76);
61
+    #endif
62
+    #if _IS_EXT(77)
63
+      _WCASE(77);
64
+    #endif
65
+    #if _IS_EXT(78)
66
+      _WCASE(78);
67
+    #endif
68
+    #if _IS_EXT(79)
69
+      _WCASE(79);
70
+    #endif
71
+    #if _IS_EXT(80)
72
+      _WCASE(80);
73
+    #endif
74
+    #if _IS_EXT(81)
75
+      _WCASE(81);
76
+    #endif
77
+    #if _IS_EXT(82)
78
+      _WCASE(82);
79
+    #endif
80
+    #if _IS_EXT(83)
81
+      _WCASE(83);
82
+    #endif
83
+    #if _IS_EXT(84)
84
+      _WCASE(84);
85
+    #endif
86
+    #if _IS_EXT(85)
87
+      _WCASE(85);
88
+    #endif
89
+    #if _IS_EXT(86)
90
+      _WCASE(86);
91
+    #endif
92
+    #if _IS_EXT(87)
93
+      _WCASE(87);
94
+    #endif
95
+    #if _IS_EXT(88)
96
+      _WCASE(88);
97
+    #endif
98
+    #if _IS_EXT(89)
99
+      _WCASE(89);
100
+    #endif
101
+    #if _IS_EXT(90)
102
+      _WCASE(90);
103
+    #endif
104
+    #if _IS_EXT(91)
105
+      _WCASE(91);
106
+    #endif
107
+    #if _IS_EXT(92)
108
+      _WCASE(92);
109
+    #endif
110
+    #if _IS_EXT(93)
111
+      _WCASE(93);
112
+    #endif
113
+    #if _IS_EXT(94)
114
+      _WCASE(94);
115
+    #endif
116
+    #if _IS_EXT(95)
117
+      _WCASE(95);
118
+    #endif
119
+    #if _IS_EXT(96)
120
+      _WCASE(96);
121
+    #endif
122
+    #if _IS_EXT(97)
123
+      _WCASE(97);
124
+    #endif
125
+    #if _IS_EXT(98)
126
+      _WCASE(98);
127
+    #endif
128
+    #if _IS_EXT(99)
129
+      _WCASE(99);
130
+    #endif
131
+    #if _IS_EXT(100)
132
+      _WCASE(100);
133
+    #endif
134
+  }
135
+}
136
+
137
+uint8_t extDigitalRead(const int8_t pin) {
138
+  #define _RCASE(N) case N: return READ(N)
139
+  switch (pin) {
140
+    default: return digitalRead(pin);
141
+    #if _IS_EXT(70)
142
+      _RCASE(70);
143
+    #endif
144
+    #if _IS_EXT(71)
145
+      _RCASE(71);
146
+    #endif
147
+    #if _IS_EXT(72)
148
+      _RCASE(72);
149
+    #endif
150
+    #if _IS_EXT(73)
151
+      _RCASE(73);
152
+    #endif
153
+    #if _IS_EXT(74)
154
+      _RCASE(74);
155
+    #endif
156
+    #if _IS_EXT(75)
157
+      _RCASE(75);
158
+    #endif
159
+    #if _IS_EXT(76)
160
+      _RCASE(76);
161
+    #endif
162
+    #if _IS_EXT(77)
163
+      _RCASE(77);
164
+    #endif
165
+    #if _IS_EXT(78)
166
+      _RCASE(78);
167
+    #endif
168
+    #if _IS_EXT(79)
169
+      _RCASE(79);
170
+    #endif
171
+    #if _IS_EXT(80)
172
+      _RCASE(80);
173
+    #endif
174
+    #if _IS_EXT(81)
175
+      _RCASE(81);
176
+    #endif
177
+    #if _IS_EXT(82)
178
+      _RCASE(82);
179
+    #endif
180
+    #if _IS_EXT(83)
181
+      _RCASE(83);
182
+    #endif
183
+    #if _IS_EXT(84)
184
+      _RCASE(84);
185
+    #endif
186
+    #if _IS_EXT(85)
187
+      _RCASE(85);
188
+    #endif
189
+    #if _IS_EXT(86)
190
+      _RCASE(86);
191
+    #endif
192
+    #if _IS_EXT(87)
193
+      _RCASE(87);
194
+    #endif
195
+    #if _IS_EXT(88)
196
+      _RCASE(88);
197
+    #endif
198
+    #if _IS_EXT(89)
199
+      _RCASE(89);
200
+    #endif
201
+    #if _IS_EXT(90)
202
+      _RCASE(90);
203
+    #endif
204
+    #if _IS_EXT(91)
205
+      _RCASE(91);
206
+    #endif
207
+    #if _IS_EXT(92)
208
+      _RCASE(92);
209
+    #endif
210
+    #if _IS_EXT(93)
211
+      _RCASE(93);
212
+    #endif
213
+    #if _IS_EXT(94)
214
+      _RCASE(94);
215
+    #endif
216
+    #if _IS_EXT(95)
217
+      _RCASE(95);
218
+    #endif
219
+    #if _IS_EXT(96)
220
+      _RCASE(96);
221
+    #endif
222
+    #if _IS_EXT(97)
223
+      _RCASE(97);
224
+    #endif
225
+    #if _IS_EXT(98)
226
+      _RCASE(98);
227
+    #endif
228
+    #if _IS_EXT(99)
229
+      _RCASE(99);
230
+    #endif
231
+    #if _IS_EXT(100)
232
+      _RCASE(100);
233
+    #endif
234
+  }
235
+}
236
+
237
+#endif // FASTIO_EXT_START
238
+#endif // __AVR__

+ 9
- 0
Marlin/src/HAL/HAL_AVR/fastio_AVR.h Целия файл

@@ -85,6 +85,15 @@
85 85
 #define _GET_OUTPUT(IO)       TEST(DIO ## IO ## _DDR, DIO ## IO ## _PIN)
86 86
 #define _GET_TIMER(IO)        DIO ## IO ## _PWM
87 87
 
88
+// digitalRead/Write wrappers
89
+#ifdef FASTIO_EXT_START
90
+  void extDigitalWrite(const int8_t pin, const uint8_t state);
91
+  uint8_t extDigitalRead(const int8_t pin);
92
+#else
93
+  #define extDigitalWrite(IO,V) digitalWrite(IO,V)
94
+  #define extDigitalRead(IO)    digitalRead(IO)
95
+#endif
96
+
88 97
 #define READ(IO)              _READ(IO)
89 98
 #define WRITE(IO,V)           _WRITE(IO,V)
90 99
 #define TOGGLE(IO)            _TOGGLE(IO)

+ 2
- 2
Marlin/src/HAL/HAL_AVR/pinsDebug_Teensyduino.h Целия файл

@@ -105,7 +105,7 @@ const uint8_t PROGMEM digital_pin_to_port_PGM[] = {
105 105
 
106 106
 // digitalPinToBitMask(pin) is OK
107 107
 
108
-#define digitalRead_mod(p)  digitalRead(p)   // Teensyduino's version of digitalRead doesn't
109
-                                             // disable the PWMs so we can use it as is
108
+#define digitalRead_mod(p)  extDigitalRead(p)   // Teensyduino's version of digitalRead doesn't
109
+                                                // disable the PWMs so we can use it as is
110 110
 
111 111
 // portModeRegister(pin) is OK

+ 2
- 2
Marlin/src/HAL/HAL_AVR/servo_AVR.cpp Целия файл

@@ -73,14 +73,14 @@ static inline void handle_interrupts(timer16_Sequence_t timer, volatile uint16_t
73 73
     *TCNTn = 0; // channel set to -1 indicated that refresh interval completed so reset the timer
74 74
   else {
75 75
     if (SERVO_INDEX(timer, Channel[timer]) < ServoCount && SERVO(timer, Channel[timer]).Pin.isActive)
76
-      digitalWrite(SERVO(timer, Channel[timer]).Pin.nbr, LOW); // pulse this channel low if activated
76
+      extDigitalWrite(SERVO(timer, Channel[timer]).Pin.nbr, LOW); // pulse this channel low if activated
77 77
   }
78 78
 
79 79
   Channel[timer]++;    // increment to the next channel
80 80
   if (SERVO_INDEX(timer, Channel[timer]) < ServoCount && Channel[timer] < SERVOS_PER_TIMER) {
81 81
     *OCRnA = *TCNTn + SERVO(timer, Channel[timer]).ticks;
82 82
     if (SERVO(timer, Channel[timer]).Pin.isActive)    // check if activated
83
-      digitalWrite(SERVO(timer, Channel[timer]).Pin.nbr, HIGH); // it's an active channel so pulse it high
83
+      extDigitalWrite(SERVO(timer, Channel[timer]).Pin.nbr, HIGH); // it's an active channel so pulse it high
84 84
   }
85 85
   else {
86 86
     // finished all channels so wait for the refresh period to expire before starting over

+ 2
- 2
Marlin/src/HAL/HAL_DUE/Servo_Due.cpp Целия файл

@@ -77,13 +77,13 @@ void Servo_Handler(timer16_Sequence_t timer, Tc *tc, uint8_t channel) {
77 77
   if (Channel[timer] < 0)
78 78
     tc->TC_CHANNEL[channel].TC_CCR |= TC_CCR_SWTRG; // channel set to -1 indicated that refresh interval completed so reset the timer
79 79
   else if (SERVO_INDEX(timer, Channel[timer]) < ServoCount && SERVO(timer, Channel[timer]).Pin.isActive)
80
-    digitalWrite(SERVO(timer, Channel[timer]).Pin.nbr, LOW); // pulse this channel low if activated
80
+    extDigitalWrite(SERVO(timer, Channel[timer]).Pin.nbr, LOW); // pulse this channel low if activated
81 81
 
82 82
   Channel[timer]++;    // increment to the next channel
83 83
   if (SERVO_INDEX(timer, Channel[timer]) < ServoCount && Channel[timer] < SERVOS_PER_TIMER) {
84 84
     tc->TC_CHANNEL[channel].TC_RA = tc->TC_CHANNEL[channel].TC_CV + SERVO(timer,Channel[timer]).ticks;
85 85
     if (SERVO(timer,Channel[timer]).Pin.isActive)    // check if activated
86
-      digitalWrite(SERVO(timer, Channel[timer]).Pin.nbr, HIGH); // its an active channel so pulse it high
86
+      extDigitalWrite(SERVO(timer, Channel[timer]).Pin.nbr, HIGH); // its an active channel so pulse it high
87 87
   }
88 88
   else {
89 89
     // finished all channels so wait for the refresh period to expire before starting over

+ 2
- 2
Marlin/src/HAL/HAL_DUE/Tone.cpp Целия файл

@@ -42,7 +42,7 @@ void tone(const pin_t _pin, const unsigned int frequency, const unsigned long du
42 42
 
43 43
 void noTone(const pin_t _pin) {
44 44
   HAL_timer_disable_interrupt(TONE_TIMER_NUM);
45
-  digitalWrite(_pin, LOW);
45
+  extDigitalWrite(_pin, LOW);
46 46
 }
47 47
 
48 48
 HAL_TONE_TIMER_ISR {
@@ -51,7 +51,7 @@ HAL_TONE_TIMER_ISR {
51 51
 
52 52
   if (toggles) {
53 53
     toggles--;
54
-    digitalWrite(tone_pin, (pin_state ^= 1));
54
+    extDigitalWrite(tone_pin, (pin_state ^= 1));
55 55
   }
56 56
   else noTone(tone_pin);                         // turn off interrupt
57 57
 }

+ 4
- 2
Marlin/src/HAL/HAL_DUE/fastio_Due.h Целия файл

@@ -81,8 +81,6 @@
81 81
 // Toggle a pin
82 82
 #define _TOGGLE(IO) _WRITE(IO, !READ(IO))
83 83
 
84
-#include <pins_arduino.h>
85
-
86 84
 #if MB(PRINTRBOARD_G2)
87 85
 
88 86
   #include "G2_pins.h"
@@ -185,6 +183,10 @@
185 183
 // Shorthand
186 184
 #define OUT_WRITE(IO,V) { SET_OUTPUT(IO); WRITE(IO,V); }
187 185
 
186
+// digitalRead/Write wrappers
187
+#define extDigitalRead(IO)    digitalRead(IO)
188
+#define extDigitalWrite(IO,V) digitalWrite(IO,V)
189
+
188 190
 /**
189 191
  * Ports and functions
190 192
  * Added as necessary or if I feel like it- not a comprehensive list!

+ 1
- 1
Marlin/src/HAL/HAL_DUE/pinsDebug.h Целия файл

@@ -63,7 +63,7 @@
63 63
 
64 64
 #define NUMBER_PINS_TOTAL PINS_COUNT
65 65
 
66
-#define digitalRead_mod(p)  digitalRead(p)  // AVR digitalRead disabled PWM before it read the pin
66
+#define digitalRead_mod(p) extDigitalRead(p)  // AVR digitalRead disabled PWM before it read the pin
67 67
 #define PRINT_PORT(p)
68 68
 #define NAME_FORMAT(p) PSTR("%-##p##s")
69 69
 #define PRINT_ARRAY_NAME(x)  do {sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer);} while (0)

+ 4
- 0
Marlin/src/HAL/HAL_ESP32/fastio_ESP32.h Целия файл

@@ -53,6 +53,10 @@
53 53
 
54 54
 #define OUT_WRITE(IO,V)       do{ _SET_OUTPUT(IO); WRITE(IO,V); }while(0)
55 55
 
56
+// digitalRead/Write wrappers
57
+#define extDigitalRead(IO)    digitalRead(IO)
58
+#define extDigitalWrite(IO,V) digitalWrite(IO,V)
59
+
56 60
 //
57 61
 // Ports and functions
58 62
 //

+ 4
- 0
Marlin/src/HAL/HAL_LINUX/fastio.h Целия файл

@@ -121,3 +121,7 @@
121 121
 
122 122
 // Shorthand
123 123
 #define OUT_WRITE(IO,V)   do{ SET_OUTPUT(IO); WRITE(IO,V); }while(0)
124
+
125
+// digitalRead/Write wrappers
126
+#define extDigitalRead(IO)    digitalRead(IO)
127
+#define extDigitalWrite(IO,V) digitalWrite(IO,V)

+ 4
- 0
Marlin/src/HAL/HAL_LPC1768/fastio.h Целия файл

@@ -121,3 +121,7 @@
121 121
 
122 122
 // Shorthand
123 123
 #define OUT_WRITE(IO,V)   do{ SET_OUTPUT(IO); WRITE(IO,V); }while(0)
124
+
125
+// digitalRead/Write wrappers
126
+#define extDigitalRead(IO)    digitalRead(IO)
127
+#define extDigitalWrite(IO,V) digitalWrite(IO,V)

+ 1
- 1
Marlin/src/HAL/HAL_LPC1768/pinsDebug.h Целия файл

@@ -32,7 +32,7 @@
32 32
 #define pwm_details(pin) pin = pin    // do nothing  // print PWM details
33 33
 #define pwm_status(pin) false //Print a pin's PWM status. Return true if it's currently a PWM pin.
34 34
 #define IS_ANALOG(P) (DIGITAL_PIN_TO_ANALOG_PIN(P) >= 0 ? 1 : 0)
35
-#define digitalRead_mod(p)  digitalRead(p)
35
+#define digitalRead_mod(p) extDigitalRead(p)
36 36
 #define PRINT_PORT(p)
37 37
 #define GET_ARRAY_PIN(p) pin_array[p].pin
38 38
 #define NAME_FORMAT(p) PSTR("%-##p##s")

+ 4
- 0
Marlin/src/HAL/HAL_STM32/fastio_STM32.h Целия файл

@@ -79,3 +79,7 @@ void FastIO_init(); // Must be called before using fast io macros
79 79
 
80 80
 #define PWM_PIN(p) digitalPinHasPWM(p)
81 81
 #define USEABLE_HARDWARE_PWM(p) PWM_PIN(p)
82
+
83
+// digitalRead/Write wrappers
84
+#define extDigitalRead(IO)    digitalRead(IO)
85
+#define extDigitalWrite(IO,V) digitalWrite(IO,V)

+ 4
- 0
Marlin/src/HAL/HAL_STM32F1/fastio_STM32F1.h Целия файл

@@ -50,3 +50,7 @@
50 50
 
51 51
 #define PWM_PIN(p) true
52 52
 #define USEABLE_HARDWARE_PWM(p) PWM_PIN(p)
53
+
54
+// digitalRead/Write wrappers
55
+#define extDigitalRead(IO)    digitalRead(IO)
56
+#define extDigitalWrite(IO,V) digitalWrite(IO,V)

+ 4
- 0
Marlin/src/HAL/HAL_STM32F4/fastio_STM32F4.h Целия файл

@@ -54,6 +54,10 @@
54 54
 #define PWM_PIN(p) true
55 55
 #define USEABLE_HARDWARE_PWM(p) PWM_PIN(p)
56 56
 
57
+// digitalRead/Write wrappers
58
+#define extDigitalRead(IO)    digitalRead(IO)
59
+#define extDigitalWrite(IO,V) digitalWrite(IO,V)
60
+
57 61
 //
58 62
 // Pins Definitions
59 63
 //

+ 10
- 10
Marlin/src/HAL/HAL_STM32F7/TMC2660.cpp Целия файл

@@ -191,9 +191,9 @@ void TMC26XStepper::start() {
191 191
   pinMode(dir_pin, OUTPUT);
192 192
   pinMode(cs_pin, OUTPUT);
193 193
   //SET_OUTPUT(STEPPER_ENABLE_PIN);
194
-  digitalWrite(step_pin, LOW);
195
-  digitalWrite(dir_pin, LOW);
196
-  digitalWrite(cs_pin, HIGH);
194
+  extDigitalWrite(step_pin, LOW);
195
+  extDigitalWrite(dir_pin, LOW);
196
+  extDigitalWrite(cs_pin, HIGH);
197 197
 
198 198
   STEPPER_SPI.begin();
199 199
   STEPPER_SPI.beginTransaction(SPISettings(4000000, MSBFIRST, SPI_MODE3));
@@ -261,10 +261,10 @@ char TMC26XStepper::move(void) {
261 261
       // increment or decrement the step number,
262 262
       // depending on direction:
263 263
       if (this->direction == 1)
264
-        digitalWrite(step_pin, HIGH);
264
+        extDigitalWrite(step_pin, HIGH);
265 265
       else {
266
-        digitalWrite(dir_pin, HIGH);
267
-        digitalWrite(step_pin, HIGH);
266
+        extDigitalWrite(dir_pin, HIGH);
267
+        extDigitalWrite(step_pin, HIGH);
268 268
       }
269 269
       // get the timeStamp of when you stepped:
270 270
       this->last_step_time = time;
@@ -272,8 +272,8 @@ char TMC26XStepper::move(void) {
272 272
       // decrement the steps left:
273 273
       steps_left--;
274 274
       //disable the step & dir pins
275
-      digitalWrite(step_pin, LOW);
276
-      digitalWrite(dir_pin, LOW);
275
+      extDigitalWrite(step_pin, LOW);
276
+      extDigitalWrite(dir_pin, LOW);
277 277
     }
278 278
     return -1;
279 279
   }
@@ -864,7 +864,7 @@ inline void TMC26XStepper::send262(uint32_t datagram) {
864 864
   //}
865 865
 
866 866
   //select the TMC driver
867
-  digitalWrite(cs_pin, LOW);
867
+  extDigitalWrite(cs_pin, LOW);
868 868
 
869 869
   //ensure that only valid bist are set (0-19)
870 870
   //datagram &=REGISTER_BIT_PATTERN;
@@ -893,7 +893,7 @@ inline void TMC26XStepper::send262(uint32_t datagram) {
893 893
   #endif
894 894
 
895 895
   //deselect the TMC chip
896
-  digitalWrite(cs_pin, HIGH);
896
+  extDigitalWrite(cs_pin, HIGH);
897 897
 
898 898
   //restore the previous SPI mode if neccessary
899 899
   //if the mode is not correct set it to mode 3

+ 4
- 0
Marlin/src/HAL/HAL_STM32F7/fastio_STM32F7.h Целия файл

@@ -53,6 +53,10 @@
53 53
 #define PWM_PIN(p) true
54 54
 #define USEABLE_HARDWARE_PWM(p) PWM_PIN(p)
55 55
 
56
+// digitalRead/Write wrappers
57
+#define extDigitalRead(IO)    digitalRead(IO)
58
+#define extDigitalWrite(IO,V) digitalWrite(IO,V)
59
+
56 60
 //
57 61
 // Pins Definitions
58 62
 //

+ 4
- 0
Marlin/src/HAL/HAL_TEENSY31_32/fastio_Teensy.h Целия файл

@@ -85,6 +85,10 @@
85 85
 
86 86
 #define OUT_WRITE(IO,V)       do{ SET_OUTPUT(IO); WRITE(IO,V); }while(0)
87 87
 
88
+// digitalRead/Write wrappers
89
+#define extDigitalRead(IO)    digitalRead(IO)
90
+#define extDigitalWrite(IO,V) digitalWrite(IO,V)
91
+
88 92
 /**
89 93
  * Ports, functions, and pins
90 94
  */

+ 4
- 0
Marlin/src/HAL/HAL_TEENSY35_36/fastio_Teensy.h Целия файл

@@ -84,6 +84,10 @@
84 84
 
85 85
 #define OUT_WRITE(IO,V)       do{ SET_OUTPUT(IO); WRITE(IO,V); }while(0)
86 86
 
87
+// digitalRead/Write wrappers
88
+#define extDigitalRead(IO)    digitalRead(IO)
89
+#define extDigitalWrite(IO,V) digitalWrite(IO,V)
90
+
87 91
 /**
88 92
  * Ports, functions, and pins
89 93
  */

+ 2
- 2
Marlin/src/HAL/shared/HAL_spi_L6470.cpp Целия файл

@@ -83,7 +83,7 @@ uint8_t L6470_transfer(uint8_t data, int16_t ss_pin, const uint8_t chain_positio
83 83
   uint8_t data_out = 0;
84 84
 
85 85
   // first device in chain has data sent last
86
-  digitalWrite(ss_pin, LOW);
86
+  extDigitalWrite(ss_pin, LOW);
87 87
 
88 88
   for (uint8_t i = L6470::chain[0]; (i >= 1) && !spi_abort; i--) {    // stop sending data if spi_abort is active
89 89
     DISABLE_ISRS();  // disable interrupts during SPI transfer (can't allow partial command to chips)
@@ -92,7 +92,7 @@ uint8_t L6470_transfer(uint8_t data, int16_t ss_pin, const uint8_t chain_positio
92 92
     if (i == chain_position) data_out = temp;
93 93
   }
94 94
 
95
-  digitalWrite(ss_pin, HIGH);
95
+  extDigitalWrite(ss_pin, HIGH);
96 96
   return data_out;
97 97
 }
98 98
 

+ 5
- 5
Marlin/src/gcode/config/M43.cpp Целия файл

@@ -77,9 +77,9 @@ inline void toggle_pins() {
77 77
       {
78 78
         pinMode(pin, OUTPUT);
79 79
         for (int16_t j = 0; j < repeat; j++) {
80
-          digitalWrite(pin, 0); safe_delay(wait);
81
-          digitalWrite(pin, 1); safe_delay(wait);
82
-          digitalWrite(pin, 0); safe_delay(wait);
80
+          extDigitalWrite(pin, 0); safe_delay(wait);
81
+          extDigitalWrite(pin, 1); safe_delay(wait);
82
+          extDigitalWrite(pin, 0); safe_delay(wait);
83 83
         }
84 84
       }
85 85
 
@@ -285,7 +285,7 @@ void GcodeSuite::M43() {
285 285
           pin_state[pin - first_pin] = analogRead(DIGITAL_PIN_TO_ANALOG_PIN(pin)); // int16_t pin_state[...]
286 286
         else
287 287
       //*/
288
-          pin_state[i - first_pin] = digitalRead(pin);
288
+          pin_state[i - first_pin] = extDigitalRead(pin);
289 289
     }
290 290
 
291 291
     #if HAS_RESUME_CONTINUE
@@ -307,7 +307,7 @@ void GcodeSuite::M43() {
307 307
               ? analogRead(DIGITAL_PIN_TO_ANALOG_PIN(pin)) : // int16_t val
308 308
               :
309 309
           //*/
310
-            digitalRead(pin);
310
+            extDigitalRead(pin);
311 311
         if (val != pin_state[i - first_pin]) {
312 312
           report_pin_state_extended(pin, ignore_protection, false);
313 313
           pin_state[i - first_pin] = val;

+ 2
- 2
Marlin/src/gcode/control/M226.cpp Целия файл

@@ -43,9 +43,9 @@ void GcodeSuite::M226() {
43 43
         switch (pin_state) {
44 44
           case 1: target = HIGH; break;
45 45
           case 0: target = LOW; break;
46
-          case -1: target = !digitalRead(pin); break;
46
+          case -1: target = !extDigitalRead(pin); break;
47 47
         }
48
-        while (digitalRead(pin) != target) idle();
48
+        while (extDigitalRead(pin) != target) idle();
49 49
       }
50 50
     } // pin_state -1 0 1 && pin > -1
51 51
   } // parser.seen('P')

+ 1
- 1
Marlin/src/gcode/control/M42.cpp Целия файл

@@ -50,7 +50,7 @@ void GcodeSuite::M42() {
50 50
   if (!parser.boolval('I') && pin_is_protected(pin)) return protected_pin_err();
51 51
 
52 52
   pinMode(pin, OUTPUT);
53
-  digitalWrite(pin, pin_status);
53
+  extDigitalWrite(pin, pin_status);
54 54
   analogWrite(pin, pin_status);
55 55
 
56 56
   #if FAN_COUNT > 0

+ 1
- 1
Marlin/src/module/endstops.cpp Целия файл

@@ -453,7 +453,7 @@ void _O2 Endstops::M119() {
453 453
         }
454 454
         SERIAL_ECHOPGM(MSG_FILAMENT_RUNOUT_SENSOR);
455 455
         if (i > 1) { SERIAL_CHAR(' '); SERIAL_CHAR('0' + i); }
456
-        print_es_state(digitalRead(pin) != FIL_RUNOUT_INVERTING);
456
+        print_es_state(extDigitalRead(pin) != FIL_RUNOUT_INVERTING);
457 457
       }
458 458
     #endif
459 459
   #endif

+ 43
- 21
Marlin/src/module/temperature.cpp Целия файл

@@ -632,15 +632,16 @@ int Temperature::getHeaterPower(const int heater) {
632 632
 #if HAS_AUTO_FAN
633 633
 
634 634
   void Temperature::checkExtruderAutoFans() {
635
-    static const pin_t fanPin[] PROGMEM = { E0_AUTO_FAN_PIN, E1_AUTO_FAN_PIN, E2_AUTO_FAN_PIN, E3_AUTO_FAN_PIN, E4_AUTO_FAN_PIN, E5_AUTO_FAN_PIN, CHAMBER_AUTO_FAN_PIN };
636 635
     static const uint8_t fanBit[] PROGMEM = {
637 636
                     0,
638 637
       AUTO_1_IS_0 ? 0 :               1,
639 638
       AUTO_2_IS_0 ? 0 : AUTO_2_IS_1 ? 1 :               2,
640 639
       AUTO_3_IS_0 ? 0 : AUTO_3_IS_1 ? 1 : AUTO_3_IS_2 ? 2 :               3,
641
-      AUTO_4_IS_0 ? 0 : AUTO_4_IS_1 ? 1 : AUTO_4_IS_2 ? 2 : AUTO_4_IS_3 ? 3 :                   4,
642
-      AUTO_5_IS_0 ? 0 : AUTO_5_IS_1 ? 1 : AUTO_5_IS_2 ? 2 : AUTO_5_IS_3 ? 3 : AUTO_5_IS_4 ? 4 : 5,
643
-      AUTO_CHAMBER_IS_0 ? 0 : AUTO_CHAMBER_IS_1 ? 1 : AUTO_CHAMBER_IS_2 ? 2 : AUTO_CHAMBER_IS_3 ? 3 : AUTO_CHAMBER_IS_4 ? 4 : 5
640
+      AUTO_4_IS_0 ? 0 : AUTO_4_IS_1 ? 1 : AUTO_4_IS_2 ? 2 : AUTO_4_IS_3 ? 3 :               4,
641
+      AUTO_5_IS_0 ? 0 : AUTO_5_IS_1 ? 1 : AUTO_5_IS_2 ? 2 : AUTO_5_IS_3 ? 3 : AUTO_5_IS_4 ? 4 : 5
642
+      #if HAS_TEMP_CHAMBER
643
+        , AUTO_CHAMBER_IS_0 ? 0 : AUTO_CHAMBER_IS_1 ? 1 : AUTO_CHAMBER_IS_2 ? 2 : AUTO_CHAMBER_IS_3 ? 3 : AUTO_CHAMBER_IS_4 ? 4 : AUTO_CHAMBER_IS_5 ? 5 : 6
644
+      #endif
644 645
     };
645 646
     uint8_t fanState = 0;
646 647
 
@@ -650,29 +651,50 @@ int Temperature::getHeaterPower(const int heater) {
650 651
 
651 652
     #if HAS_TEMP_CHAMBER
652 653
       if (current_temperature_chamber > EXTRUDER_AUTO_FAN_TEMPERATURE)
653
-        SBI(fanState, pgm_read_byte(&fanBit[5]));
654
+        SBI(fanState, pgm_read_byte(&fanBit[6]));
654 655
     #endif
655 656
 
657
+    #define _UPDATE_AUTO_FAN(P,D,A) do{           \
658
+      if (USEABLE_HARDWARE_PWM(P##_AUTO_FAN_PIN)) \
659
+        analogWrite(P##_AUTO_FAN_PIN, A);         \
660
+      else                                        \
661
+        WRITE(P##_AUTO_FAN_PIN, D);               \
662
+    }while(0)
663
+
656 664
     uint8_t fanDone = 0;
657
-    for (uint8_t f = 0; f < COUNT(fanPin); f++) {
658
-      const pin_t pin =
659
-        #ifdef ARDUINO
660
-          pgm_read_byte(&fanPin[f])
661
-        #else
662
-          fanPin[f]
663
-        #endif
664
-      ;
665
+    for (uint8_t f = 0; f < COUNT(fanBit); f++) {
665 666
       const uint8_t bit = pgm_read_byte(&fanBit[f]);
666
-      if (pin >= 0 && !TEST(fanDone, bit)) {
667
-        uint8_t newFanSpeed = TEST(fanState, bit) ? EXTRUDER_AUTO_FAN_SPEED : 0;
668
-        #if ENABLED(AUTO_POWER_E_FANS)
669
-          autofan_speed[f] = newFanSpeed;
667
+      if (TEST(fanDone, bit)) continue;
668
+      const bool fan_on = TEST(fanState, bit);
669
+      const uint8_t speed = fan_on ? EXTRUDER_AUTO_FAN_SPEED : 0;
670
+      #if ENABLED(AUTO_POWER_E_FANS)
671
+        autofan_speed[f] = speed;
672
+      #endif
673
+      switch (f) {
674
+        #if HAS_AUTO_FAN_0
675
+          case 0: _UPDATE_AUTO_FAN(E0, fan_on, speed); break;
676
+        #endif
677
+        #if HAS_AUTO_FAN_1
678
+          case 1: _UPDATE_AUTO_FAN(E1, fan_on, speed); break;
679
+        #endif
680
+        #if HAS_AUTO_FAN_2
681
+          case 2: _UPDATE_AUTO_FAN(E2, fan_on, speed); break;
682
+        #endif
683
+        #if HAS_AUTO_FAN_3
684
+          case 3: _UPDATE_AUTO_FAN(E3, fan_on, speed); break;
685
+        #endif
686
+        #if HAS_AUTO_FAN_4
687
+          case 4: _UPDATE_AUTO_FAN(E4, fan_on, speed); break;
688
+        #endif
689
+        #if HAS_AUTO_FAN_5
690
+          case 5: _UPDATE_AUTO_FAN(E5, fan_on, speed); break;
691
+        #endif
692
+        #if HAS_AUTO_CHAMBER_FAN
693
+          case 6: _UPDATE_AUTO_FAN(CHAMBER, fan_on, speed); break;
670 694
         #endif
671
-        // this idiom allows both digital and PWM fan outputs (see M42 handling).
672
-        digitalWrite(pin, newFanSpeed);
673
-        analogWrite(pin, newFanSpeed);
674
-        SBI(fanDone, bit);
675 695
       }
696
+      SBI(fanDone, bit);
697
+      UNUSED(fan_on); UNUSED(speed);
676 698
     }
677 699
   }
678 700
 

+ 4
- 4
Marlin/src/sd/Sd2Card.cpp Целия файл

@@ -156,13 +156,13 @@ uint32_t Sd2Card::cardSize() {
156 156
 }
157 157
 
158 158
 void Sd2Card::chipDeselect() {
159
-  digitalWrite(chipSelectPin_, HIGH);
159
+  extDigitalWrite(chipSelectPin_, HIGH);
160 160
   spiSend(0xFF); // Ensure MISO goes high impedance
161 161
 }
162 162
 
163 163
 void Sd2Card::chipSelect() {
164 164
   spiInit(spiRate_);
165
-  digitalWrite(chipSelectPin_, LOW);
165
+  extDigitalWrite(chipSelectPin_, LOW);
166 166
 }
167 167
 
168 168
 /**
@@ -241,8 +241,8 @@ bool Sd2Card::init(const uint8_t sckRateID/*=0*/, const pin_t chipSelectPin/*=SD
241 241
   #endif
242 242
 
243 243
   // Set pin modes
244
-  digitalWrite(chipSelectPin_, HIGH);  // For some CPUs pinMode can write the wrong data so init desired data value first
245
-  pinMode(chipSelectPin_, OUTPUT);     // Solution for #8746 by @benlye
244
+  extDigitalWrite(chipSelectPin_, HIGH);  // For some CPUs pinMode can write the wrong data so init desired data value first
245
+  pinMode(chipSelectPin_, OUTPUT);        // Solution for #8746 by @benlye
246 246
   spiBegin();
247 247
 
248 248
   // Set SCK rate for initialization commands

Loading…
Отказ
Запис