Browse Source

BigTreeTech GTR V1.0 / Support 8 extruders, heaters, temp sensors, fans (#16595)

yangwenxiong 4 years ago
parent
commit
248b7dfa59
66 changed files with 2081 additions and 212 deletions
  1. 15
    4
      Marlin/src/HAL/HAL_AVR/fastio.h
  2. 4
    0
      Marlin/src/HAL/HAL_LPC1768/inc/SanityCheck.h
  3. 43
    7
      Marlin/src/HAL/HAL_SAMD51/HAL.cpp
  4. 18
    0
      Marlin/src/HAL/HAL_STM32F1/HAL.cpp
  5. 4
    2
      Marlin/src/core/drivers.h
  6. 6
    0
      Marlin/src/core/language.h
  7. 1
    5
      Marlin/src/core/types.h
  8. 24
    9
      Marlin/src/gcode/control/M42.cpp
  9. 25
    1
      Marlin/src/gcode/feature/trinamic/M911-M914.cpp
  10. 2
    0
      Marlin/src/inc/Conditionals_adv.h
  11. 93
    15
      Marlin/src/inc/Conditionals_post.h
  12. 95
    9
      Marlin/src/inc/SanityCheck.h
  13. 15
    0
      Marlin/src/lcd/HD44780/ultralcd_HD44780.cpp
  14. 2
    2
      Marlin/src/lcd/extensible_ui/ui_api.cpp
  15. 1
    1
      Marlin/src/lcd/extensible_ui/ui_api.h
  16. 1
    1
      Marlin/src/lcd/language/language_an.h
  17. 1
    1
      Marlin/src/lcd/language/language_bg.h
  18. 1
    1
      Marlin/src/lcd/language/language_ca.h
  19. 3
    3
      Marlin/src/lcd/language/language_cz.h
  20. 1
    1
      Marlin/src/lcd/language/language_da.h
  21. 1
    1
      Marlin/src/lcd/language/language_el.h
  22. 1
    1
      Marlin/src/lcd/language/language_el_gr.h
  23. 3
    3
      Marlin/src/lcd/language/language_en.h
  24. 2
    2
      Marlin/src/lcd/language/language_es.h
  25. 2
    2
      Marlin/src/lcd/language/language_eu.h
  26. 1
    1
      Marlin/src/lcd/language/language_fi.h
  27. 3
    3
      Marlin/src/lcd/language/language_fr.h
  28. 3
    3
      Marlin/src/lcd/language/language_it.h
  29. 2
    2
      Marlin/src/lcd/language/language_ko_KR.h
  30. 1
    1
      Marlin/src/lcd/language/language_nl.h
  31. 2
    2
      Marlin/src/lcd/language/language_pl.h
  32. 1
    1
      Marlin/src/lcd/language/language_pt.h
  33. 2
    2
      Marlin/src/lcd/language/language_pt_br.h
  34. 2
    2
      Marlin/src/lcd/language/language_sk.h
  35. 2
    2
      Marlin/src/lcd/language/language_tr.h
  36. 1
    1
      Marlin/src/lcd/language/language_uk.h
  37. 2
    2
      Marlin/src/lcd/language/language_vi.h
  38. 2
    2
      Marlin/src/lcd/language/language_zh_CN.h
  39. 2
    2
      Marlin/src/lcd/language/language_zh_TW.h
  40. 1
    1
      Marlin/src/lcd/menu/menu.h
  41. 12
    0
      Marlin/src/lcd/menu/menu_advanced.cpp
  42. 18
    0
      Marlin/src/lcd/menu/menu_info.cpp
  43. 58
    19
      Marlin/src/lcd/menu/menu_temperature.cpp
  44. 18
    0
      Marlin/src/lcd/menu/menu_tmc.cpp
  45. 57
    18
      Marlin/src/lcd/menu/menu_tune.cpp
  46. 3
    1
      Marlin/src/libs/L64XX/L64XX_Marlin.cpp
  47. 1
    1
      Marlin/src/libs/L64XX/L64XX_Marlin.h
  48. 2
    5
      Marlin/src/libs/softspi.h
  49. 44
    0
      Marlin/src/module/configuration_store.cpp
  50. 10
    4
      Marlin/src/module/endstops.cpp
  51. 15
    1
      Marlin/src/module/planner.cpp
  52. 86
    18
      Marlin/src/module/stepper.cpp
  53. 34
    0
      Marlin/src/module/stepper/L64xx.h
  54. 16
    0
      Marlin/src/module/stepper/TMC26X.h
  55. 245
    21
      Marlin/src/module/stepper/indirection.h
  56. 40
    0
      Marlin/src/module/stepper/trinamic.cpp
  57. 28
    0
      Marlin/src/module/stepper/trinamic.h
  58. 176
    6
      Marlin/src/module/temperature.cpp
  59. 6
    0
      Marlin/src/module/temperature.h
  60. 40
    1
      Marlin/src/module/thermistor/thermistors.h
  61. 70
    0
      Marlin/src/pins/pins.h
  62. 153
    0
      Marlin/src/pins/pinsDebug_list.h
  63. 100
    4
      Marlin/src/pins/sensitive_pins.h
  64. 391
    0
      Marlin/src/pins/stm32/pins_BTT_GTR_V1_0.h
  65. 35
    14
      buildroot/share/PlatformIO/variants/BIGTREE_SKR_PRO_1v1/PeripheralPins.c
  66. 32
    1
      platformio.ini

+ 15
- 4
Marlin/src/HAL/HAL_AVR/fastio.h View File

@@ -279,14 +279,25 @@ enum ClockSource2 : char {
279 279
  */
280 280
 
281 281
 // Determine which harware PWMs are already in use
282
+#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 == E6_AUTO_FAN_PIN || P == E7_AUTO_FAN_PIN || P == CHAMBER_AUTO_FAN_PIN)
282 283
 #if PIN_EXISTS(CONTROLLER_FAN)
283
-  #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)
284
+  #define PWM_CHK_FAN_B(P) (_PWM_CHK_FAN_B(P) || P == CONTROLLER_FAN_PIN)
284 285
 #else
285
-  #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)
286
+  #define PWM_CHK_FAN_B(P) _PWM_CHK_FAN_B(P)
286 287
 #endif
287 288
 
288
-#if ANY_PIN(FAN, FAN1, FAN2)
289
-  #if PIN_EXISTS(FAN2)
289
+#if ANY_PIN(FAN, FAN1, FAN2, FAN3, FAN4, FAN5, FAN6, FAN7)
290
+  #if PIN_EXISTS(FAN7)
291
+    #define PWM_CHK_FAN_A(P) (P == FAN0_PIN || P == FAN1_PIN || P == FAN2_PIN || P == FAN3_PIN || P == FAN4_PIN || P == FAN5_PIN || P == FAN6_PIN || P == FAN7_PIN)
292
+  #elif PIN_EXISTS(FAN6)
293
+    #define PWM_CHK_FAN_A(P) (P == FAN0_PIN || P == FAN1_PIN || P == FAN2_PIN || P == FAN3_PIN || P == FAN4_PIN || P == FAN5_PIN || P == FAN6_PIN)
294
+  #elif PIN_EXISTS(FAN5)
295
+    #define PWM_CHK_FAN_A(P) (P == FAN0_PIN || P == FAN1_PIN || P == FAN2_PIN || P == FAN3_PIN || P == FAN4_PIN || P == FAN5_PIN)
296
+  #elif PIN_EXISTS(FAN4)
297
+    #define PWM_CHK_FAN_A(P) (P == FAN0_PIN || P == FAN1_PIN || P == FAN2_PIN || P == FAN3_PIN || P == FAN4_PIN)
298
+  #elif PIN_EXISTS(FAN3)
299
+    #define PWM_CHK_FAN_A(P) (P == FAN0_PIN || P == FAN1_PIN || P == FAN2_PIN || P == FAN3_PIN)
300
+  #elif PIN_EXISTS(FAN2)
290 301
     #define PWM_CHK_FAN_A(P) (P == FAN0_PIN || P == FAN1_PIN || P == FAN2_PIN)
291 302
   #elif PIN_EXISTS(FAN1)
292 303
     #define PWM_CHK_FAN_A(P) (P == FAN0_PIN || P == FAN1_PIN)

+ 4
- 0
Marlin/src/HAL/HAL_LPC1768/inc/SanityCheck.h View File

@@ -46,6 +46,10 @@
46 46
   #error "TEMP_4_PIN must be defined using the Pn_nn or Pn_nn_An format. (See the included pins files)."
47 47
 #elif _OLD_TEMP_PIN(TEMP_5)
48 48
   #error "TEMP_5_PIN must be defined using the Pn_nn or Pn_nn_An format. (See the included pins files)."
49
+#elif _OLD_TEMP_PIN(TEMP_6)
50
+  #error "TEMP_6_PIN must be defined using the Pn_nn or Pn_nn_An format. (See the included pins files)."
51
+#elif _OLD_TEMP_PIN(TEMP_7)
52
+  #error "TEMP_7_PIN must be defined using the Pn_nn or Pn_nn_An format. (See the included pins files)."
49 53
 #endif
50 54
 #undef _OLD_TEMP_PIN
51 55
 

+ 43
- 7
Marlin/src/HAL/HAL_SAMD51/HAL.cpp View File

@@ -59,6 +59,16 @@
59 59
 #else
60 60
   #define GET_TEMP_5_ADC()          -1
61 61
 #endif
62
+#if HAS_TEMP_ADC_6
63
+  #define GET_TEMP_6_ADC()          PIN_TO_ADC(TEMP_6_PIN)
64
+#else
65
+  #define GET_TEMP_6_ADC()          -1
66
+#endif
67
+#if HAS_TEMP_ADC_7
68
+  #define GET_TEMP_7_ADC()          PIN_TO_ADC(TEMP_7_PIN)
69
+#else
70
+  #define GET_TEMP_7_ADC()          -1
71
+#endif
62 72
 #if HAS_TEMP_PROBE
63 73
   #define GET_PROBE_ADC()           PIN_TO_ADC(TEMP_PROBE_PIN)
64 74
 #else
@@ -85,13 +95,15 @@
85 95
   #define GET_BUTTONS_ADC()         -1
86 96
 #endif
87 97
 
88
-#define IS_ADC_REQUIRED(n)      (GET_TEMP_0_ADC() == n || GET_TEMP_1_ADC() == n || GET_TEMP_2_ADC() == n      \
89
-                                 || GET_TEMP_3_ADC() == n || GET_TEMP_4_ADC() == n || GET_TEMP_5_ADC() == n   \
90
-                                 || GET_PROBE_ADC() == n                                                      \
91
-                                 || GET_BED_ADC() == n                                                        \
92
-                                 || GET_CHAMBER_ADC() == n                                                    \
93
-                                 || GET_FILAMENT_WIDTH_ADC() == n                                             \
94
-                                 || GET_BUTTONS_ADC() == n)
98
+#define IS_ADC_REQUIRED(n) ( \
99
+     GET_TEMP_0_ADC() == n || GET_TEMP_1_ADC() == n || GET_TEMP_2_ADC() == n || GET_TEMP_3_ADC() == n \
100
+  || GET_TEMP_4_ADC() == n || GET_TEMP_5_ADC() == n || GET_TEMP_6_ADC() == n || GET_TEMP_7_ADC() == n \
101
+  || GET_PROBE_ADC() == n          \
102
+  || GET_BED_ADC() == n            \
103
+  || GET_CHAMBER_ADC() == n        \
104
+  || GET_FILAMENT_WIDTH_ADC() == n \
105
+  || GET_BUTTONS_ADC() == n        \
106
+)
95 107
 
96 108
 #define ADC0_IS_REQUIRED    IS_ADC_REQUIRED(0)
97 109
 #define ADC1_IS_REQUIRED    IS_ADC_REQUIRED(1)
@@ -151,6 +163,12 @@ uint16_t HAL_adc_result;
151 163
     #if GET_TEMP_5_ADC() == 0
152 164
       TEMP_5_PIN,
153 165
     #endif
166
+    #if GET_TEMP_6_ADC() == 0
167
+      TEMP_6_PIN,
168
+    #endif
169
+    #if GET_TEMP_7_ADC() == 0
170
+      TEMP_7_PIN,
171
+    #endif
154 172
     #if GET_PROBE_ADC() == 0
155 173
       TEMP_PROBE_PIN,
156 174
     #endif
@@ -185,6 +203,12 @@ uint16_t HAL_adc_result;
185 203
     #if GET_TEMP_5_ADC() == 1
186 204
       TEMP_5_PIN,
187 205
     #endif
206
+    #if GET_TEMP_6_ADC() == 1
207
+      TEMP_6_PIN,
208
+    #endif
209
+    #if GET_TEMP_7_ADC() == 1
210
+      TEMP_7_PIN,
211
+    #endif
188 212
     #if GET_PROBE_ADC() == 1
189 213
       TEMP_PROBE_PIN,
190 214
     #endif
@@ -227,6 +251,12 @@ uint16_t HAL_adc_result;
227 251
       #if GET_TEMP_5_ADC() == 0
228 252
         { PIN_TO_INPUTCTRL(TEMP_5_PIN) },
229 253
       #endif
254
+      #if GET_TEMP_6_ADC() == 0
255
+        { PIN_TO_INPUTCTRL(TEMP_6_PIN) },
256
+      #endif
257
+      #if GET_TEMP_7_ADC() == 0
258
+        { PIN_TO_INPUTCTRL(TEMP_7_PIN) },
259
+      #endif
230 260
       #if GET_PROBE_ADC() == 0
231 261
         { PIN_TO_INPUTCTRL(TEMP_PROBE_PIN) },
232 262
       #endif
@@ -270,6 +300,12 @@ uint16_t HAL_adc_result;
270 300
       #if GET_TEMP_5_ADC() == 1
271 301
         { PIN_TO_INPUTCTRL(TEMP_5_PIN) },
272 302
       #endif
303
+      #if GET_TEMP_6_ADC() == 1
304
+        { PIN_TO_INPUTCTRL(TEMP_6_PIN) },
305
+      #endif
306
+      #if GET_TEMP_7_ADC() == 1
307
+        { PIN_TO_INPUTCTRL(TEMP_7_PIN) },
308
+      #endif
273 309
       #if GET_PROBE_ADC() == 1
274 310
         { PIN_TO_INPUTCTRL(TEMP_PROBE_PIN) },
275 311
       #endif

+ 18
- 0
Marlin/src/HAL/HAL_STM32F1/HAL.cpp View File

@@ -118,6 +118,12 @@ const uint8_t adc_pins[] = {
118 118
   #if HAS_TEMP_ADC_5
119 119
     TEMP_5_PIN,
120 120
   #endif
121
+  #if HAS_TEMP_ADC_6
122
+    TEMP_6_PIN,
123
+  #endif
124
+  #if HAS_TEMP_ADC_7
125
+    TEMP_7_PIN,
126
+  #endif
121 127
   #if ENABLED(FILAMENT_WIDTH_SENSOR)
122 128
     FILWIDTH_PIN,
123 129
   #endif
@@ -160,6 +166,12 @@ enum TEMP_PINS : char {
160 166
   #if HAS_TEMP_ADC_5
161 167
     TEMP_5,
162 168
   #endif
169
+  #if HAS_TEMP_ADC_6
170
+    TEMP_6,
171
+  #endif
172
+  #if HAS_TEMP_ADC_7
173
+    TEMP_7,
174
+  #endif
163 175
   #if ENABLED(FILAMENT_WIDTH_SENSOR)
164 176
     FILWIDTH,
165 177
   #endif
@@ -346,6 +358,12 @@ void HAL_adc_start_conversion(const uint8_t adc_pin) {
346 358
     #if HAS_TEMP_ADC_5
347 359
       case TEMP_5_PIN: pin_index = TEMP_5; break;
348 360
     #endif
361
+    #if HAS_TEMP_ADC_6
362
+      case TEMP_6_PIN: pin_index = TEMP_6; break;
363
+    #endif
364
+    #if HAS_TEMP_ADC_7
365
+      case TEMP_7_PIN: pin_index = TEMP_7; break;
366
+    #endif
349 367
     #if HAS_JOY_ADC_X
350 368
       case JOY_X_PIN: pin_index = JOY_X; break;
351 369
     #endif

+ 4
- 2
Marlin/src/core/drivers.h View File

@@ -79,7 +79,8 @@
79 79
 
80 80
 #define HAS_E_DRIVER(T) (  AXIS_DRIVER_TYPE_E0(T) || AXIS_DRIVER_TYPE_E1(T) \
81 81
                         || AXIS_DRIVER_TYPE_E2(T) || AXIS_DRIVER_TYPE_E3(T) \
82
-                        || AXIS_DRIVER_TYPE_E4(T) || AXIS_DRIVER_TYPE_E5(T) )
82
+                        || AXIS_DRIVER_TYPE_E4(T) || AXIS_DRIVER_TYPE_E5(T) \
83
+                        || AXIS_DRIVER_TYPE_E6(T) || AXIS_DRIVER_TYPE_E7(T) )
83 84
 
84 85
 #define HAS_DRIVER(T) (    AXIS_DRIVER_TYPE_X(T)  || AXIS_DRIVER_TYPE_X2(T) \
85 86
                         || AXIS_DRIVER_TYPE_Y(T)  || AXIS_DRIVER_TYPE_Y2(T) \
@@ -152,7 +153,8 @@
152 153
                           || AXIS_HAS_##T(Z3) \
153 154
                           || AXIS_HAS_##T(E0) || AXIS_HAS_##T(E1) \
154 155
                           || AXIS_HAS_##T(E2) || AXIS_HAS_##T(E3) \
155
-                          || AXIS_HAS_##T(E4) || AXIS_HAS_##T(E5) )
156
+                          || AXIS_HAS_##T(E4) || AXIS_HAS_##T(E5) \
157
+                          || AXIS_HAS_##T(E6) || AXIS_HAS_##T(E7) )
156 158
 
157 159
 #define HAS_STEALTHCHOP    ANY_AXIS_HAS(STEALTHCHOP)
158 160
 #define HAS_STALLGUARD     ANY_AXIS_HAS(STALLGUARD)

+ 6
- 0
Marlin/src/core/language.h View File

@@ -359,6 +359,8 @@
359 359
   #define LCD_STR_N3 "3"
360 360
   #define LCD_STR_N4 "4"
361 361
   #define LCD_STR_N5 "5"
362
+  #define LCD_STR_N6 "6"
363
+  #define LCD_STR_N7 "7"
362 364
 #else
363 365
   #define LCD_FIRST_TOOL '1'
364 366
   #define LCD_STR_N0 "1"
@@ -367,6 +369,8 @@
367 369
   #define LCD_STR_N3 "4"
368 370
   #define LCD_STR_N4 "5"
369 371
   #define LCD_STR_N5 "6"
372
+  #define LCD_STR_N6 "7"
373
+  #define LCD_STR_N7 "8"
370 374
 #endif
371 375
 
372 376
 #define LCD_STR_E0 "E" LCD_STR_N0
@@ -375,6 +379,8 @@
375 379
 #define LCD_STR_E3 "E" LCD_STR_N3
376 380
 #define LCD_STR_E4 "E" LCD_STR_N4
377 381
 #define LCD_STR_E5 "E" LCD_STR_N5
382
+#define LCD_STR_E6 "E" LCD_STR_N6
383
+#define LCD_STR_E7 "E" LCD_STR_N7
378 384
 
379 385
 #include "multi_language.h"   // Allow multiple languages
380 386
 

+ 1
- 5
Marlin/src/core/types.h View File

@@ -43,11 +43,7 @@ enum AxisEnum : uint8_t {
43 43
   E_AXIS   = 3,
44 44
   X_HEAD   = 4, Y_HEAD = 5, Z_HEAD = 6,
45 45
   E0_AXIS  = 3,
46
-  E1_AXIS  = 4,
47
-  E2_AXIS  = 5,
48
-  E3_AXIS  = 6,
49
-  E4_AXIS  = 7,
50
-  E5_AXIS  = 8,
46
+  E1_AXIS, E2_AXIS, E3_AXIS, E4_AXIS, E5_AXIS, E6_AXIS, E7_AXIS,
51 47
   ALL_AXES = 0xFE, NO_AXIS = 0xFF
52 48
 };
53 49
 

+ 24
- 9
Marlin/src/gcode/control/M42.cpp View File

@@ -47,23 +47,38 @@ void GcodeSuite::M42() {
47 47
 
48 48
   const pin_t pin = GET_PIN_MAP_PIN(pin_index);
49 49
 
50
-  if (!parser.boolval('I') && pin_is_protected(pin)) return protected_pin_err();
51
-
52
-  pinMode(pin, OUTPUT);
53
-  extDigitalWrite(pin, pin_status);
54
-  analogWrite(pin, pin_status);
55
-
56 50
   #if FAN_COUNT > 0
57 51
     switch (pin) {
58 52
       #if HAS_FAN0
59
-        case FAN0_PIN: thermalManager.fan_speed[0] = pin_status; break;
53
+        case FAN0_PIN: thermalManager.fan_speed[0] = pin_status; return;
60 54
       #endif
61 55
       #if HAS_FAN1
62
-        case FAN1_PIN: thermalManager.fan_speed[1] = pin_status; break;
56
+        case FAN1_PIN: thermalManager.fan_speed[1] = pin_status; return;
63 57
       #endif
64 58
       #if HAS_FAN2
65
-        case FAN2_PIN: thermalManager.fan_speed[2] = pin_status; break;
59
+        case FAN2_PIN: thermalManager.fan_speed[2] = pin_status; return;
60
+      #endif
61
+      #if HAS_FAN3
62
+        case FAN3_PIN: thermalManager.fan_speed[3] = pin_status; return;
63
+      #endif
64
+      #if HAS_FAN4
65
+        case FAN4_PIN: thermalManager.fan_speed[4] = pin_status; return;
66
+      #endif
67
+      #if HAS_FAN5
68
+        case FAN5_PIN: thermalManager.fan_speed[5] = pin_status; return;
69
+      #endif
70
+      #if HAS_FAN6
71
+        case FAN6_PIN: thermalManager.fan_speed[6] = pin_status; return;
72
+      #endif
73
+      #if HAS_FAN7
74
+        case FAN7_PIN: thermalManager.fan_speed[7] = pin_status; return;
66 75
       #endif
67 76
     }
68 77
   #endif
78
+
79
+  if (!parser.boolval('I') && pin_is_protected(pin)) return protected_pin_err();
80
+
81
+  pinMode(pin, OUTPUT);
82
+  extDigitalWrite(pin, pin_status);
83
+  analogWrite(pin, pin_status);
69 84
 }

+ 25
- 1
Marlin/src/gcode/feature/trinamic/M911-M914.cpp View File

@@ -38,7 +38,7 @@
38 38
   #define M91x_SOME_X (M91x_USE(X) || M91x_USE(X2))
39 39
   #define M91x_SOME_Y (M91x_USE(Y) || M91x_USE(Y2))
40 40
   #define M91x_SOME_Z (M91x_USE(Z) || M91x_USE(Z2) || M91x_USE(Z3) || M91x_USE(Z4))
41
-  #define M91x_SOME_E (M91x_USE_E(0) || M91x_USE_E(1) || M91x_USE_E(2) || M91x_USE_E(3) || M91x_USE_E(4) || M91x_USE_E(5))
41
+  #define M91x_SOME_E (M91x_USE_E(0) || M91x_USE_E(1) || M91x_USE_E(2) || M91x_USE_E(3) || M91x_USE_E(4) || M91x_USE_E(5) || M91x_USE_E(6) || M91x_USE_E(7))
42 42
 
43 43
   #if !M91x_SOME_X && !M91x_SOME_Y && !M91x_SOME_Z && !M91x_SOME_E
44 44
     #error "MONITOR_DRIVER_STATUS requires at least one TMC2130, 2160, 2208, 2209, 2660, 5130, or 5160."
@@ -91,6 +91,12 @@
91 91
     #if M91x_USE_E(5)
92 92
       tmc_report_otpw(stepperE5);
93 93
     #endif
94
+    #if M91x_USE_E(6)
95
+      tmc_report_otpw(stepperE6);
96
+    #endif
97
+    #if M91x_USE_E(7)
98
+      tmc_report_otpw(stepperE7);
99
+    #endif
94 100
   }
95 101
 
96 102
   /**
@@ -188,6 +194,12 @@
188 194
       #if M91x_USE_E(5)
189 195
         if (hasNone || eval == 5 || (hasE && eval < 0)) tmc_clear_otpw(stepperE5);
190 196
       #endif
197
+      #if M91x_USE_E(6)
198
+        if (hasNone || eval == 6 || (hasE && eval < 0)) tmc_clear_otpw(stepperE6);
199
+      #endif
200
+      #if M91x_USE_E(7)
201
+        if (hasNone || eval == 7 || (hasE && eval < 0)) tmc_clear_otpw(stepperE7);
202
+      #endif
191 203
     #endif
192 204
   }
193 205
 
@@ -263,6 +275,12 @@
263 275
               #if E_STEPPERS > 5 && AXIS_HAS_STEALTHCHOP(E5)
264 276
                 case 5: TMC_SET_PWMTHRS_E(5); break;
265 277
               #endif
278
+              #if E_STEPPERS > 6 && AXIS_HAS_STEALTHCHOP(E6)
279
+                case 6: TMC_SET_PWMTHRS_E(6); break;
280
+              #endif
281
+              #if E_STEPPERS > 7 && AXIS_HAS_STEALTHCHOP(E7)
282
+                case 7: TMC_SET_PWMTHRS_E(7); break;
283
+              #endif
266 284
             }
267 285
           #endif // E_STEPPERS
268 286
         } break;
@@ -312,6 +330,12 @@
312 330
       #if E_STEPPERS > 5 && AXIS_HAS_STEALTHCHOP(E5)
313 331
         TMC_SAY_PWMTHRS_E(5);
314 332
       #endif
333
+      #if E_STEPPERS > 6 && AXIS_HAS_STEALTHCHOP(E6)
334
+        TMC_SAY_PWMTHRS_E(6);
335
+      #endif
336
+      #if E_STEPPERS > 7 && AXIS_HAS_STEALTHCHOP(E7)
337
+        TMC_SAY_PWMTHRS_E(7);
338
+      #endif
315 339
     }
316 340
   }
317 341
 #endif // HYBRID_THRESHOLD

+ 2
- 0
Marlin/src/inc/Conditionals_adv.h View File

@@ -34,6 +34,8 @@
34 34
   #undef TEMP_SENSOR_3
35 35
   #undef TEMP_SENSOR_4
36 36
   #undef TEMP_SENSOR_5
37
+  #undef TEMP_SENSOR_6
38
+  #undef TEMP_SENSOR_7
37 39
   #undef FWRETRACT
38 40
   #undef PIDTEMP
39 41
   #undef AUTOTEMP

+ 93
- 15
Marlin/src/inc/Conditionals_post.h View File

@@ -341,7 +341,7 @@
341 341
  * Temp Sensor defines
342 342
  */
343 343
 
344
-#define ANY_TEMP_SENSOR_IS(n) (TEMP_SENSOR_0 == (n) || TEMP_SENSOR_1 == (n) || TEMP_SENSOR_2 == (n) || TEMP_SENSOR_3 == (n) || TEMP_SENSOR_4 == (n) || TEMP_SENSOR_5 == (n) || TEMP_SENSOR_BED == (n) || TEMP_SENSOR_PROBE == (n) || TEMP_SENSOR_CHAMBER == (n))
344
+#define ANY_TEMP_SENSOR_IS(n) (TEMP_SENSOR_0 == (n) || TEMP_SENSOR_1 == (n) || TEMP_SENSOR_2 == (n) || TEMP_SENSOR_3 == (n) || TEMP_SENSOR_4 == (n) || TEMP_SENSOR_5 == (n) || TEMP_SENSOR_6 == (n) || TEMP_SENSOR_7 == (n) || TEMP_SENSOR_BED == (n) || TEMP_SENSOR_PROBE == (n) || TEMP_SENSOR_CHAMBER == (n))
345 345
 
346 346
 #define HAS_USER_THERMISTORS ANY_TEMP_SENSOR_IS(1000)
347 347
 
@@ -483,6 +483,44 @@
483 483
   #undef HEATER_5_MAXTEMP
484 484
 #endif
485 485
 
486
+#if TEMP_SENSOR_6 == -4
487
+  #define HEATER_6_USES_AD8495
488
+#elif TEMP_SENSOR_6 == -3
489
+  #error "MAX31855 Thermocouples (-3) not supported for TEMP_SENSOR_6."
490
+#elif TEMP_SENSOR_6 == -2
491
+  #error "MAX6675 Thermocouples (-2) not supported for TEMP_SENSOR_6."
492
+#elif TEMP_SENSOR_6 == -1
493
+  #define HEATER_6_USES_AD595
494
+#elif TEMP_SENSOR_6 > 0
495
+  #define THERMISTOR_HEATER_6 TEMP_SENSOR_6
496
+  #define HEATER_6_USES_THERMISTOR
497
+  #if TEMP_SENSOR_6 == 1000
498
+    #define HEATER_6_USER_THERMISTOR
499
+  #endif
500
+#else
501
+  #undef HEATER_6_MINTEMP
502
+  #undef HEATER_6_MAXTEMP
503
+#endif
504
+
505
+#if TEMP_SENSOR_7 == -4
506
+  #define HEATER_7_USES_AD8495
507
+#elif TEMP_SENSOR_7 == -3
508
+  #error "MAX31855 Thermocouples (-3) not supported for TEMP_SENSOR_7."
509
+#elif TEMP_SENSOR_7 == -2
510
+  #error "MAX7775 Thermocouples (-2) not supported for TEMP_SENSOR_7."
511
+#elif TEMP_SENSOR_7 == -1
512
+  #define HEATER_7_USES_AD595
513
+#elif TEMP_SENSOR_7 > 0
514
+  #define THERMISTOR_HEATER_7 TEMP_SENSOR_7
515
+  #define HEATER_7_USES_THERMISTOR
516
+  #if TEMP_SENSOR_7 == 1000
517
+    #define HEATER_7_USER_THERMISTOR
518
+  #endif
519
+#else
520
+  #undef HEATER_7_MINTEMP
521
+  #undef HEATER_7_MAXTEMP
522
+#endif
523
+
486 524
 #if TEMP_SENSOR_BED == -4
487 525
   #define HEATER_BED_USES_AD8495
488 526
 #elif TEMP_SENSOR_BED == -3
@@ -538,8 +576,8 @@
538 576
 #endif
539 577
 
540 578
 #define HOTEND_USES_THERMISTOR ANY( \
541
-  HEATER_0_USES_THERMISTOR, HEATER_1_USES_THERMISTOR, HEATER_2_USES_THERMISTOR, \
542
-  HEATER_3_USES_THERMISTOR, HEATER_4_USES_THERMISTOR, HEATER_5_USES_THERMISTOR)
579
+  HEATER_0_USES_THERMISTOR, HEATER_1_USES_THERMISTOR, HEATER_2_USES_THERMISTOR, HEATER_3_USES_THERMISTOR, \
580
+  HEATER_4_USES_THERMISTOR, HEATER_5_USES_THERMISTOR, HEATER_6_USES_THERMISTOR, HEATER_7_USES_THERMISTOR )
543 581
 
544 582
 /**
545 583
  * Default hotend offsets, if not defined
@@ -1025,6 +1063,18 @@
1025 1063
 #define HAS_E5_MICROSTEPS (PIN_EXISTS(E5_MS1))
1026 1064
 #define HAS_SOLENOID_5    (PIN_EXISTS(SOL5))
1027 1065
 
1066
+#define HAS_E6_ENABLE     (PIN_EXISTS(E6_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E6)))
1067
+#define HAS_E6_DIR        (PIN_EXISTS(E6_DIR))
1068
+#define HAS_E6_STEP       (PIN_EXISTS(E6_STEP))
1069
+#define HAS_E6_MICROSTEPS (PIN_EXISTS(E6_MS1))
1070
+#define HAS_SOLENOID_6    (PIN_EXISTS(SOL6))
1071
+
1072
+#define HAS_E7_ENABLE     (PIN_EXISTS(E7_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E7)))
1073
+#define HAS_E7_DIR        (PIN_EXISTS(E7_DIR))
1074
+#define HAS_E7_STEP       (PIN_EXISTS(E7_STEP))
1075
+#define HAS_E7_MICROSTEPS (PIN_EXISTS(E7_MS1))
1076
+#define HAS_SOLENOID_7    (PIN_EXISTS(SOL7))
1077
+
1028 1078
 // Trinamic Stepper Drivers
1029 1079
 #if HAS_TRINAMIC
1030 1080
   #define STEALTHCHOP_ENABLED ANY(STEALTHCHOP_XY, STEALTHCHOP_Z, STEALTHCHOP_E)
@@ -1095,6 +1145,8 @@
1095 1145
 #define HAS_TEMP_ADC_3        HAS_ADC_TEST(3)
1096 1146
 #define HAS_TEMP_ADC_4        HAS_ADC_TEST(4)
1097 1147
 #define HAS_TEMP_ADC_5        HAS_ADC_TEST(5)
1148
+#define HAS_TEMP_ADC_6        HAS_ADC_TEST(6)
1149
+#define HAS_TEMP_ADC_7        HAS_ADC_TEST(7)
1098 1150
 #define HAS_TEMP_ADC_BED      HAS_ADC_TEST(BED)
1099 1151
 #define HAS_TEMP_ADC_PROBE    HAS_ADC_TEST(PROBE)
1100 1152
 #define HAS_TEMP_ADC_CHAMBER  HAS_ADC_TEST(CHAMBER)
@@ -1118,6 +1170,8 @@
1118 1170
 #define HAS_HEATER_3    (PIN_EXISTS(HEATER_3))
1119 1171
 #define HAS_HEATER_4    (PIN_EXISTS(HEATER_4))
1120 1172
 #define HAS_HEATER_5    (PIN_EXISTS(HEATER_5))
1173
+#define HAS_HEATER_6    (PIN_EXISTS(HEATER_6))
1174
+#define HAS_HEATER_7    (PIN_EXISTS(HEATER_7))
1121 1175
 #define HAS_HEATER_BED  (PIN_EXISTS(HEATER_BED))
1122 1176
 
1123 1177
 // Shorthand for common combinations
@@ -1146,12 +1200,14 @@
1146 1200
 #define HAS_AUTO_FAN_3 (HOTENDS > 3 && PIN_EXISTS(E3_AUTO_FAN))
1147 1201
 #define HAS_AUTO_FAN_4 (HOTENDS > 4 && PIN_EXISTS(E4_AUTO_FAN))
1148 1202
 #define HAS_AUTO_FAN_5 (HOTENDS > 5 && PIN_EXISTS(E5_AUTO_FAN))
1203
+#define HAS_AUTO_FAN_6 (HOTENDS > 6 && PIN_EXISTS(E6_AUTO_FAN))
1204
+#define HAS_AUTO_FAN_7 (HOTENDS > 7 && PIN_EXISTS(E7_AUTO_FAN))
1149 1205
 #define HAS_AUTO_CHAMBER_FAN (HAS_TEMP_CHAMBER && PIN_EXISTS(CHAMBER_AUTO_FAN))
1150 1206
 
1151
-#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)
1207
+#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_FAN_6 || HAS_AUTO_FAN_7 || HAS_AUTO_CHAMBER_FAN)
1152 1208
 #define _FANOVERLAP(A,B) (A##_AUTO_FAN_PIN == E##B##_AUTO_FAN_PIN)
1153 1209
 #if HAS_AUTO_FAN
1154
-  #define AUTO_CHAMBER_IS_E (_FANOVERLAP(CHAMBER,0) || _FANOVERLAP(CHAMBER,1) || _FANOVERLAP(CHAMBER,2) || _FANOVERLAP(CHAMBER,3) || _FANOVERLAP(CHAMBER,4) || _FANOVERLAP(CHAMBER,5))
1210
+  #define AUTO_CHAMBER_IS_E (_FANOVERLAP(CHAMBER,0) || _FANOVERLAP(CHAMBER,1) || _FANOVERLAP(CHAMBER,2) || _FANOVERLAP(CHAMBER,3) || _FANOVERLAP(CHAMBER,4) || _FANOVERLAP(CHAMBER,5) || _FANOVERLAP(CHAMBER,6) || _FANOVERLAP(CHAMBER,7))
1155 1211
 #endif
1156 1212
 
1157 1213
 #if !HAS_TEMP_SENSOR
@@ -1164,8 +1220,14 @@
1164 1220
 
1165 1221
 // Other fans
1166 1222
 #define HAS_FAN0 (PIN_EXISTS(FAN))
1167
-#define HAS_FAN1 (PIN_EXISTS(FAN1) && CONTROLLER_FAN_PIN != FAN1_PIN && E0_AUTO_FAN_PIN != FAN1_PIN && E1_AUTO_FAN_PIN != FAN1_PIN && E2_AUTO_FAN_PIN != FAN1_PIN && E3_AUTO_FAN_PIN != FAN1_PIN && E4_AUTO_FAN_PIN != FAN1_PIN && E5_AUTO_FAN_PIN != FAN1_PIN)
1168
-#define HAS_FAN2 (PIN_EXISTS(FAN2) && CONTROLLER_FAN_PIN != FAN2_PIN && E0_AUTO_FAN_PIN != FAN2_PIN && E1_AUTO_FAN_PIN != FAN2_PIN && E2_AUTO_FAN_PIN != FAN2_PIN && E3_AUTO_FAN_PIN != FAN2_PIN && E4_AUTO_FAN_PIN != FAN2_PIN && E5_AUTO_FAN_PIN != FAN2_PIN)
1223
+#define _HAS_FAN(P) (PIN_EXISTS(FAN_##P) && CONTROLLER_FAN_PIN != FAN_##P##_PIN && E0_AUTO_FAN_PIN != FAN_##P##_PIN && E1_AUTO_FAN_PIN != FAN_##P##_PIN && E2_AUTO_FAN_PIN != FAN_##P##_PIN && E3_AUTO_FAN_PIN != FAN_##P##_PIN && E4_AUTO_FAN_PIN != FAN_##P##_PIN && E5_AUTO_FAN_PIN != FAN_##P##_PIN && E6_AUTO_FAN_PIN != FAN_##P##_PIN && E7_AUTO_FAN_PIN != FAN_##P##_PIN)
1224
+#define HAS_FAN1 _HAS_FAN(1)
1225
+#define HAS_FAN2 _HAS_FAN(2)
1226
+#define HAS_FAN3 _HAS_FAN(3)
1227
+#define HAS_FAN4 _HAS_FAN(4)
1228
+#define HAS_FAN5 _HAS_FAN(5)
1229
+#define HAS_FAN6 _HAS_FAN(6)
1230
+#define HAS_FAN7 _HAS_FAN(7)
1169 1231
 #define HAS_CONTROLLER_FAN (PIN_EXISTS(CONTROLLER_FAN))
1170 1232
 
1171 1233
 // Servos
@@ -1203,7 +1265,7 @@
1203 1265
 #define HAS_MOTOR_CURRENT_PWM ANY_PIN(MOTOR_CURRENT_PWM_X, MOTOR_CURRENT_PWM_Y, MOTOR_CURRENT_PWM_XY, MOTOR_CURRENT_PWM_Z, MOTOR_CURRENT_PWM_E)
1204 1266
 
1205 1267
 #define HAS_SOME_Z_MICROSTEPS (HAS_Z_MICROSTEPS || HAS_Z2_MICROSTEPS || HAS_Z3_MICROSTEPS || HAS_Z4_MICROSTEPS)
1206
-#define HAS_SOME_E_MICROSTEPS (HAS_E0_MICROSTEPS || HAS_E1_MICROSTEPS || HAS_E2_MICROSTEPS || HAS_E3_MICROSTEPS || HAS_E4_MICROSTEPS || HAS_E5_MICROSTEPS)
1268
+#define HAS_SOME_E_MICROSTEPS (HAS_E0_MICROSTEPS || HAS_E1_MICROSTEPS || HAS_E2_MICROSTEPS || HAS_E3_MICROSTEPS || HAS_E4_MICROSTEPS || HAS_E5_MICROSTEPS || HAS_E6_MICROSTEPS || HAS_E7_MICROSTEPS)
1207 1269
 #define HAS_MICROSTEPS (HAS_X_MICROSTEPS || HAS_X2_MICROSTEPS || HAS_Y_MICROSTEPS || HAS_Y2_MICROSTEPS || HAS_SOME_Z_MICROSTEPS || HAS_SOME_E_MICROSTEPS)
1208 1270
 
1209 1271
 #if HAS_MICROSTEPS
@@ -1278,26 +1340,27 @@
1278 1340
 #if HAS_HEATER_0 && !defined(HEATER_0_INVERTING)
1279 1341
   #define HEATER_0_INVERTING false
1280 1342
 #endif
1281
-
1282 1343
 #if HAS_HEATER_1 && !defined(HEATER_1_INVERTING)
1283 1344
   #define HEATER_1_INVERTING false
1284 1345
 #endif
1285
-
1286 1346
 #if HAS_HEATER_2 && !defined(HEATER_2_INVERTING)
1287 1347
   #define HEATER_2_INVERTING false
1288 1348
 #endif
1289
-
1290 1349
 #if HAS_HEATER_3 && !defined(HEATER_3_INVERTING)
1291 1350
   #define HEATER_3_INVERTING false
1292 1351
 #endif
1293
-
1294 1352
 #if HAS_HEATER_4 && !defined(HEATER_4_INVERTING)
1295 1353
   #define HEATER_4_INVERTING false
1296 1354
 #endif
1297
-
1298 1355
 #if HAS_HEATER_5 && !defined(HEATER_5_INVERTING)
1299 1356
   #define HEATER_5_INVERTING false
1300 1357
 #endif
1358
+#if HAS_HEATER_6 && !defined(HEATER_6_INVERTING)
1359
+  #define HEATER_6_INVERTING false
1360
+#endif
1361
+#if HAS_HEATER_7 && !defined(HEATER_7_INVERTING)
1362
+  #define HEATER_7_INVERTING false
1363
+#endif
1301 1364
 
1302 1365
 /**
1303 1366
  * Helper Macros for heaters and extruder fan
@@ -1314,6 +1377,12 @@
1314 1377
         #define WRITE_HEATER_4(v) WRITE(HEATER_4_PIN, (v) ^ HEATER_4_INVERTING)
1315 1378
         #if HOTENDS > 5
1316 1379
           #define WRITE_HEATER_5(v) WRITE(HEATER_5_PIN, (v) ^ HEATER_5_INVERTING)
1380
+          #if HOTENDS > 6
1381
+            #define WRITE_HEATER_6(v) WRITE(HEATER_6_PIN, (v) ^ HEATER_6_INVERTING)
1382
+            #if HOTENDS > 7
1383
+              #define WRITE_HEATER_7(v) WRITE(HEATER_7_PIN, (v) ^ HEATER_7_INVERTING)
1384
+            #endif // HOTENDS > 7
1385
+          #endif // HOTENDS > 6
1317 1386
         #endif // HOTENDS > 5
1318 1387
       #endif // HOTENDS > 4
1319 1388
     #endif // HOTENDS > 3
@@ -1365,7 +1434,17 @@
1365 1434
   #define FAN_INVERTING false
1366 1435
 #endif
1367 1436
 
1368
-#if HAS_FAN2
1437
+#if HAS_FAN7
1438
+  #define FAN_COUNT 8
1439
+#elif HAS_FAN6
1440
+  #define FAN_COUNT 7
1441
+#elif HAS_FAN5
1442
+  #define FAN_COUNT 6
1443
+#elif HAS_FAN4
1444
+  #define FAN_COUNT 5
1445
+#elif HAS_FAN3
1446
+  #define FAN_COUNT 4
1447
+#elif HAS_FAN2
1369 1448
   #define FAN_COUNT 3
1370 1449
 #elif HAS_FAN1
1371 1450
   #define FAN_COUNT 2
@@ -1640,7 +1719,6 @@
1640 1719
   #define HAS_FIXED_3POINT
1641 1720
 #endif
1642 1721
 
1643
-
1644 1722
 /**
1645 1723
  * Buzzer/Speaker
1646 1724
  */

+ 95
- 9
Marlin/src/inc/SanityCheck.h View File

@@ -294,19 +294,19 @@
294 294
 #elif defined(HAVE_L6470DRIVER)
295 295
   #error "HAVE_L6470DRIVER is now [AXIS]_DRIVER_TYPE L6470. Please update your Configuration.h."
296 296
 #elif defined(X_IS_TMC) || defined(X2_IS_TMC) || defined(Y_IS_TMC) || defined(Y2_IS_TMC) || defined(Z_IS_TMC) || defined(Z2_IS_TMC) || defined(Z3_IS_TMC) \
297
-   || defined(E0_IS_TMC) || defined(E1_IS_TMC) || defined(E2_IS_TMC) || defined(E3_IS_TMC) || defined(E4_IS_TMC) || defined(E5_IS_TMC)
297
+   || defined(E0_IS_TMC) || defined(E1_IS_TMC) || defined(E2_IS_TMC) || defined(E3_IS_TMC) || defined(E4_IS_TMC) || defined(E5_IS_TMC) || defined(E6_IS_TMC) || defined(E7_IS_TMC)
298 298
   #error "[AXIS]_IS_TMC is now [AXIS]_DRIVER_TYPE TMC26X. Please update your Configuration.h."
299 299
 #elif defined(X_IS_TMC26X) || defined(X2_IS_TMC26X) || defined(Y_IS_TMC26X) || defined(Y2_IS_TMC26X) || defined(Z_IS_TMC26X) || defined(Z2_IS_TMC26X) || defined(Z3_IS_TMC26X) \
300
-   || defined(E0_IS_TMC26X) || defined(E1_IS_TMC26X) || defined(E2_IS_TMC26X) || defined(E3_IS_TMC26X) || defined(E4_IS_TMC26X) || defined(E5_IS_TMC26X)
300
+   || defined(E0_IS_TMC26X) || defined(E1_IS_TMC26X) || defined(E2_IS_TMC26X) || defined(E3_IS_TMC26X) || defined(E4_IS_TMC26X) || defined(E5_IS_TMC26X) || defined(E6_IS_TMC26X) || defined(E7_IS_TMC26X)
301 301
   #error "[AXIS]_IS_TMC26X is now [AXIS]_DRIVER_TYPE TMC26X. Please update your Configuration.h."
302 302
 #elif defined(X_IS_TMC2130) || defined(X2_IS_TMC2130) || defined(Y_IS_TMC2130) || defined(Y2_IS_TMC2130) || defined(Z_IS_TMC2130) || defined(Z2_IS_TMC2130) || defined(Z3_IS_TMC2130) \
303
-   || defined(E0_IS_TMC2130) || defined(E1_IS_TMC2130) || defined(E2_IS_TMC2130) || defined(E3_IS_TMC2130) || defined(E4_IS_TMC2130) || defined(E5_IS_TMC2130)
303
+   || defined(E0_IS_TMC2130) || defined(E1_IS_TMC2130) || defined(E2_IS_TMC2130) || defined(E3_IS_TMC2130) || defined(E4_IS_TMC2130) || defined(E5_IS_TMC2130) || defined(E6_IS_TMC2130) || defined(E7_IS_TMC2130)
304 304
   #error "[AXIS]_IS_TMC2130 is now [AXIS]_DRIVER_TYPE TMC2130. Please update your Configuration.h."
305 305
 #elif defined(X_IS_TMC2208) || defined(X2_IS_TMC2208) || defined(Y_IS_TMC2208) || defined(Y2_IS_TMC2208) || defined(Z_IS_TMC2208) || defined(Z2_IS_TMC2208) || defined(Z3_IS_TMC2208) \
306
-   || defined(E0_IS_TMC2208) || defined(E1_IS_TMC2208) || defined(E2_IS_TMC2208) || defined(E3_IS_TMC2208) || defined(E4_IS_TMC2208) || defined(E5_IS_TMC2208)
306
+   || defined(E0_IS_TMC2208) || defined(E1_IS_TMC2208) || defined(E2_IS_TMC2208) || defined(E3_IS_TMC2208) || defined(E4_IS_TMC2208) || defined(E5_IS_TMC2208) || defined(E6_IS_TMC2208) || defined(E7_IS_TMC2208)
307 307
   #error "[AXIS]_IS_TMC2208 is now [AXIS]_DRIVER_TYPE TMC2208. Please update your Configuration.h."
308 308
 #elif defined(X_IS_L6470) || defined(X2_IS_L6470) || defined(Y_IS_L6470) || defined(Y2_IS_L6470) || defined(Z_IS_L6470) || defined(Z2_IS_L6470) || defined(Z3_IS_L6470) \
309
-   || defined(E0_IS_L6470) || defined(E1_IS_L6470) || defined(E2_IS_L6470) || defined(E3_IS_L6470) || defined(E4_IS_L6470) || defined(E5_IS_L6470)
309
+   || defined(E0_IS_L6470) || defined(E1_IS_L6470) || defined(E2_IS_L6470) || defined(E3_IS_L6470) || defined(E4_IS_L6470) || defined(E5_IS_L6470) || defined(E6_IS_L6470) || defined(E7_IS_L6470)
310 310
   #error "[AXIS]_IS_L6470 is now [AXIS]_DRIVER_TYPE L6470. Please update your Configuration.h."
311 311
 #elif defined(AUTOMATIC_CURRENT_CONTROL)
312 312
   #error "AUTOMATIC_CURRENT_CONTROL is now MONITOR_DRIVER_STATUS. Please update your configuration."
@@ -752,8 +752,8 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS
752 752
  */
753 753
 #if EXTRUDERS > 1
754 754
 
755
-  #if EXTRUDERS > 6
756
-    #error "Marlin supports a maximum of 6 EXTRUDERS."
755
+  #if EXTRUDERS > 8
756
+    #error "Marlin supports a maximum of 8 EXTRUDERS."
757 757
   #endif
758 758
 
759 759
   #if ENABLED(HEATERS_PARALLEL)
@@ -1494,6 +1494,10 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS
1494 1494
   #error "TEMP_SENSOR_4 1000 requires HOTEND4_PULLUP_RESISTOR_OHMS, HOTEND4_RESISTANCE_25C_OHMS and HOTEND4_BETA in Configuration_adv.h."
1495 1495
 #elif ENABLED(HEATER_5_USER_THERMISTOR) && !(defined(HOTEND5_PULLUP_RESISTOR_OHMS) && defined(HOTEND5_RESISTANCE_25C_OHMS) && defined(HOTEND5_BETA))
1496 1496
   #error "TEMP_SENSOR_5 1000 requires HOTEND5_PULLUP_RESISTOR_OHMS, HOTEND5_RESISTANCE_25C_OHMS and HOTEND5_BETA in Configuration_adv.h."
1497
+#elif ENABLED(HEATER_6_USER_THERMISTOR) && !(defined(HOTEND6_PULLUP_RESISTOR_OHMS) && defined(HOTEND6_RESISTANCE_25C_OHMS) && defined(HOTEND6_BETA))
1498
+  #error "TEMP_SENSOR_6 1000 requires HOTEND6_PULLUP_RESISTOR_OHMS, HOTEND6_RESISTANCE_25C_OHMS and HOTEND6_BETA in Configuration_adv.h."
1499
+#elif ENABLED(HEATER_7_USER_THERMISTOR) && !(defined(HOTEND7_PULLUP_RESISTOR_OHMS) && defined(HOTEND7_RESISTANCE_25C_OHMS) && defined(HOTEND7_BETA))
1500
+  #error "TEMP_SENSOR_7 1000 requires HOTEND7_PULLUP_RESISTOR_OHMS, HOTEND7_RESISTANCE_25C_OHMS and HOTEND7_BETA in Configuration_adv.h."
1497 1501
 #elif ENABLED(HEATER_BED_USER_THERMISTOR) && !(defined(BED_PULLUP_RESISTOR_OHMS) && defined(BED_RESISTANCE_25C_OHMS) && defined(BED_BETA))
1498 1502
   #error "TEMP_SENSOR_BED 1000 requires BED_PULLUP_RESISTOR_OHMS, BED_RESISTANCE_25C_OHMS and BED_BETA in Configuration_adv.h."
1499 1503
 #elif ENABLED(HEATER_CHAMBER_USER_THERMISTOR) && !(defined(CHAMBER_PULLUP_RESISTOR_OHMS) && defined(CHAMBER_RESISTANCE_25C_OHMS) && defined(CHAMBER_BETA))
@@ -1564,13 +1568,45 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS
1564 1568
           #elif !PIN_EXISTS(TEMP_5)
1565 1569
             #error "TEMP_5_PIN not defined for this board."
1566 1570
           #endif
1571
+          #if HOTENDS > 6
1572
+            #if TEMP_SENSOR_6 == 0
1573
+              #error "TEMP_SENSOR_6 is required with 6 HOTENDS."
1574
+            #elif !HAS_HEATER_6
1575
+              #error "HEATER_6_PIN not defined for this board."
1576
+            #elif !PIN_EXISTS(TEMP_6)
1577
+              #error "TEMP_6_PIN not defined for this board."
1578
+            #endif
1579
+            #if HOTENDS > 7
1580
+              #if TEMP_SENSOR_7 == 0
1581
+                #error "TEMP_SENSOR_7 is required with 7 HOTENDS."
1582
+              #elif !HAS_HEATER_7
1583
+                #error "HEATER_7_PIN not defined for this board."
1584
+              #elif !PIN_EXISTS(TEMP_7)
1585
+                #error "TEMP_7_PIN not defined for this board."
1586
+              #endif
1587
+            #elif TEMP_SENSOR_7 != 0
1588
+              #error "TEMP_SENSOR_7 shouldn't be set with only 7 HOTENDS."
1589
+            #endif
1590
+          #elif TEMP_SENSOR_6 != 0
1591
+            #error "TEMP_SENSOR_6 shouldn't be set with only 6 HOTENDS."
1592
+          #elif TEMP_SENSOR_7 != 0
1593
+            #error "TEMP_SENSOR_7 shouldn't be set with only 6 HOTENDS."
1594
+          #endif
1567 1595
         #elif TEMP_SENSOR_5 != 0
1568 1596
           #error "TEMP_SENSOR_5 shouldn't be set with only 5 HOTENDS."
1597
+        #elif TEMP_SENSOR_6 != 0
1598
+          #error "TEMP_SENSOR_6 shouldn't be set with only 5 HOTENDS."
1599
+        #elif TEMP_SENSOR_7 != 0
1600
+          #error "TEMP_SENSOR_7 shouldn't be set with only 5 HOTENDS."
1569 1601
         #endif
1570 1602
       #elif TEMP_SENSOR_4 != 0
1571 1603
         #error "TEMP_SENSOR_4 shouldn't be set with only 4 HOTENDS."
1572 1604
       #elif TEMP_SENSOR_5 != 0
1573 1605
         #error "TEMP_SENSOR_5 shouldn't be set with only 4 HOTENDS."
1606
+      #elif TEMP_SENSOR_6 != 0
1607
+        #error "TEMP_SENSOR_6 shouldn't be set with only 4 HOTENDS."
1608
+      #elif TEMP_SENSOR_7 != 0
1609
+        #error "TEMP_SENSOR_7 shouldn't be set with only 4 HOTENDS."
1574 1610
       #endif
1575 1611
     #elif TEMP_SENSOR_3 != 0
1576 1612
       #error "TEMP_SENSOR_3 shouldn't be set with only 3 HOTENDS."
@@ -1578,6 +1614,10 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS
1578 1614
       #error "TEMP_SENSOR_4 shouldn't be set with only 3 HOTENDS."
1579 1615
     #elif TEMP_SENSOR_5 != 0
1580 1616
       #error "TEMP_SENSOR_5 shouldn't be set with only 3 HOTENDS."
1617
+    #elif TEMP_SENSOR_6 != 0
1618
+      #error "TEMP_SENSOR_6 shouldn't be set with only 3 HOTENDS."
1619
+    #elif TEMP_SENSOR_7 != 0
1620
+      #error "TEMP_SENSOR_7 shouldn't be set with only 3 HOTENDS."
1581 1621
     #endif
1582 1622
   #elif TEMP_SENSOR_2 != 0
1583 1623
     #error "TEMP_SENSOR_2 shouldn't be set with only 2 HOTENDS."
@@ -1587,6 +1627,10 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS
1587 1627
     #error "TEMP_SENSOR_4 shouldn't be set with only 2 HOTENDS."
1588 1628
   #elif TEMP_SENSOR_5 != 0
1589 1629
     #error "TEMP_SENSOR_5 shouldn't be set with only 2 HOTENDS."
1630
+  #elif TEMP_SENSOR_6 != 0
1631
+    #error "TEMP_SENSOR_6 shouldn't be set with only 2 HOTENDS."
1632
+  #elif TEMP_SENSOR_7 != 0
1633
+    #error "TEMP_SENSOR_7 shouldn't be set with only 2 HOTENDS."
1590 1634
   #endif
1591 1635
 #elif TEMP_SENSOR_1 != 0 && DISABLED(TEMP_SENSOR_1_AS_REDUNDANT)
1592 1636
   #error "TEMP_SENSOR_1 shouldn't be set with only 1 HOTEND."
@@ -1598,6 +1642,10 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS
1598 1642
   #error "TEMP_SENSOR_4 shouldn't be set with only 1 HOTEND."
1599 1643
 #elif TEMP_SENSOR_5 != 0
1600 1644
   #error "TEMP_SENSOR_5 shouldn't be set with only 1 HOTEND."
1645
+#elif TEMP_SENSOR_6 != 0
1646
+  #error "TEMP_SENSOR_6 shouldn't be set with only 1 HOTEND."
1647
+#elif TEMP_SENSOR_7 != 0
1648
+  #error "TEMP_SENSOR_7 shouldn't be set with only 1 HOTEND."
1601 1649
 #endif
1602 1650
 
1603 1651
 #if TEMP_SENSOR_PROBE
@@ -1680,6 +1728,16 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS
1680 1728
               #if !(PIN_EXISTS(E5_STEP, E5_DIR) && HAS_E5_ENABLE)
1681 1729
                 #error "E5_STEP_PIN, E5_DIR_PIN, or E5_ENABLE_PIN not defined for this board."
1682 1730
               #endif
1731
+              #if E_STEPPERS > 6
1732
+                #if !(PIN_EXISTS(E6_STEP, E6_DIR) && HAS_E6_ENABLE)
1733
+                  #error "E6_STEP_PIN, E6_DIR_PIN, or E6_ENABLE_PIN not defined for this board."
1734
+                #endif
1735
+                #if E_STEPPERS > 7
1736
+                  #if !(PIN_EXISTS(E7_STEP, E7_DIR) && HAS_E7_ENABLE)
1737
+                    #error "E7_STEP_PIN, E7_DIR_PIN, or E7_ENABLE_PIN not defined for this board."
1738
+                  #endif
1739
+                #endif // E_STEPPERS > 7
1740
+              #endif // E_STEPPERS > 6
1683 1741
             #endif // E_STEPPERS > 5
1684 1742
           #endif // E_STEPPERS > 4
1685 1743
         #endif // E_STEPPERS > 3
@@ -2008,6 +2066,10 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS
2008 2066
   #error "An SPI driven TMC driver on E4 requires E4_CS_PIN."
2009 2067
 #elif INVALID_TMC_SPI(E5)
2010 2068
   #error "An SPI driven TMC driver on E5 requires E5_CS_PIN."
2069
+#elif INVALID_TMC_SPI(E6)
2070
+  #error "An SPI driven TMC driver on E6 requires E6_CS_PIN."
2071
+#elif INVALID_TMC_SPI(E7)
2072
+  #error "An SPI driven TMC driver on E7 requires E7_CS_PIN."
2011 2073
 #endif
2012 2074
 #undef INVALID_TMC_SPI
2013 2075
 
@@ -2041,6 +2103,10 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS
2041 2103
   #error "TMC2208 or TMC2209 on E4 requires E4_HARDWARE_SERIAL or E4_SERIAL_(RX|TX)_PIN."
2042 2104
 #elif INVALID_TMC_UART(E5)
2043 2105
   #error "TMC2208 or TMC2209 on E5 requires E5_HARDWARE_SERIAL or E5_SERIAL_(RX|TX)_PIN."
2106
+#elif INVALID_TMC_UART(E6)
2107
+  #error "TMC2208 or TMC2209 on E6 requires E6_HARDWARE_SERIAL or E6_SERIAL_(RX|TX)_PIN."
2108
+#elif INVALID_TMC_UART(E7)
2109
+  #error "TMC2208 or TMC2209 on E7 requires E7_HARDWARE_SERIAL or E7_SERIAL_(RX|TX)_PIN."
2044 2110
 #endif
2045 2111
 #undef INVALID_TMC_UART
2046 2112
 
@@ -2192,7 +2258,8 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS
2192 2258
     || (IN_CHAIN(Z3) && !PIN_EXISTS(Z3_CS)) || (IN_CHAIN(E0) && !PIN_EXISTS(E0_CS)) \
2193 2259
     || (IN_CHAIN(E1) && !PIN_EXISTS(E1_CS)) || (IN_CHAIN(E2) && !PIN_EXISTS(E2_CS)) \
2194 2260
     || (IN_CHAIN(E3) && !PIN_EXISTS(E3_CS)) || (IN_CHAIN(E4) && !PIN_EXISTS(E4_CS)) \
2195
-    || (IN_CHAIN(E5) && !PIN_EXISTS(E5_CS))
2261
+    || (IN_CHAIN(E5) && !PIN_EXISTS(E5_CS)) || (IN_CHAIN(E6) && !PIN_EXISTS(E6_CS)) \
2262
+    || (IN_CHAIN(E7) && !PIN_EXISTS(E7_CS))
2196 2263
     #error "All chained TMC drivers need a CS pin."
2197 2264
   #else
2198 2265
     #if IN_CHAIN(X)
@@ -2221,6 +2288,10 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS
2221 2288
       #define CS_COMPARE E4_CS_PIN
2222 2289
     #elif IN_CHAIN(E5)
2223 2290
       #define CS_COMPARE E5_CS_PIN
2291
+    #elif IN_CHAIN(E6)
2292
+      #define CS_COMPARE E6_CS_PIN
2293
+    #elif IN_CHAIN(E7)
2294
+      #define CS_COMPARE E7_CS_PIN
2224 2295
     #endif
2225 2296
     #if  (IN_CHAIN(X)  && X_CS_PIN  != CS_COMPARE) || (IN_CHAIN(Y)  && Y_CS_PIN  != CS_COMPARE) \
2226 2297
       || (IN_CHAIN(Z)  && Z_CS_PIN  != CS_COMPARE) || (IN_CHAIN(X2) && X2_CS_PIN != CS_COMPARE) \
@@ -2228,7 +2299,8 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS
2228 2299
       || (IN_CHAIN(Z3) && Z3_CS_PIN != CS_COMPARE) || (IN_CHAIN(E0) && E0_CS_PIN != CS_COMPARE) \
2229 2300
       || (IN_CHAIN(E1) && E1_CS_PIN != CS_COMPARE) || (IN_CHAIN(E2) && E2_CS_PIN != CS_COMPARE) \
2230 2301
       || (IN_CHAIN(E3) && E3_CS_PIN != CS_COMPARE) || (IN_CHAIN(E4) && E4_CS_PIN != CS_COMPARE) \
2231
-      || (IN_CHAIN(E5) && E5_CS_PIN != CS_COMPARE)
2302
+      || (IN_CHAIN(E5) && E5_CS_PIN != CS_COMPARE) || (IN_CHAIN(E6) && E6_CS_PIN != CS_COMPARE) \
2303
+      || (IN_CHAIN(E7) && E7_CS_PIN != CS_COMPARE)
2232 2304
       #error "All chained TMC drivers must use the same CS pin."
2233 2305
     #endif
2234 2306
   #endif
@@ -2521,12 +2593,26 @@ static_assert(   _ARR_TEST(3,0) && _ARR_TEST(3,1) && _ARR_TEST(3,2)
2521 2593
       #error "SPINDLE_LASER_PWM_PIN conflicts with E4_AUTO_FAN_PIN."
2522 2594
     #elif _PIN_CONFLICT(E5_AUTO_FAN)
2523 2595
       #error "SPINDLE_LASER_PWM_PIN conflicts with E5_AUTO_FAN_PIN."
2596
+    #elif _PIN_CONFLICT(E6_AUTO_FAN)
2597
+      #error "SPINDLE_LASER_PWM_PIN conflicts with E6_AUTO_FAN_PIN."
2598
+    #elif _PIN_CONFLICT(E7_AUTO_FAN)
2599
+      #error "SPINDLE_LASER_PWM_PIN conflicts with E7_AUTO_FAN_PIN."
2524 2600
     #elif _PIN_CONFLICT(FAN)
2525 2601
       #error "SPINDLE_LASER_PWM_PIN conflicts with FAN_PIN."
2526 2602
     #elif _PIN_CONFLICT(FAN1)
2527 2603
       #error "SPINDLE_LASER_PWM_PIN conflicts with FAN1_PIN."
2528 2604
     #elif _PIN_CONFLICT(FAN2)
2529 2605
       #error "SPINDLE_LASER_PWM_PIN conflicts with FAN2_PIN."
2606
+    #elif _PIN_CONFLICT(FAN3)
2607
+      #error "SPINDLE_LASER_PWM_PIN conflicts with FAN3_PIN."
2608
+    #elif _PIN_CONFLICT(FAN4)
2609
+      #error "SPINDLE_LASER_PWM_PIN conflicts with FAN4_PIN."
2610
+    #elif _PIN_CONFLICT(FAN5)
2611
+      #error "SPINDLE_LASER_PWM_PIN conflicts with FAN5_PIN."
2612
+    #elif _PIN_CONFLICT(FAN6)
2613
+      #error "SPINDLE_LASER_PWM_PIN conflicts with FAN6_PIN."
2614
+    #elif _PIN_CONFLICT(FAN7)
2615
+      #error "SPINDLE_LASER_PWM_PIN conflicts with FAN7_PIN."
2530 2616
     #elif _PIN_CONFLICT(CONTROLLERFAN)
2531 2617
       #error "SPINDLE_LASER_PWM_PIN conflicts with CONTROLLERFAN_PIN."
2532 2618
     #elif _PIN_CONFLICT(MOTOR_CURRENT_PWM_XY)

+ 15
- 0
Marlin/src/lcd/HD44780/ultralcd_HD44780.cpp View File

@@ -1092,6 +1092,21 @@ void MarlinUI::draw_status_screen() {
1092 1092
           #if HAS_FAN2
1093 1093
             || thermalManager.fan_speed[2]
1094 1094
           #endif
1095
+          #if HAS_FAN3
1096
+            || thermalManager.fan_speed[3]
1097
+          #endif
1098
+          #if HAS_FAN4
1099
+            || thermalManager.fan_speed[4]
1100
+          #endif
1101
+          #if HAS_FAN5
1102
+            || thermalManager.fan_speed[5]
1103
+          #endif
1104
+          #if HAS_FAN6
1105
+            || thermalManager.fan_speed[6]
1106
+          #endif
1107
+          #if HAS_FAN7
1108
+            || thermalManager.fan_speed[7]
1109
+          #endif
1095 1110
         ) leds |= LED_C;
1096 1111
       #endif // FAN_COUNT > 0
1097 1112
 

+ 2
- 2
Marlin/src/lcd/extensible_ui/ui_api.cpp View File

@@ -912,7 +912,7 @@ namespace ExtUI {
912 912
     #endif
913 913
       {
914 914
         #if HOTENDS
915
-          static constexpr int16_t heater_maxtemp[HOTENDS] = ARRAY_BY_HOTENDS(HEATER_0_MAXTEMP, HEATER_1_MAXTEMP, HEATER_2_MAXTEMP, HEATER_3_MAXTEMP, HEATER_4_MAXTEMP, HEATER_5_MAXTEMP);
915
+          static constexpr int16_t heater_maxtemp[HOTENDS] = ARRAY_BY_HOTENDS(HEATER_0_MAXTEMP, HEATER_1_MAXTEMP, HEATER_2_MAXTEMP, HEATER_3_MAXTEMP, HEATER_4_MAXTEMP, HEATER_5_MAXTEMP, HEATER_6_MAXTEMP, HEATER_7_MAXTEMP);
916 916
           const int16_t e = heater - H0;
917 917
           thermalManager.setTargetHotend(LROUND(constrain(value, 0, heater_maxtemp[e] - 15)), e);
918 918
         #endif
@@ -924,7 +924,7 @@ namespace ExtUI {
924 924
       value *= TOUCH_UI_LCD_TEMP_SCALING;
925 925
     #endif
926 926
     #if HOTENDS
927
-      constexpr int16_t heater_maxtemp[HOTENDS] = ARRAY_BY_HOTENDS(HEATER_0_MAXTEMP, HEATER_1_MAXTEMP, HEATER_2_MAXTEMP, HEATER_3_MAXTEMP, HEATER_4_MAXTEMP, HEATER_5_MAXTEMP);
927
+      constexpr int16_t heater_maxtemp[HOTENDS] = ARRAY_BY_HOTENDS(HEATER_0_MAXTEMP, HEATER_1_MAXTEMP, HEATER_2_MAXTEMP, HEATER_3_MAXTEMP, HEATER_4_MAXTEMP, HEATER_5_MAXTEMP, HEATER_6_MAXTEMP, HEATER_7_MAXTEMP);
928 928
       const int16_t e = extruder - E0;
929 929
       enableHeater(extruder);
930 930
       thermalManager.setTargetHotend(LROUND(constrain(value, 0, heater_maxtemp[e] - 15)), e);

+ 1
- 1
Marlin/src/lcd/extensible_ui/ui_api.h View File

@@ -55,7 +55,7 @@ namespace ExtUI {
55 55
   enum axis_t     : uint8_t { X, Y, Z };
56 56
   enum extruder_t : uint8_t { E0, E1, E2, E3, E4, E5 };
57 57
   enum heater_t   : uint8_t { H0, H1, H2, H3, H4, H5, BED, CHAMBER };
58
-  enum fan_t      : uint8_t { FAN0, FAN1, FAN2, FAN3, FAN4, FAN5 };
58
+  enum fan_t      : uint8_t { FAN0, FAN1, FAN2, FAN3, FAN4, FAN5, FAN6, FAN7 };
59 59
   enum result_t   : uint8_t { PID_BAD_EXTRUDER_NUM, PID_TEMP_TOO_HIGH, PID_TUNING_TIMEOUT, PID_DONE };
60 60
 
61 61
   constexpr uint8_t extruderCount = EXTRUDERS;

+ 1
- 1
Marlin/src/lcd/language/language_an.h View File

@@ -93,7 +93,7 @@ namespace Language_an {
93 93
   PROGMEM Language_Str MSG_NOZZLE_N                        = _UxGT("Boquilla ~");
94 94
   PROGMEM Language_Str MSG_BED                             = _UxGT("Base");
95 95
   PROGMEM Language_Str MSG_FAN_SPEED                       = _UxGT("Ixoriador");
96
-  PROGMEM Language_Str MSG_FAN_SPEED_N                     = _UxGT("Ixoriador =");
96
+  PROGMEM Language_Str MSG_FAN_SPEED_N                     = _UxGT("Ixoriador ~");
97 97
   PROGMEM Language_Str MSG_FLOW                            = _UxGT("Fluxo");
98 98
   PROGMEM Language_Str MSG_FLOW_N                          = _UxGT("Fluxo ~");
99 99
   PROGMEM Language_Str MSG_CONTROL                         = _UxGT("Control");

+ 1
- 1
Marlin/src/lcd/language/language_bg.h View File

@@ -83,7 +83,7 @@ namespace Language_bg {
83 83
   PROGMEM Language_Str MSG_NOZZLE_N                        = " " LCD_STR_THERMOMETER _UxGT(" Дюза ~");
84 84
   PROGMEM Language_Str MSG_BED                             = " " LCD_STR_THERMOMETER _UxGT(" Легло");
85 85
   PROGMEM Language_Str MSG_FAN_SPEED                       = _UxGT("Вентилатор");
86
-  PROGMEM Language_Str MSG_FAN_SPEED_N                     = _UxGT("Вентилатор =");
86
+  PROGMEM Language_Str MSG_FAN_SPEED_N                     = _UxGT("Вентилатор ~");
87 87
   PROGMEM Language_Str MSG_FLOW                            = _UxGT("Поток");
88 88
   PROGMEM Language_Str MSG_FLOW_N                          = _UxGT("Поток ~");
89 89
   PROGMEM Language_Str MSG_CONTROL                         = _UxGT("Управление");

+ 1
- 1
Marlin/src/lcd/language/language_ca.h View File

@@ -94,7 +94,7 @@ namespace Language_ca {
94 94
   PROGMEM Language_Str MSG_NOZZLE_N                        = _UxGT("Nozzle ~");
95 95
   PROGMEM Language_Str MSG_BED                             = _UxGT("Llit");
96 96
   PROGMEM Language_Str MSG_FAN_SPEED                       = _UxGT("Vel. Ventilador");
97
-  PROGMEM Language_Str MSG_FAN_SPEED_N                     = _UxGT("Vel. Ventilador =");
97
+  PROGMEM Language_Str MSG_FAN_SPEED_N                     = _UxGT("Vel. Ventilador ~");
98 98
   PROGMEM Language_Str MSG_FLOW                            = _UxGT("Flux");
99 99
   PROGMEM Language_Str MSG_FLOW_N                          = _UxGT("Flux ~");
100 100
   PROGMEM Language_Str MSG_VTRAV_MIN                       = _UxGT("VViatge min");

+ 3
- 3
Marlin/src/lcd/language/language_cz.h View File

@@ -251,10 +251,10 @@ namespace Language_cz {
251 251
   PROGMEM Language_Str MSG_BED                             = _UxGT("Podložka");
252 252
   PROGMEM Language_Str MSG_CHAMBER                         = _UxGT("Komora");
253 253
   PROGMEM Language_Str MSG_FAN_SPEED                       = _UxGT("Rychlost vent.");
254
-  PROGMEM Language_Str MSG_FAN_SPEED_N                     = _UxGT("Rychlost vent. =");
255
-  PROGMEM Language_Str MSG_STORED_FAN_N                    = _UxGT("Ulož. vent. =");
254
+  PROGMEM Language_Str MSG_FAN_SPEED_N                     = _UxGT("Rychlost vent. ~");
255
+  PROGMEM Language_Str MSG_STORED_FAN_N                    = _UxGT("Ulož. vent. ~");
256 256
   PROGMEM Language_Str MSG_EXTRA_FAN_SPEED                 = _UxGT("Rychlost ex. vent.");
257
-  PROGMEM Language_Str MSG_EXTRA_FAN_SPEED_N               = _UxGT("Rychlost ex. vent. =");
257
+  PROGMEM Language_Str MSG_EXTRA_FAN_SPEED_N               = _UxGT("Rychlost ex. vent. ~");
258 258
   PROGMEM Language_Str MSG_FLOW                            = _UxGT("Průtok");
259 259
   PROGMEM Language_Str MSG_FLOW_N                          = _UxGT("Průtok ~");
260 260
   PROGMEM Language_Str MSG_CONTROL                         = _UxGT("Ovládaní");

+ 1
- 1
Marlin/src/lcd/language/language_da.h View File

@@ -84,7 +84,7 @@ namespace Language_da {
84 84
 
85 85
   PROGMEM Language_Str MSG_BED                             = _UxGT("Plade");
86 86
   PROGMEM Language_Str MSG_FAN_SPEED                       = _UxGT("Blæser hastighed");
87
-  PROGMEM Language_Str MSG_FAN_SPEED_N                     = _UxGT("Blæser hastighed =");
87
+  PROGMEM Language_Str MSG_FAN_SPEED_N                     = _UxGT("Blæser hastighed ~");
88 88
   PROGMEM Language_Str MSG_CONTROL                         = _UxGT("Kontrol");
89 89
   PROGMEM Language_Str MSG_MIN                             = _UxGT(" \002 Min");
90 90
   PROGMEM Language_Str MSG_MAX                             = _UxGT(" \002 Max");

+ 1
- 1
Marlin/src/lcd/language/language_el.h View File

@@ -91,7 +91,7 @@ namespace Language_el {
91 91
   PROGMEM Language_Str MSG_NOZZLE_N                        = _UxGT("Ακροφύσιο ~");
92 92
   PROGMEM Language_Str MSG_BED                             = _UxGT("Κλίνη");
93 93
   PROGMEM Language_Str MSG_FAN_SPEED                       = _UxGT("Ταχύτητα ανεμιστήρα");
94
-  PROGMEM Language_Str MSG_FAN_SPEED_N                     = _UxGT("Ταχύτητα ανεμιστήρα =");
94
+  PROGMEM Language_Str MSG_FAN_SPEED_N                     = _UxGT("Ταχύτητα ανεμιστήρα ~");
95 95
   PROGMEM Language_Str MSG_FLOW                            = _UxGT("Ροή");
96 96
   PROGMEM Language_Str MSG_FLOW_N                          = _UxGT("Ροή ~");
97 97
   PROGMEM Language_Str MSG_CONTROL                         = _UxGT("Έλεγχος");

+ 1
- 1
Marlin/src/lcd/language/language_el_gr.h View File

@@ -92,7 +92,7 @@ namespace Language_el_gr {
92 92
   PROGMEM Language_Str MSG_NOZZLE_N                        = _UxGT("Ακροφύσιο ~");
93 93
   PROGMEM Language_Str MSG_BED                             = _UxGT("Κλίνη");
94 94
   PROGMEM Language_Str MSG_FAN_SPEED                       = _UxGT("Ταχύτητα ανεμιστήρα");
95
-  PROGMEM Language_Str MSG_FAN_SPEED_N                     = _UxGT("Ταχύτητα ανεμιστήρα =");
95
+  PROGMEM Language_Str MSG_FAN_SPEED_N                     = _UxGT("Ταχύτητα ανεμιστήρα ~");
96 96
   PROGMEM Language_Str MSG_FLOW                            = _UxGT("Ροή");
97 97
   PROGMEM Language_Str MSG_FLOW_N                          = _UxGT("Ροή ~");
98 98
   PROGMEM Language_Str MSG_CONTROL                         = _UxGT("Έλεγχος");

+ 3
- 3
Marlin/src/lcd/language/language_en.h View File

@@ -242,10 +242,10 @@ namespace Language_en {
242 242
   PROGMEM Language_Str MSG_BED                             = _UxGT("Bed");
243 243
   PROGMEM Language_Str MSG_CHAMBER                         = _UxGT("Enclosure");
244 244
   PROGMEM Language_Str MSG_FAN_SPEED                       = _UxGT("Fan Speed");
245
-  PROGMEM Language_Str MSG_FAN_SPEED_N                     = _UxGT("Fan Speed =");
246
-  PROGMEM Language_Str MSG_STORED_FAN_N                    = _UxGT("Stored Fan =");
245
+  PROGMEM Language_Str MSG_FAN_SPEED_N                     = _UxGT("Fan Speed ~");
246
+  PROGMEM Language_Str MSG_STORED_FAN_N                    = _UxGT("Stored Fan ~");
247 247
   PROGMEM Language_Str MSG_EXTRA_FAN_SPEED                 = _UxGT("Extra Fan Speed");
248
-  PROGMEM Language_Str MSG_EXTRA_FAN_SPEED_N               = _UxGT("Extra Fan Speed =");
248
+  PROGMEM Language_Str MSG_EXTRA_FAN_SPEED_N               = _UxGT("Extra Fan Speed ~");
249 249
   PROGMEM Language_Str MSG_FLOW                            = _UxGT("Flow");
250 250
   PROGMEM Language_Str MSG_FLOW_N                          = _UxGT("Flow ~");
251 251
   PROGMEM Language_Str MSG_CONTROL                         = _UxGT("Control");

+ 2
- 2
Marlin/src/lcd/language/language_es.h View File

@@ -240,9 +240,9 @@ namespace Language_es {
240 240
   PROGMEM Language_Str MSG_BED                             = _UxGT("Cama");
241 241
   PROGMEM Language_Str MSG_CHAMBER                         = _UxGT("Recinto");
242 242
   PROGMEM Language_Str MSG_FAN_SPEED                       = _UxGT("Ventilador");
243
-  PROGMEM Language_Str MSG_FAN_SPEED_N                     = _UxGT("Ventilador =");
243
+  PROGMEM Language_Str MSG_FAN_SPEED_N                     = _UxGT("Ventilador ~");
244 244
   PROGMEM Language_Str MSG_EXTRA_FAN_SPEED                 = _UxGT("Vel. Ext. ventilador");
245
-  PROGMEM Language_Str MSG_EXTRA_FAN_SPEED_N               = _UxGT("Vel. Ext. ventilador =");
245
+  PROGMEM Language_Str MSG_EXTRA_FAN_SPEED_N               = _UxGT("Vel. Ext. ventilador ~");
246 246
   PROGMEM Language_Str MSG_FLOW                            = _UxGT("Flujo");
247 247
   PROGMEM Language_Str MSG_FLOW_N                          = _UxGT("Flujo ~");
248 248
   PROGMEM Language_Str MSG_CONTROL                         = _UxGT("Control");

+ 2
- 2
Marlin/src/lcd/language/language_eu.h View File

@@ -147,9 +147,9 @@ namespace Language_eu {
147 147
   PROGMEM Language_Str MSG_NOZZLE_N                        = _UxGT("Pita ~");
148 148
   PROGMEM Language_Str MSG_BED                             = _UxGT("Ohea");
149 149
   PROGMEM Language_Str MSG_FAN_SPEED                       = _UxGT("Haizagailu abiadura");
150
-  PROGMEM Language_Str MSG_FAN_SPEED_N                     = _UxGT("Haizagailu abiadura =");
150
+  PROGMEM Language_Str MSG_FAN_SPEED_N                     = _UxGT("Haizagailu abiadura ~");
151 151
   PROGMEM Language_Str MSG_EXTRA_FAN_SPEED                 = _UxGT("Haiz.gehig. abiadura");
152
-  PROGMEM Language_Str MSG_EXTRA_FAN_SPEED_N               = _UxGT("Haiz.gehig. abiadura =");
152
+  PROGMEM Language_Str MSG_EXTRA_FAN_SPEED_N               = _UxGT("Haiz.gehig. abiadura ~");
153 153
   PROGMEM Language_Str MSG_FLOW                            = _UxGT("Fluxua");
154 154
   PROGMEM Language_Str MSG_FLOW_N                          = _UxGT("Fluxua ~");
155 155
   PROGMEM Language_Str MSG_CONTROL                         = _UxGT("Kontrola");

+ 1
- 1
Marlin/src/lcd/language/language_fi.h View File

@@ -79,7 +79,7 @@ namespace Language_fi {
79 79
   PROGMEM Language_Str MSG_NOZZLE_N                        = _UxGT("Suutin ~");
80 80
   PROGMEM Language_Str MSG_BED                             = _UxGT("Alusta");
81 81
   PROGMEM Language_Str MSG_FAN_SPEED                       = _UxGT("Tuul. nopeus");
82
-  PROGMEM Language_Str MSG_FAN_SPEED_N                     = _UxGT("Tuul. nopeus =");
82
+  PROGMEM Language_Str MSG_FAN_SPEED_N                     = _UxGT("Tuul. nopeus ~");
83 83
   PROGMEM Language_Str MSG_FLOW                            = _UxGT("Virtaus");
84 84
   PROGMEM Language_Str MSG_FLOW_N                          = _UxGT("Virtaus ~");
85 85
   PROGMEM Language_Str MSG_CONTROL                         = _UxGT("Kontrolli");

+ 3
- 3
Marlin/src/lcd/language/language_fr.h View File

@@ -235,10 +235,10 @@ namespace Language_fr {
235 235
   PROGMEM Language_Str MSG_BED                             = _UxGT("Lit");
236 236
   PROGMEM Language_Str MSG_CHAMBER                         = _UxGT("Caisson");
237 237
   PROGMEM Language_Str MSG_FAN_SPEED                       = _UxGT("Vit.  ventil.  "); // 15 car. max
238
-  PROGMEM Language_Str MSG_FAN_SPEED_N                     = _UxGT("Vit.  ventil. =");
239
-  PROGMEM Language_Str MSG_STORED_FAN_N                    = _UxGT("Vit.  enreg.  =");
238
+  PROGMEM Language_Str MSG_FAN_SPEED_N                     = _UxGT("Vit.  ventil. ~");
239
+  PROGMEM Language_Str MSG_STORED_FAN_N                    = _UxGT("Vit.  enreg.  ~");
240 240
   PROGMEM Language_Str MSG_EXTRA_FAN_SPEED                 = _UxGT("Extra ventil.  ");
241
-  PROGMEM Language_Str MSG_EXTRA_FAN_SPEED_N               = _UxGT("Extra ventil. =");
241
+  PROGMEM Language_Str MSG_EXTRA_FAN_SPEED_N               = _UxGT("Extra ventil. ~");
242 242
 
243 243
   PROGMEM Language_Str MSG_FLOW                            = _UxGT("Flux");
244 244
   PROGMEM Language_Str MSG_FLOW_N                          = _UxGT("Flux ~");

+ 3
- 3
Marlin/src/lcd/language/language_it.h View File

@@ -240,10 +240,10 @@ namespace Language_it {
240 240
   PROGMEM Language_Str MSG_BED                             = _UxGT("Piatto");
241 241
   PROGMEM Language_Str MSG_CHAMBER                         = _UxGT("Camera");
242 242
   PROGMEM Language_Str MSG_FAN_SPEED                       = _UxGT("Vel. ventola");     // Max 15 characters
243
-  PROGMEM Language_Str MSG_FAN_SPEED_N                     = _UxGT("Vel. ventola =");   // Max 15 characters
244
-  PROGMEM Language_Str MSG_STORED_FAN_N                    = _UxGT("Ventola mem. =");   // Max 15 characters
243
+  PROGMEM Language_Str MSG_FAN_SPEED_N                     = _UxGT("Vel. ventola ~");   // Max 15 characters
244
+  PROGMEM Language_Str MSG_STORED_FAN_N                    = _UxGT("Ventola mem. ~");   // Max 15 characters
245 245
   PROGMEM Language_Str MSG_EXTRA_FAN_SPEED                 = _UxGT("Extra vel.vent.");  // Max 15 characters
246
-  PROGMEM Language_Str MSG_EXTRA_FAN_SPEED_N               = _UxGT("Extra v.vent. =");  // Max 15 characters
246
+  PROGMEM Language_Str MSG_EXTRA_FAN_SPEED_N               = _UxGT("Extra v.vent. ~");  // Max 15 characters
247 247
   PROGMEM Language_Str MSG_FLOW                            = _UxGT("Flusso");
248 248
   PROGMEM Language_Str MSG_FLOW_N                          = _UxGT("Flusso ~");
249 249
   PROGMEM Language_Str MSG_CONTROL                         = _UxGT("Controllo");

+ 2
- 2
Marlin/src/lcd/language/language_ko_KR.h View File

@@ -77,9 +77,9 @@ namespace Language_ko_KR {
77 77
   PROGMEM Language_Str MSG_NOZZLE_N                        = _UxGT("노즐 ~");
78 78
   PROGMEM Language_Str MSG_BED                             = _UxGT("베드");
79 79
   PROGMEM Language_Str MSG_FAN_SPEED                       = _UxGT("펜 속도");
80
-  PROGMEM Language_Str MSG_FAN_SPEED_N                     = _UxGT("펜 속도 =");
80
+  PROGMEM Language_Str MSG_FAN_SPEED_N                     = _UxGT("펜 속도 ~");
81 81
   PROGMEM Language_Str MSG_EXTRA_FAN_SPEED                 = _UxGT("엑스트라 펜 속도");
82
-  PROGMEM Language_Str MSG_EXTRA_FAN_SPEED_N               = _UxGT("엑스트라 펜 속도 =");
82
+  PROGMEM Language_Str MSG_EXTRA_FAN_SPEED_N               = _UxGT("엑스트라 펜 속도 ~");
83 83
   PROGMEM Language_Str MSG_TEMPERATURE                     = _UxGT("온도");
84 84
   PROGMEM Language_Str MSG_MOTION                          = _UxGT("동작");
85 85
   PROGMEM Language_Str MSG_STORE_EEPROM                    = _UxGT("설정 저장하기");

+ 1
- 1
Marlin/src/lcd/language/language_nl.h View File

@@ -99,7 +99,7 @@ namespace Language_nl {
99 99
   PROGMEM Language_Str MSG_NOZZLE_N                        = _UxGT("Nozzle ~");
100 100
   PROGMEM Language_Str MSG_BED                             = _UxGT("Bed");
101 101
   PROGMEM Language_Str MSG_FAN_SPEED                       = _UxGT("Fan snelheid");
102
-  PROGMEM Language_Str MSG_FAN_SPEED_N                     = _UxGT("Fan snelheid =");
102
+  PROGMEM Language_Str MSG_FAN_SPEED_N                     = _UxGT("Fan snelheid ~");
103 103
   PROGMEM Language_Str MSG_FLOW                            = _UxGT("Flow");
104 104
   PROGMEM Language_Str MSG_FLOW_N                          = _UxGT("Flow ~");
105 105
   PROGMEM Language_Str MSG_CONTROL                         = _UxGT("Control");

+ 2
- 2
Marlin/src/lcd/language/language_pl.h View File

@@ -240,9 +240,9 @@ namespace Language_pl {
240 240
   PROGMEM Language_Str MSG_BED                             = _UxGT("Stół");
241 241
   PROGMEM Language_Str MSG_CHAMBER                         = _UxGT("Obudowa");
242 242
   PROGMEM Language_Str MSG_FAN_SPEED                       = _UxGT("Obroty wiatraka");
243
-  PROGMEM Language_Str MSG_FAN_SPEED_N                     = _UxGT("Obroty wiatraka =");
243
+  PROGMEM Language_Str MSG_FAN_SPEED_N                     = _UxGT("Obroty wiatraka ~");
244 244
   PROGMEM Language_Str MSG_EXTRA_FAN_SPEED                 = _UxGT("Obroty dodatkowego wiatraka");
245
-  PROGMEM Language_Str MSG_EXTRA_FAN_SPEED_N               = _UxGT("Obroty dodatkowego wiatraka =");
245
+  PROGMEM Language_Str MSG_EXTRA_FAN_SPEED_N               = _UxGT("Obroty dodatkowego wiatraka ~");
246 246
   PROGMEM Language_Str MSG_FLOW                            = _UxGT("Przepływ");
247 247
   PROGMEM Language_Str MSG_FLOW_N                          = _UxGT("Przepływ ~");
248 248
   PROGMEM Language_Str MSG_CONTROL                         = _UxGT("Ustawienia");

+ 1
- 1
Marlin/src/lcd/language/language_pt.h View File

@@ -89,7 +89,7 @@ namespace Language_pt {
89 89
   PROGMEM Language_Str MSG_NOZZLE_N                        = " " LCD_STR_THERMOMETER _UxGT(" Bico ~");
90 90
   PROGMEM Language_Str MSG_BED                             = " " LCD_STR_THERMOMETER _UxGT(" Base");
91 91
   PROGMEM Language_Str MSG_FAN_SPEED                       = _UxGT("Vel. ventoinha");
92
-  PROGMEM Language_Str MSG_FAN_SPEED_N                     = _UxGT("Vel. ventoinha =");
92
+  PROGMEM Language_Str MSG_FAN_SPEED_N                     = _UxGT("Vel. ventoinha ~");
93 93
   PROGMEM Language_Str MSG_FLOW                            = _UxGT("Fluxo");
94 94
   PROGMEM Language_Str MSG_FLOW_N                          = _UxGT("Fluxo ~");
95 95
   PROGMEM Language_Str MSG_CONTROL                         = _UxGT("Controlo");

+ 2
- 2
Marlin/src/lcd/language/language_pt_br.h View File

@@ -207,9 +207,9 @@ namespace Language_pt_br {
207 207
   PROGMEM Language_Str MSG_NOZZLE_N                        = _UxGT("Bocal ~");
208 208
   PROGMEM Language_Str MSG_BED                             = _UxGT("Mesa");
209 209
   PROGMEM Language_Str MSG_FAN_SPEED                       = _UxGT("Vel. Ventoinha");
210
-  PROGMEM Language_Str MSG_FAN_SPEED_N                     = _UxGT("Vel. Ventoinha =");
210
+  PROGMEM Language_Str MSG_FAN_SPEED_N                     = _UxGT("Vel. Ventoinha ~");
211 211
   PROGMEM Language_Str MSG_EXTRA_FAN_SPEED                 = _UxGT("+Vel. Ventoinha");
212
-  PROGMEM Language_Str MSG_EXTRA_FAN_SPEED_N               = _UxGT("+Vel. Ventoinha =");
212
+  PROGMEM Language_Str MSG_EXTRA_FAN_SPEED_N               = _UxGT("+Vel. Ventoinha ~");
213 213
   PROGMEM Language_Str MSG_FLOW                            = _UxGT("Vazão");
214 214
   PROGMEM Language_Str MSG_FLOW_N                          = _UxGT("Vazão ~");
215 215
   PROGMEM Language_Str MSG_CONTROL                         = _UxGT("Controle");

+ 2
- 2
Marlin/src/lcd/language/language_sk.h View File

@@ -243,9 +243,9 @@ namespace Language_sk {
243 243
   PROGMEM Language_Str MSG_BED                             = _UxGT("Podložka");
244 244
   PROGMEM Language_Str MSG_CHAMBER                         = _UxGT("Komora");
245 245
   PROGMEM Language_Str MSG_FAN_SPEED                       = _UxGT("Rýchlosť vent.");
246
-  PROGMEM Language_Str MSG_FAN_SPEED_N                     = _UxGT("Rýchlosť vent. =");
246
+  PROGMEM Language_Str MSG_FAN_SPEED_N                     = _UxGT("Rýchlosť vent. ~");
247 247
   PROGMEM Language_Str MSG_EXTRA_FAN_SPEED                 = _UxGT("Rýchlosť ex. vent.");
248
-  PROGMEM Language_Str MSG_EXTRA_FAN_SPEED_N               = _UxGT("Rýchlosť ex. vent. =");
248
+  PROGMEM Language_Str MSG_EXTRA_FAN_SPEED_N               = _UxGT("Rýchlosť ex. vent. ~");
249 249
   PROGMEM Language_Str MSG_FLOW                            = _UxGT("Prietok");
250 250
   PROGMEM Language_Str MSG_FLOW_N                          = _UxGT("Prietok ~");
251 251
   PROGMEM Language_Str MSG_CONTROL                         = _UxGT("Ovládanie");

+ 2
- 2
Marlin/src/lcd/language/language_tr.h View File

@@ -210,9 +210,9 @@ namespace Language_tr {
210 210
   PROGMEM Language_Str MSG_NOZZLE_N                        = _UxGT("Nozul ~");
211 211
   PROGMEM Language_Str MSG_BED                             = _UxGT("Tabla");
212 212
   PROGMEM Language_Str MSG_FAN_SPEED                       = _UxGT("Fan Hızı");
213
-  PROGMEM Language_Str MSG_FAN_SPEED_N                     = _UxGT("Fan Hızı =");
213
+  PROGMEM Language_Str MSG_FAN_SPEED_N                     = _UxGT("Fan Hızı ~");
214 214
   PROGMEM Language_Str MSG_EXTRA_FAN_SPEED                 = _UxGT("Ekstra Fan Hızı");
215
-  PROGMEM Language_Str MSG_EXTRA_FAN_SPEED_N               = _UxGT("Ekstra Fan Hızı =");
215
+  PROGMEM Language_Str MSG_EXTRA_FAN_SPEED_N               = _UxGT("Ekstra Fan Hızı ~");
216 216
   PROGMEM Language_Str MSG_FLOW                            = _UxGT("Akış");
217 217
   PROGMEM Language_Str MSG_FLOW_N                          = _UxGT("Akış ~");
218 218
   PROGMEM Language_Str MSG_CONTROL                         = _UxGT("Kontrol");

+ 1
- 1
Marlin/src/lcd/language/language_uk.h View File

@@ -92,7 +92,7 @@ namespace Language_uk {
92 92
   PROGMEM Language_Str MSG_NOZZLE_N                        = _UxGT("Сопло ~");
93 93
   PROGMEM Language_Str MSG_BED                             = _UxGT("Стіл");
94 94
   PROGMEM Language_Str MSG_FAN_SPEED                       = _UxGT("Охолодж.");
95
-  PROGMEM Language_Str MSG_FAN_SPEED_N                     = _UxGT("Охолодж. =");
95
+  PROGMEM Language_Str MSG_FAN_SPEED_N                     = _UxGT("Охолодж. ~");
96 96
   PROGMEM Language_Str MSG_FLOW                            = _UxGT("Потік");
97 97
   PROGMEM Language_Str MSG_FLOW_N                          = _UxGT("Потік ~");
98 98
   PROGMEM Language_Str MSG_CONTROL                         = _UxGT("Налаштування");

+ 2
- 2
Marlin/src/lcd/language/language_vi.h View File

@@ -210,9 +210,9 @@ namespace Language_vi {
210 210
   PROGMEM Language_Str MSG_NOZZLE_N                        = _UxGT("Đầu phun ~");                           // Nozzle
211 211
   PROGMEM Language_Str MSG_BED                             = _UxGT("Bàn");                                  // bed
212 212
   PROGMEM Language_Str MSG_FAN_SPEED                       = _UxGT("Tốc độ quạt");                          // fan speed
213
-  PROGMEM Language_Str MSG_FAN_SPEED_N                     = _UxGT("Tốc độ quạt =");                        // fan speed
213
+  PROGMEM Language_Str MSG_FAN_SPEED_N                     = _UxGT("Tốc độ quạt ~");                        // fan speed
214 214
   PROGMEM Language_Str MSG_EXTRA_FAN_SPEED                 = _UxGT("Tốc độ quạt phụ");                      // Extra fan speed
215
-  PROGMEM Language_Str MSG_EXTRA_FAN_SPEED_N               = _UxGT("Tốc độ quạt phụ =");                    // Extra fan speed
215
+  PROGMEM Language_Str MSG_EXTRA_FAN_SPEED_N               = _UxGT("Tốc độ quạt phụ ~");                    // Extra fan speed
216 216
   PROGMEM Language_Str MSG_FLOW                            = _UxGT("Lưu Lượng");
217 217
   PROGMEM Language_Str MSG_FLOW_N                          = _UxGT("Lưu Lượng ~");
218 218
   PROGMEM Language_Str MSG_CONTROL                         = _UxGT("Điều khiển");                           // Control

+ 2
- 2
Marlin/src/lcd/language/language_zh_CN.h View File

@@ -187,9 +187,9 @@ namespace Language_zh_CN {
187 187
   PROGMEM Language_Str MSG_NOZZLE_N                        = " " LCD_STR_THERMOMETER _UxGT(" 喷嘴 ~");     //"Nozzle" 噴嘴
188 188
   PROGMEM Language_Str MSG_BED                             = " " LCD_STR_THERMOMETER _UxGT(" 热床");     //"Bed"
189 189
   PROGMEM Language_Str MSG_FAN_SPEED                       = _UxGT("风扇速率");     //"Fan speed"
190
-  PROGMEM Language_Str MSG_FAN_SPEED_N                     = _UxGT("风扇速率 =");     //"Fan speed"
190
+  PROGMEM Language_Str MSG_FAN_SPEED_N                     = _UxGT("风扇速率 ~");     //"Fan speed"
191 191
   PROGMEM Language_Str MSG_EXTRA_FAN_SPEED                 = _UxGT("额外风扇速率");     // "Extra fan speed"
192
-  PROGMEM Language_Str MSG_EXTRA_FAN_SPEED_N               = _UxGT("额外风扇速率 =");     // "Extra fan speed"
192
+  PROGMEM Language_Str MSG_EXTRA_FAN_SPEED_N               = _UxGT("额外风扇速率 ~");     // "Extra fan speed"
193 193
   PROGMEM Language_Str MSG_FLOW                            = _UxGT("挤出速率");     //"Flow"
194 194
   PROGMEM Language_Str MSG_FLOW_N                          = _UxGT("挤出速率 ~");     //"Flow"
195 195
   PROGMEM Language_Str MSG_CONTROL                         = _UxGT("控制");     //"Control"

+ 2
- 2
Marlin/src/lcd/language/language_zh_TW.h View File

@@ -187,9 +187,9 @@ namespace Language_zh_TW {
187 187
   PROGMEM Language_Str MSG_NOZZLE_N                        = " " LCD_STR_THERMOMETER _UxGT(" 噴嘴 ~");
188 188
   PROGMEM Language_Str MSG_BED                             = " " LCD_STR_THERMOMETER _UxGT(" 熱床");     //"Bed"
189 189
   PROGMEM Language_Str MSG_FAN_SPEED                       = _UxGT("風扇速率");     //"Fan speed"
190
-  PROGMEM Language_Str MSG_FAN_SPEED_N                     = _UxGT("風扇速率 =");
190
+  PROGMEM Language_Str MSG_FAN_SPEED_N                     = _UxGT("風扇速率 ~");
191 191
   PROGMEM Language_Str MSG_EXTRA_FAN_SPEED                 = _UxGT("額外風扇速率");     // "Extra fan speed"
192
-  PROGMEM Language_Str MSG_EXTRA_FAN_SPEED_N               = _UxGT("額外風扇速率 =");
192
+  PROGMEM Language_Str MSG_EXTRA_FAN_SPEED_N               = _UxGT("額外風扇速率 ~");
193 193
   PROGMEM Language_Str MSG_FLOW                            = _UxGT("擠出速率");
194 194
   PROGMEM Language_Str MSG_FLOW_N                          = _UxGT("擠出速率 ~");     //"Flow"
195 195
   PROGMEM Language_Str MSG_CONTROL                         = _UxGT("控制");     //"Control"

+ 1
- 1
Marlin/src/lcd/menu/menu.h View File

@@ -30,7 +30,7 @@
30 30
 extern int8_t encoderLine, encoderTopLine, screen_items;
31 31
 
32 32
 #if HOTENDS
33
-  constexpr int16_t heater_maxtemp[HOTENDS] = ARRAY_BY_HOTENDS(HEATER_0_MAXTEMP, HEATER_1_MAXTEMP, HEATER_2_MAXTEMP, HEATER_3_MAXTEMP, HEATER_4_MAXTEMP, HEATER_5_MAXTEMP);
33
+  constexpr int16_t heater_maxtemp[HOTENDS] = ARRAY_BY_HOTENDS(HEATER_0_MAXTEMP, HEATER_1_MAXTEMP, HEATER_2_MAXTEMP, HEATER_3_MAXTEMP, HEATER_4_MAXTEMP, HEATER_5_MAXTEMP, HEATER_6_MAXTEMP, HEATER_7_MAXTEMP);
34 34
 #endif
35 35
 
36 36
 void scroll_screen(const uint8_t limit, const bool is_menu);

+ 12
- 0
Marlin/src/lcd/menu/menu_advanced.cpp View File

@@ -245,6 +245,12 @@ void menu_cancelobject();
245 245
           DEFINE_PIDTEMP_FUNCS(4);
246 246
           #if HOTENDS > 5
247 247
             DEFINE_PIDTEMP_FUNCS(5);
248
+            #if HOTENDS > 6
249
+              DEFINE_PIDTEMP_FUNCS(6);
250
+              #if HOTENDS > 7
251
+                DEFINE_PIDTEMP_FUNCS(7);
252
+              #endif // HOTENDS > 7
253
+            #endif // HOTENDS > 6
248 254
           #endif // HOTENDS > 5
249 255
         #endif // HOTENDS > 4
250 256
       #endif // HOTENDS > 3
@@ -330,6 +336,12 @@ void menu_cancelobject();
330 336
             PID_EDIT_MENU_ITEMS(4);
331 337
             #if HOTENDS > 5
332 338
               PID_EDIT_MENU_ITEMS(5);
339
+              #if HOTENDS > 6
340
+                PID_EDIT_MENU_ITEMS(6);
341
+                #if HOTENDS > 7
342
+                  PID_EDIT_MENU_ITEMS(7);
343
+                #endif // HOTENDS > 7
344
+              #endif // HOTENDS > 6
333 345
             #endif // HOTENDS > 5
334 346
           #endif // HOTENDS > 4
335 347
         #endif // HOTENDS > 3

+ 18
- 0
Marlin/src/lcd/menu/menu_info.cpp View File

@@ -152,6 +152,24 @@ void menu_info_thermistors() {
152 152
     VALUE_ITEM_P(MSG_INFO_MAX_TEMP, STRINGIFY(HEATER_5_MAXTEMP), SS_LEFT);
153 153
   #endif
154 154
 
155
+  #if TEMP_SENSOR_6 != 0
156
+    #undef THERMISTOR_ID
157
+    #define THERMISTOR_ID TEMP_SENSOR_6
158
+    #include "../thermistornames.h"
159
+    STATIC_ITEM_P(PSTR(LCD_STR_E6 ": " THERMISTOR_NAME), SS_INVERT);
160
+    VALUE_ITEM_P(MSG_INFO_MIN_TEMP, STRINGIFY(HEATER_6_MINTEMP), SS_LEFT);
161
+    VALUE_ITEM_P(MSG_INFO_MAX_TEMP, STRINGIFY(HEATER_6_MAXTEMP), SS_LEFT);
162
+  #endif
163
+
164
+  #if TEMP_SENSOR_7 != 0
165
+    #undef THERMISTOR_ID
166
+    #define THERMISTOR_ID TEMP_SENSOR_7
167
+    #include "../thermistornames.h"
168
+    STATIC_ITEM_P(PSTR(LCD_STR_E7 ": " THERMISTOR_NAME), SS_INVERT);
169
+    VALUE_ITEM_P(MSG_INFO_MIN_TEMP, STRINGIFY(HEATER_7_MINTEMP), SS_LEFT);
170
+    VALUE_ITEM_P(MSG_INFO_MAX_TEMP, STRINGIFY(HEATER_7_MAXTEMP), SS_LEFT);
171
+  #endif
172
+
155 173
   #if EXTRUDERS
156 174
   {
157 175
     STATIC_ITEM(

+ 58
- 19
Marlin/src/lcd/menu/menu_temperature.cpp View File

@@ -198,33 +198,72 @@ void menu_temperature() {
198 198
   // Fan Speed:
199 199
   //
200 200
   #if FAN_COUNT > 0
201
+
202
+    auto on_fan_update = []{
203
+      thermalManager.set_fan_speed(MenuItemBase::itemIndex, editable.uint8);
204
+    };
205
+
206
+    #if HAS_FAN1 || HAS_FAN2 || HAS_FAN3 || HAS_FAN4 || HAS_FAN5 || HAS_FAN6 || HAS_FAN7
207
+      auto fan_edit_items = [&](const uint8_t f) {
208
+        editable.uint8 = thermalManager.fan_speed[f];
209
+        EDIT_ITEM_FAST_N(percent, f, MSG_FAN_SPEED_N, &editable.uint8, 0, 255, on_fan_update);
210
+        #if ENABLED(EXTRA_FAN_SPEED)
211
+          EDIT_ITEM_FAST_N(percent, f, MSG_EXTRA_FAN_SPEED_N, &thermalManager.new_fan_speed[f], 3, 255);
212
+        #endif
213
+      };
214
+    #endif
215
+
216
+    #define SNFAN(N) (ENABLED(SINGLENOZZLE) && !HAS_FAN##N && EXTRUDERS > N)
217
+    #if SNFAN(1) || SNFAN(2) || SNFAN(3) || SNFAN(4) || SNFAN(5) || SNFAN(6) || SNFAN(7)
218
+      auto singlenozzle_item = [&](const uint8_t f) {
219
+        editable.uint8 = thermalManager.fan_speed[f];
220
+        EDIT_ITEM_FAST_N(percent, f, MSG_STORED_FAN_N, &editable.uint8, 0, 255, on_fan_update);
221
+      };
222
+    #endif
223
+
201 224
     #if HAS_FAN0
202 225
       editable.uint8 = thermalManager.fan_speed[0];
203
-      EDIT_ITEM_FAST_N(percent, 1, MSG_FIRST_FAN_SPEED, &editable.uint8, 0, 255, []{ thermalManager.set_fan_speed(0, editable.uint8); });
226
+      EDIT_ITEM_FAST_N(percent, 0, MSG_FIRST_FAN_SPEED, &editable.uint8, 0, 255, on_fan_update);
204 227
       #if ENABLED(EXTRA_FAN_SPEED)
205
-        EDIT_ITEM_FAST_N(percent, 1, MSG_FIRST_EXTRA_FAN_SPEED, &thermalManager.new_fan_speed[0], 3, 255);
228
+        EDIT_ITEM_FAST_N(percent, 0, MSG_FIRST_EXTRA_FAN_SPEED, &thermalManager.new_fan_speed[0], 3, 255);
206 229
       #endif
207 230
     #endif
208 231
     #if HAS_FAN1
209
-      editable.uint8 = thermalManager.fan_speed[1];
210
-      EDIT_ITEM_FAST_N(percent, 2, MSG_FAN_SPEED_N, &editable.uint8, 0, 255, []{ thermalManager.set_fan_speed(1, editable.uint8); });
211
-      #if ENABLED(EXTRA_FAN_SPEED)
212
-        EDIT_ITEM_FAST_N(percent, 2, MSG_EXTRA_FAN_SPEED_N, &thermalManager.new_fan_speed[1], 3, 255);
213
-      #endif
214
-    #elif ENABLED(SINGLENOZZLE) && EXTRUDERS > 1
215
-      editable.uint8 = thermalManager.fan_speed[1];
216
-      EDIT_ITEM_FAST_N(percent, 2, MSG_STORED_FAN_N, &editable.uint8, 0, 255, []{ thermalManager.set_fan_speed(1, editable.uint8); });
232
+      fan_edit_items(1);
233
+    #elif SNFAN(1)
234
+      singlenozzle_item(1);
217 235
     #endif
218 236
     #if HAS_FAN2
219
-      editable.uint8 = thermalManager.fan_speed[2];
220
-      EDIT_ITEM_FAST_N(percent, 3, MSG_FAN_SPEED_N, &editable.uint8, 0, 255, []{ thermalManager.set_fan_speed(2, editable.uint8); });
221
-      #if ENABLED(EXTRA_FAN_SPEED)
222
-        EDIT_ITEM_FAST_N(percent, 3, MSG_EXTRA_FAN_SPEED_N, &thermalManager.new_fan_speed[2], 3, 255);
223
-      #endif
224
-    #elif ENABLED(SINGLENOZZLE) && EXTRUDERS > 2
225
-      editable.uint8 = thermalManager.fan_speed[2];
226
-      EDIT_ITEM_FAST_N(percent, 3, MSG_STORED_FAN_N, &editable.uint8, 0, 255, []{ thermalManager.set_fan_speed(2, editable.uint8); });
237
+      fan_edit_items(2);
238
+    #elif SNFAN(2)
239
+      singlenozzle_item(1);
240
+    #endif
241
+    #if HAS_FAN3
242
+      fan_edit_items(3);
243
+    #elif SNFAN(3)
244
+      singlenozzle_item(1);
245
+    #endif
246
+    #if HAS_FAN4
247
+      fan_edit_items(4);
248
+    #elif SNFAN(4)
249
+      singlenozzle_item(1);
227 250
     #endif
251
+    #if HAS_FAN5
252
+      fan_edit_items(5);
253
+    #elif SNFAN(5)
254
+      singlenozzle_item(1);
255
+    #endif
256
+    #if HAS_FAN6
257
+      fan_edit_items(6);
258
+    #elif SNFAN(6)
259
+      singlenozzle_item(1);
260
+    #endif
261
+    #if HAS_FAN7
262
+      fan_edit_items(7);
263
+    #elif SNFAN(7)
264
+      singlenozzle_item(1);
265
+    #endif
266
+
228 267
   #endif // FAN_COUNT > 0
229 268
 
230 269
   #if HAS_TEMP_HOTEND
@@ -232,7 +271,7 @@ void menu_temperature() {
232 271
     //
233 272
     // Preheat for Material 1 and 2
234 273
     //
235
-    #if TEMP_SENSOR_1 != 0 || TEMP_SENSOR_2 != 0 || TEMP_SENSOR_3 != 0 || TEMP_SENSOR_4 != 0 || TEMP_SENSOR_5 != 0 || HAS_HEATED_BED
274
+    #if TEMP_SENSOR_1 != 0 || TEMP_SENSOR_2 != 0 || TEMP_SENSOR_3 != 0 || TEMP_SENSOR_4 != 0 || TEMP_SENSOR_5 != 0 || TEMP_SENSOR_6 != 0 || TEMP_SENSOR_7 != 0 || HAS_HEATED_BED
236 275
       SUBMENU(MSG_PREHEAT_1, menu_preheat_m1);
237 276
       SUBMENU(MSG_PREHEAT_2, menu_preheat_m2);
238 277
     #else

+ 18
- 0
Marlin/src/lcd/menu/menu_tmc.cpp View File

@@ -79,6 +79,12 @@ void menu_tmc_current() {
79 79
   #if AXIS_IS_TMC(E5)
80 80
     TMC_EDIT_STORED_I_RMS(E5, LCD_STR_E5);
81 81
   #endif
82
+  #if AXIS_IS_TMC(E6)
83
+    TMC_EDIT_STORED_I_RMS(E6, LCD_STR_E6);
84
+  #endif
85
+  #if AXIS_IS_TMC(E7)
86
+    TMC_EDIT_STORED_I_RMS(E7, LCD_STR_E7);
87
+  #endif
82 88
   END_MENU();
83 89
 }
84 90
 
@@ -131,6 +137,12 @@ void menu_tmc_current() {
131 137
     #if AXIS_HAS_STEALTHCHOP(E5)
132 138
       TMC_EDIT_STORED_HYBRID_THRS(E5, LCD_STR_E5);
133 139
     #endif
140
+    #if AXIS_HAS_STEALTHCHOP(E6)
141
+      TMC_EDIT_STORED_HYBRID_THRS(E6, LCD_STR_E6);
142
+    #endif
143
+    #if AXIS_HAS_STEALTHCHOP(E7)
144
+      TMC_EDIT_STORED_HYBRID_THRS(E7, LCD_STR_E7);
145
+    #endif
134 146
     END_MENU();
135 147
   }
136 148
 
@@ -210,6 +222,12 @@ void menu_tmc_current() {
210 222
     #if AXIS_HAS_STEALTHCHOP(E5)
211 223
       TMC_EDIT_STEP_MODE(E5, LCD_STR_E5);
212 224
     #endif
225
+    #if AXIS_HAS_STEALTHCHOP(E6)
226
+      TMC_EDIT_STEP_MODE(E6, LCD_STR_E6);
227
+    #endif
228
+    #if AXIS_HAS_STEALTHCHOP(E7)
229
+      TMC_EDIT_STEP_MODE(E7, LCD_STR_E7);
230
+    #endif
213 231
     END_MENU();
214 232
   }
215 233
 

+ 57
- 18
Marlin/src/lcd/menu/menu_tune.cpp View File

@@ -147,33 +147,72 @@ void menu_tune() {
147 147
   // Fan Speed:
148 148
   //
149 149
   #if FAN_COUNT > 0
150
+
151
+    auto on_fan_update = []{
152
+      thermalManager.set_fan_speed(MenuItemBase::itemIndex, editable.uint8);
153
+    };
154
+
155
+    #if HAS_FAN1 || HAS_FAN2 || HAS_FAN3 || HAS_FAN4 || HAS_FAN5 || HAS_FAN6 || HAS_FAN7
156
+      auto fan_edit_items = [&](const uint8_t f) {
157
+        editable.uint8 = thermalManager.fan_speed[f];
158
+        EDIT_ITEM_FAST_N(percent, f, MSG_FAN_SPEED_N, &editable.uint8, 0, 255, on_fan_update);
159
+        #if ENABLED(EXTRA_FAN_SPEED)
160
+          EDIT_ITEM_FAST_N(percent, f, MSG_EXTRA_FAN_SPEED_N, &thermalManager.new_fan_speed[f], 3, 255);
161
+        #endif
162
+      };
163
+    #endif
164
+
165
+    #define SNFAN(N) (ENABLED(SINGLENOZZLE) && !HAS_FAN##N && EXTRUDERS > N)
166
+    #if SNFAN(1) || SNFAN(2) || SNFAN(3) || SNFAN(4) || SNFAN(5) || SNFAN(6) || SNFAN(7)
167
+      auto singlenozzle_item = [&](const uint8_t f) {
168
+        editable.uint8 = thermalManager.fan_speed[f];
169
+        EDIT_ITEM_FAST_N(percent, f, MSG_STORED_FAN_N, &editable.uint8, 0, 255, on_fan_update);
170
+      };
171
+    #endif
172
+
150 173
     #if HAS_FAN0
151 174
       editable.uint8 = thermalManager.fan_speed[0];
152
-      EDIT_ITEM_FAST_N(percent, 1, MSG_FIRST_FAN_SPEED, &editable.uint8, 0, 255, []{ thermalManager.set_fan_speed(0, editable.uint8); });
175
+      EDIT_ITEM_FAST_N(percent, 0, MSG_FIRST_FAN_SPEED, &editable.uint8, 0, 255, on_fan_update);
153 176
       #if ENABLED(EXTRA_FAN_SPEED)
154
-        EDIT_ITEM_FAST_N(percent, 1, MSG_FIRST_EXTRA_FAN_SPEED, &thermalManager.new_fan_speed[0], 3, 255);
177
+        EDIT_ITEM_FAST_N(percent, 0, MSG_FIRST_EXTRA_FAN_SPEED, &thermalManager.new_fan_speed[0], 3, 255);
155 178
       #endif
156 179
     #endif
157 180
     #if HAS_FAN1
158
-      editable.uint8 = thermalManager.fan_speed[1];
159
-      EDIT_ITEM_FAST_N(percent, 2, MSG_FAN_SPEED_N, &editable.uint8, 0, 255, []{ thermalManager.set_fan_speed(1, editable.uint8); });
160
-      #if ENABLED(EXTRA_FAN_SPEED)
161
-        EDIT_ITEM_FAST_N(percent, 2, MSG_EXTRA_FAN_SPEED_N, &thermalManager.new_fan_speed[1], 3, 255);
162
-      #endif
163
-    #elif ENABLED(SINGLENOZZLE) && EXTRUDERS > 1
164
-      editable.uint8 = thermalManager.fan_speed[1];
165
-      EDIT_ITEM_FAST_N(percent, 2, MSG_STORED_FAN_N, &editable.uint8, 0, 255, []{ thermalManager.set_fan_speed(1, editable.uint8); });
181
+      fan_edit_items(1);
182
+    #elif SNFAN(1)
183
+      singlenozzle_item(1);
166 184
     #endif
167 185
     #if HAS_FAN2
168
-      editable.uint8 = thermalManager.fan_speed[2];
169
-      EDIT_ITEM_FAST_N(percent, 3, MSG_FAN_SPEED_N, &editable.uint8, 0, 255, []{ thermalManager.set_fan_speed(2, editable.uint8); });
170
-      #if ENABLED(EXTRA_FAN_SPEED)
171
-        EDIT_ITEM_FAST_N(percent, 3, MSG_EXTRA_FAN_SPEED_N, &thermalManager.new_fan_speed[2], 3, 255);
172
-      #endif
173
-    #elif ENABLED(SINGLENOZZLE) && EXTRUDERS > 2
174
-      editable.uint8 = thermalManager.fan_speed[2];
175
-      EDIT_ITEM_FAST_N(percent, 3, MSG_STORED_FAN_N, &editable.uint8, 0, 255, []{ thermalManager.set_fan_speed(2, editable.uint8); });
186
+      fan_edit_items(2);
187
+    #elif SNFAN(2)
188
+      singlenozzle_item(1);
189
+    #endif
190
+    #if HAS_FAN3
191
+      fan_edit_items(3);
192
+    #elif SNFAN(3)
193
+      singlenozzle_item(1);
194
+    #endif
195
+    #if HAS_FAN4
196
+      fan_edit_items(4);
197
+    #elif SNFAN(4)
198
+      singlenozzle_item(1);
176 199
     #endif
200
+    #if HAS_FAN5
201
+      fan_edit_items(5);
202
+    #elif SNFAN(5)
203
+      singlenozzle_item(1);
204
+    #endif
205
+    #if HAS_FAN6
206
+      fan_edit_items(6);
207
+    #elif SNFAN(6)
208
+      singlenozzle_item(1);
209
+    #endif
210
+    #if HAS_FAN7
211
+      fan_edit_items(7);
212
+    #elif SNFAN(7)
213
+      singlenozzle_item(1);
214
+    #endif
215
+
177 216
   #endif // FAN_COUNT > 0
178 217
 
179 218
   //

+ 3
- 1
Marlin/src/libs/L64XX/L64XX_Marlin.cpp View File

@@ -39,7 +39,7 @@ L64XX_Marlin L64xxManager;
39 39
 
40 40
 void echo_yes_no(const bool yes) { serialprintPGM(yes ? PSTR(" YES") : PSTR(" NO ")); }
41 41
 
42
-char L64XX_Marlin::index_to_axis[MAX_L64XX][3] = { "X ", "Y ", "Z ", "X2", "Y2", "Z2", "Z3", "Z4", "E0", "E1", "E2", "E3", "E4", "E5" };
42
+char L64XX_Marlin::index_to_axis[MAX_L64XX][3] = { "X ", "Y ", "Z ", "X2", "Y2", "Z2", "Z3", "Z4", "E0", "E1", "E2", "E3", "E4", "E5", "E6", "E7" };
43 43
 
44 44
 #define DEBUG_OUT ENABLED(L6470_CHITCHAT)
45 45
 #include "../../core/debug_out.h"
@@ -69,6 +69,8 @@ uint8_t L64XX_Marlin::index_to_dir[MAX_L64XX] = { (INVERT_X_DIR),
69 69
                                                   (INVERT_E3_DIR),                        // 11 E3
70 70
                                                   (INVERT_E4_DIR),                        // 12 E4
71 71
                                                   (INVERT_E5_DIR),                        // 13 E5
72
+                                                  (INVERT_E6_DIR),                        // 14 E6
73
+                                                  (INVERT_E7_DIR)                         // 15 E7
72 74
                                                 };
73 75
 
74 76
 volatile uint8_t L64XX_Marlin::spi_abort = false;

+ 1
- 1
Marlin/src/libs/L64XX/L64XX_Marlin.h View File

@@ -35,7 +35,7 @@
35 35
 #define dSPIN_STEP_CLOCK_REV dSPIN_STEP_CLOCK+1
36 36
 #define HAS_L64XX_EXTRUDER (AXIS_IS_L64XX(E0) || AXIS_IS_L64XX(E1) || AXIS_IS_L64XX(E2) || AXIS_IS_L64XX(E3) || AXIS_IS_L64XX(E4) || AXIS_IS_L64XX(E5))
37 37
 
38
-enum L64XX_axis_t : uint8_t { X, Y, Z, X2, Y2, Z2, Z3, Z4, E0, E1, E2, E3, E4, E5, MAX_L64XX };
38
+enum L64XX_axis_t : uint8_t { X, Y, Z, X2, Y2, Z2, Z3, Z4, E0, E1, E2, E3, E4, E5, E6, E7, MAX_L64XX };
39 39
 
40 40
 class L64XX_Marlin : public L64XXHelper {
41 41
 public:

+ 2
- 5
Marlin/src/libs/softspi.h View File

@@ -66,7 +66,7 @@
66 66
      * @return value read
67 67
      */
68 68
     FORCE_INLINE static bool fastDigitalRead(uint8_t pin) {
69
-      return g_APinDescription[pin].pPort->PIO_PDSR & g_APinDescription[pin].ulPin;
69
+      return digitalRead(pin);
70 70
     }
71 71
 
72 72
     /**
@@ -75,10 +75,7 @@
75 75
      * @param[in] level value to write
76 76
      */
77 77
     FORCE_INLINE static void fastDigitalWrite(uint8_t pin, bool value) {
78
-      if (value)
79
-        g_APinDescription[pin].pPort->PIO_SODR = g_APinDescription[pin].ulPin;
80
-      else
81
-        g_APinDescription[pin].pPort->PIO_CODR = g_APinDescription[pin].ulPin;
78
+      digitalWrite(pin, value);
82 79
     }
83 80
 
84 81
   #endif // !CORE_TEENSY

+ 44
- 0
Marlin/src/module/configuration_store.cpp View File

@@ -1008,6 +1008,16 @@ void MarlinSettings::postprocess() {
1008 1008
                     #if AXIS_IS_TMC(E5)
1009 1009
                       tmc_stepper_current.E5 = stepperE5.getMilliamps();
1010 1010
                     #endif
1011
+                    #if MAX_EXTRUDERS > 6
1012
+                      #if AXIS_IS_TMC(E6)
1013
+                        tmc_stepper_current.E6 = stepperE6.getMilliamps();
1014
+                      #endif
1015
+                      #if MAX_EXTRUDERS > 7
1016
+                        #if AXIS_IS_TMC(E7)
1017
+                          tmc_stepper_current.E7 = stepperE7.getMilliamps();
1018
+                        #endif
1019
+                      #endif // MAX_EXTRUDERS > 7
1020
+                    #endif // MAX_EXTRUDERS > 6
1011 1021
                   #endif // MAX_EXTRUDERS > 5
1012 1022
                 #endif // MAX_EXTRUDERS > 4
1013 1023
               #endif // MAX_EXTRUDERS > 3
@@ -1074,6 +1084,16 @@ void MarlinSettings::postprocess() {
1074 1084
                     #if AXIS_HAS_STEALTHCHOP(E5)
1075 1085
                       tmc_hybrid_threshold.E5 = stepperE5.get_pwm_thrs();
1076 1086
                     #endif
1087
+                    #if MAX_EXTRUDERS > 6
1088
+                      #if AXIS_HAS_STEALTHCHOP(E6)
1089
+                        tmc_hybrid_threshold.E6 = stepperE6.get_pwm_thrs();
1090
+                      #endif
1091
+                      #if MAX_EXTRUDERS > 7
1092
+                        #if AXIS_HAS_STEALTHCHOP(E7)
1093
+                          tmc_hybrid_threshold.E7 = stepperE7.get_pwm_thrs();
1094
+                        #endif
1095
+                      #endif // MAX_EXTRUDERS > 7
1096
+                    #endif // MAX_EXTRUDERS > 6
1077 1097
                   #endif // MAX_EXTRUDERS > 5
1078 1098
                 #endif // MAX_EXTRUDERS > 4
1079 1099
               #endif // MAX_EXTRUDERS > 3
@@ -1170,6 +1190,16 @@ void MarlinSettings::postprocess() {
1170 1190
                     #if AXIS_HAS_STEALTHCHOP(E5)
1171 1191
                       tmc_stealth_enabled.E5 = stepperE5.get_stealthChop_status();
1172 1192
                     #endif
1193
+                    #if MAX_EXTRUDERS > 6
1194
+                      #if AXIS_HAS_STEALTHCHOP(E6)
1195
+                        tmc_stealth_enabled.E6 = stepperE6.get_stealthChop_status();
1196
+                      #endif
1197
+                      #if MAX_EXTRUDERS > 7
1198
+                        #if AXIS_HAS_STEALTHCHOP(E7)
1199
+                          tmc_stealth_enabled.E7 = stepperE7.get_stealthChop_status();
1200
+                        #endif
1201
+                      #endif // MAX_EXTRUDERS > 7
1202
+                    #endif // MAX_EXTRUDERS > 6
1173 1203
                   #endif // MAX_EXTRUDERS > 5
1174 1204
                 #endif // MAX_EXTRUDERS > 4
1175 1205
               #endif // MAX_EXTRUDERS > 3
@@ -2788,6 +2818,14 @@ void MarlinSettings::reset() {
2788 2818
               #if EXTRUDERS > 5
2789 2819
                 CONFIG_ECHO_START();
2790 2820
                 SERIAL_ECHOLNPAIR("  M200 T5 D", LINEAR_UNIT(planner.filament_size[5]));
2821
+                #if EXTRUDERS > 6
2822
+                  CONFIG_ECHO_START();
2823
+                  SERIAL_ECHOLNPAIR("  M200 T6 D", LINEAR_UNIT(planner.filament_size[6]));
2824
+                  #if EXTRUDERS > 7
2825
+                    CONFIG_ECHO_START();
2826
+                    SERIAL_ECHOLNPAIR("  M200 T7 D", LINEAR_UNIT(planner.filament_size[7]));
2827
+                  #endif // EXTRUDERS > 7
2828
+                #endif // EXTRUDERS > 6
2791 2829
               #endif // EXTRUDERS > 5
2792 2830
             #endif // EXTRUDERS > 4
2793 2831
           #endif // EXTRUDERS > 3
@@ -3528,6 +3566,12 @@ void MarlinSettings::reset() {
3528 3566
               _ECHO_603(4);
3529 3567
               #if EXTRUDERS > 5
3530 3568
                 _ECHO_603(5);
3569
+                #if EXTRUDERS > 6
3570
+                  _ECHO_603(6);
3571
+                  #if EXTRUDERS > 7
3572
+                    _ECHO_603(7);
3573
+                  #endif // EXTRUDERS > 7
3574
+                #endif // EXTRUDERS > 6
3531 3575
               #endif // EXTRUDERS > 5
3532 3576
             #endif // EXTRUDERS > 4
3533 3577
           #endif // EXTRUDERS > 3

+ 10
- 4
Marlin/src/module/endstops.cpp View File

@@ -486,14 +486,20 @@ void _O2 Endstops::report_states() {
486 486
           default: continue;
487 487
           case 1: pin = FIL_RUNOUT_PIN; break;
488 488
           case 2: pin = FIL_RUNOUT2_PIN; break;
489
-          #if NUM_RUNOUT_SENSORS > 2
489
+          #if NUM_RUNOUT_SENSORS >= 3
490 490
             case 3: pin = FIL_RUNOUT3_PIN; break;
491
-            #if NUM_RUNOUT_SENSORS > 3
491
+            #if NUM_RUNOUT_SENSORS >= 4
492 492
               case 4: pin = FIL_RUNOUT4_PIN; break;
493
-              #if NUM_RUNOUT_SENSORS > 4
493
+              #if NUM_RUNOUT_SENSORS >= 5
494 494
                 case 5: pin = FIL_RUNOUT5_PIN; break;
495
-                #if NUM_RUNOUT_SENSORS > 5
495
+                #if NUM_RUNOUT_SENSORS >= 6
496 496
                   case 6: pin = FIL_RUNOUT6_PIN; break;
497
+                  #if NUM_RUNOUT_SENSORS >= 7
498
+                    case 7: pin = FIL_RUNOUT7_PIN; break;
499
+                    #if NUM_RUNOUT_SENSORS >= 8
500
+                      case 8: pin = FIL_RUNOUT8_PIN; break;
501
+                    #endif
502
+                  #endif
497 503
                 #endif
498 504
               #endif
499 505
             #endif

+ 15
- 1
Marlin/src/module/planner.cpp View File

@@ -1308,7 +1308,21 @@ void Planner::check_axes_activity() {
1308 1308
     #if HAS_FAN2
1309 1309
       FAN_SET(2);
1310 1310
     #endif
1311
-
1311
+    #if HAS_FAN3
1312
+      FAN_SET(3);
1313
+    #endif
1314
+    #if HAS_FAN4
1315
+      FAN_SET(4);
1316
+    #endif
1317
+    #if HAS_FAN5
1318
+      FAN_SET(5);
1319
+    #endif
1320
+    #if HAS_FAN6
1321
+      FAN_SET(6);
1322
+    #endif
1323
+    #if HAS_FAN7
1324
+      FAN_SET(7);
1325
+    #endif
1312 1326
   #endif // FAN_COUNT > 0
1313 1327
 
1314 1328
   #if ENABLED(AUTOTEMP)

+ 86
- 18
Marlin/src/module/stepper.cpp View File

@@ -2140,6 +2140,12 @@ void Stepper::init() {
2140 2140
   #if HAS_E5_DIR
2141 2141
     E5_DIR_INIT();
2142 2142
   #endif
2143
+  #if HAS_E6_DIR
2144
+    E6_DIR_INIT();
2145
+  #endif
2146
+  #if HAS_E7_DIR
2147
+    E7_DIR_INIT();
2148
+  #endif
2143 2149
 
2144 2150
   // Init Enable Pins - steppers default to disabled.
2145 2151
   #if HAS_X_ENABLE
@@ -2198,6 +2204,14 @@ void Stepper::init() {
2198 2204
     E5_ENABLE_INIT();
2199 2205
     if (!E_ENABLE_ON) E5_ENABLE_WRITE(HIGH);
2200 2206
   #endif
2207
+  #if HAS_E6_ENABLE
2208
+    E6_ENABLE_INIT();
2209
+    if (!E_ENABLE_ON) E6_ENABLE_WRITE(HIGH);
2210
+  #endif
2211
+  #if HAS_E7_ENABLE
2212
+    E7_ENABLE_INIT();
2213
+    if (!E_ENABLE_ON) E7_ENABLE_WRITE(HIGH);
2214
+  #endif
2201 2215
 
2202 2216
   #define _STEP_INIT(AXIS) AXIS ##_STEP_INIT()
2203 2217
   #define _WRITE_STEP(AXIS, HIGHLOW) AXIS ##_STEP_WRITE(HIGHLOW)
@@ -2261,6 +2275,12 @@ void Stepper::init() {
2261 2275
   #if E_STEPPERS > 5 && HAS_E5_STEP
2262 2276
     E_AXIS_INIT(5);
2263 2277
   #endif
2278
+  #if E_STEPPERS > 6 && HAS_E6_STEP
2279
+    E_AXIS_INIT(6);
2280
+  #endif
2281
+  #if E_STEPPERS > 7 && HAS_E7_STEP
2282
+    E_AXIS_INIT(7);
2283
+  #endif
2264 2284
 
2265 2285
   #if DISABLED(I2S_STEPPER_STREAM)
2266 2286
     HAL_timer_start(STEP_TIMER_NUM, 122); // Init Stepper ISR to 122 Hz for quick starting
@@ -2802,6 +2822,20 @@ void Stepper::report_positions() {
2802 2822
         SET_OUTPUT(E5_MS3_PIN);
2803 2823
       #endif
2804 2824
     #endif
2825
+    #if HAS_E6_MICROSTEPS
2826
+      SET_OUTPUT(E6_MS1_PIN);
2827
+      SET_OUTPUT(E6_MS2_PIN);
2828
+      #if PIN_EXISTS(E6_MS3)
2829
+        SET_OUTPUT(E6_MS3_PIN);
2830
+      #endif
2831
+    #endif
2832
+    #if HAS_E7_MICROSTEPS
2833
+      SET_OUTPUT(E7_MS1_PIN);
2834
+      SET_OUTPUT(E7_MS2_PIN);
2835
+      #if PIN_EXISTS(E7_MS3)
2836
+        SET_OUTPUT(E7_MS3_PIN);
2837
+      #endif
2838
+    #endif
2805 2839
 
2806 2840
     static const uint8_t microstep_modes[] = MICROSTEP_MODES;
2807 2841
     for (uint16_t i = 0; i < COUNT(microstep_modes); i++)
@@ -2847,22 +2881,28 @@ void Stepper::report_positions() {
2847 2881
           break;
2848 2882
       #endif
2849 2883
       #if HAS_E0_MICROSTEPS
2850
-        case 3: WRITE(E0_MS1_PIN, ms1); break;
2884
+        case  3: WRITE(E0_MS1_PIN, ms1); break;
2851 2885
       #endif
2852 2886
       #if HAS_E1_MICROSTEPS
2853
-        case 4: WRITE(E1_MS1_PIN, ms1); break;
2887
+        case  4: WRITE(E1_MS1_PIN, ms1); break;
2854 2888
       #endif
2855 2889
       #if HAS_E2_MICROSTEPS
2856
-        case 5: WRITE(E2_MS1_PIN, ms1); break;
2890
+        case  5: WRITE(E2_MS1_PIN, ms1); break;
2857 2891
       #endif
2858 2892
       #if HAS_E3_MICROSTEPS
2859
-        case 6: WRITE(E3_MS1_PIN, ms1); break;
2893
+        case  6: WRITE(E3_MS1_PIN, ms1); break;
2860 2894
       #endif
2861 2895
       #if HAS_E4_MICROSTEPS
2862
-        case 7: WRITE(E4_MS1_PIN, ms1); break;
2896
+        case  7: WRITE(E4_MS1_PIN, ms1); break;
2863 2897
       #endif
2864 2898
       #if HAS_E5_MICROSTEPS
2865
-        case 8: WRITE(E5_MS1_PIN, ms1); break;
2899
+        case  8: WRITE(E5_MS1_PIN, ms1); break;
2900
+      #endif
2901
+      #if HAS_E6_MICROSTEPS
2902
+        case  9: WRITE(E6_MS1_PIN, ms1); break;
2903
+      #endif
2904
+      #if HAS_E7_MICROSTEPS
2905
+        case 10: WRITE(E7_MS1_PIN, ms1); break;
2866 2906
       #endif
2867 2907
     }
2868 2908
     if (ms2 >= 0) switch (driver) {
@@ -2903,22 +2943,28 @@ void Stepper::report_positions() {
2903 2943
           break;
2904 2944
       #endif
2905 2945
       #if HAS_E0_MICROSTEPS
2906
-        case 3: WRITE(E0_MS2_PIN, ms2); break;
2946
+        case  3: WRITE(E0_MS2_PIN, ms2); break;
2907 2947
       #endif
2908 2948
       #if HAS_E1_MICROSTEPS
2909
-        case 4: WRITE(E1_MS2_PIN, ms2); break;
2949
+        case  4: WRITE(E1_MS2_PIN, ms2); break;
2910 2950
       #endif
2911 2951
       #if HAS_E2_MICROSTEPS
2912
-        case 5: WRITE(E2_MS2_PIN, ms2); break;
2952
+        case  5: WRITE(E2_MS2_PIN, ms2); break;
2913 2953
       #endif
2914 2954
       #if HAS_E3_MICROSTEPS
2915
-        case 6: WRITE(E3_MS2_PIN, ms2); break;
2955
+        case  6: WRITE(E3_MS2_PIN, ms2); break;
2916 2956
       #endif
2917 2957
       #if HAS_E4_MICROSTEPS
2918
-        case 7: WRITE(E4_MS2_PIN, ms2); break;
2958
+        case  7: WRITE(E4_MS2_PIN, ms2); break;
2919 2959
       #endif
2920 2960
       #if HAS_E5_MICROSTEPS
2921
-        case 8: WRITE(E5_MS2_PIN, ms2); break;
2961
+        case  8: WRITE(E5_MS2_PIN, ms2); break;
2962
+      #endif
2963
+      #if HAS_E6_MICROSTEPS
2964
+        case  9: WRITE(E6_MS2_PIN, ms2); break;
2965
+      #endif
2966
+      #if HAS_E7_MICROSTEPS
2967
+        case 10: WRITE(E7_MS2_PIN, ms2); break;
2922 2968
       #endif
2923 2969
     }
2924 2970
     if (ms3 >= 0) switch (driver) {
@@ -2959,22 +3005,28 @@ void Stepper::report_positions() {
2959 3005
           break;
2960 3006
       #endif
2961 3007
       #if HAS_E0_MICROSTEPS && PIN_EXISTS(E0_MS3)
2962
-        case 3: WRITE(E0_MS3_PIN, ms3); break;
3008
+        case  3: WRITE(E0_MS3_PIN, ms3); break;
2963 3009
       #endif
2964 3010
       #if HAS_E1_MICROSTEPS && PIN_EXISTS(E1_MS3)
2965
-        case 4: WRITE(E1_MS3_PIN, ms3); break;
3011
+        case  4: WRITE(E1_MS3_PIN, ms3); break;
2966 3012
       #endif
2967 3013
       #if HAS_E2_MICROSTEPS && PIN_EXISTS(E2_MS3)
2968
-        case 5: WRITE(E2_MS3_PIN, ms3); break;
3014
+        case  5: WRITE(E2_MS3_PIN, ms3); break;
2969 3015
       #endif
2970 3016
       #if HAS_E3_MICROSTEPS && PIN_EXISTS(E3_MS3)
2971
-        case 6: WRITE(E3_MS3_PIN, ms3); break;
3017
+        case  6: WRITE(E3_MS3_PIN, ms3); break;
2972 3018
       #endif
2973 3019
       #if HAS_E4_MICROSTEPS && PIN_EXISTS(E4_MS3)
2974
-        case 7: WRITE(E4_MS3_PIN, ms3); break;
3020
+        case  7: WRITE(E4_MS3_PIN, ms3); break;
2975 3021
       #endif
2976 3022
       #if HAS_E5_MICROSTEPS && PIN_EXISTS(E5_MS3)
2977
-        case 8: WRITE(E5_MS3_PIN, ms3); break;
3023
+        case  8: WRITE(E5_MS3_PIN, ms3); break;
3024
+      #endif
3025
+      #if HAS_E6_MICROSTEPS && PIN_EXISTS(E6_MS3)
3026
+        case  9: WRITE(E6_MS3_PIN, ms3); break;
3027
+      #endif
3028
+      #if HAS_E7_MICROSTEPS && PIN_EXISTS(E7_MS3)
3029
+        case 10: WRITE(E7_MS3_PIN, ms3); break;
2978 3030
       #endif
2979 3031
     }
2980 3032
   }
@@ -3084,6 +3136,22 @@ void Stepper::report_positions() {
3084 3136
         #endif
3085 3137
       );
3086 3138
     #endif
3139
+    #if HAS_E6_MICROSTEPS
3140
+      SERIAL_ECHOPGM("E6: ");
3141
+      SERIAL_CHAR('0' + READ(E6_MS1_PIN), '0' + READ(E6_MS2_PIN)
3142
+        #if PIN_EXISTS(E6_MS3)
3143
+          , '0' + READ(E6_MS3_PIN)
3144
+        #endif
3145
+      );
3146
+    #endif
3147
+    #if HAS_E7_MICROSTEPS
3148
+      SERIAL_ECHOPGM("E7: ");
3149
+      SERIAL_CHAR('0' + READ(E7_MS1_PIN), '0' + READ(E7_MS2_PIN)
3150
+        #if PIN_EXISTS(E7_MS3)
3151
+          , '0' + READ(E7_MS3_PIN)
3152
+        #endif
3153
+      );
3154
+    #endif
3087 3155
   }
3088 3156
 
3089 3157
 #endif // HAS_MICROSTEPS

+ 34
- 0
Marlin/src/module/stepper/L64xx.h View File

@@ -278,3 +278,37 @@
278 278
     #define E5_DIR_READ()        (stepper##E5.getStatus() & STATUS_DIR);
279 279
   #endif
280 280
 #endif
281
+
282
+// E6 Stepper
283
+#if AXIS_IS_L64XX(E6)
284
+  extern L64XX_CLASS(E6)         stepperE6;
285
+  #define E6_ENABLE_INIT()       NOOP
286
+  #define E6_ENABLE_WRITE(STATE) (STATE ? NOOP : stepperE6.free())
287
+  #define E6_ENABLE_READ()       (stepperE6.getStatus() & STATUS_HIZ)
288
+  #if AXIS_DRIVER_TYPE_E6(L6474)
289
+    #define E6_DIR_INIT()        SET_OUTPUT(E6_DIR_PIN)
290
+    #define E6_DIR_WRITE(STATE)  L6474_DIR_WRITE(E6, STATE)
291
+    #define E6_DIR_READ()        READ(E6_DIR_PIN)
292
+  #else
293
+    #define E6_DIR_INIT()        NOOP
294
+    #define E6_DIR_WRITE(STATE)  L64XX_DIR_WRITE(E6, STATE)
295
+    #define E6_DIR_READ()        (stepper##E6.getStatus() & STATUS_DIR);
296
+  #endif
297
+#endif
298
+
299
+// E7 Stepper
300
+#if AXIS_IS_L64XX(E7)
301
+  extern L64XX_CLASS(E7)         stepperE7;
302
+  #define E7_ENABLE_INIT()       NOOP
303
+  #define E7_ENABLE_WRITE(STATE) (STATE ? NOOP : stepperE7.free())
304
+  #define E7_ENABLE_READ()       (stepperE7.getStatus() & STATUS_HIZ)
305
+  #if AXIS_DRIVER_TYPE_E7(L6474)
306
+    #define E7_DIR_INIT()        SET_OUTPUT(E7_DIR_PIN)
307
+    #define E7_DIR_WRITE(STATE)  L6474_DIR_WRITE(E7, STATE)
308
+    #define E7_DIR_READ()        READ(E7_DIR_PIN)
309
+  #else
310
+    #define E7_DIR_INIT()        NOOP
311
+    #define E7_DIR_WRITE(STATE)  L64XX_DIR_WRITE(E7, STATE)
312
+    #define E7_DIR_READ()        (stepper##E7.getStatus() & STATUS_DIR);
313
+  #endif
314
+#endif

+ 16
- 0
Marlin/src/module/stepper/TMC26X.h View File

@@ -150,3 +150,19 @@ void tmc26x_init_to_defaults();
150 150
   #define E5_ENABLE_WRITE(STATE) stepperE5.setEnabled(STATE)
151 151
   #define E5_ENABLE_READ() stepperE5.isEnabled()
152 152
 #endif
153
+
154
+// E6 Stepper
155
+#if AXIS_DRIVER_TYPE_E6(TMC26X)
156
+  extern TMC26XStepper stepperE6;
157
+  #define E6_ENABLE_INIT() NOOP
158
+  #define E6_ENABLE_WRITE(STATE) stepperE6.setEnabled(STATE)
159
+  #define E6_ENABLE_READ() stepperE6.isEnabled()
160
+#endif
161
+
162
+// E7 Stepper
163
+#if AXIS_DRIVER_TYPE_E7(TMC26X)
164
+  extern TMC26XStepper stepperE7;
165
+  #define E7_ENABLE_INIT() NOOP
166
+  #define E7_ENABLE_WRITE(STATE) stepperE7.setEnabled(STATE)
167
+  #define E7_ENABLE_READ() stepperE7.isEnabled()
168
+#endif

+ 245
- 21
Marlin/src/module/stepper/indirection.h View File

@@ -303,26 +303,115 @@ void reset_stepper_drivers();    // Called by settings.load / settings.reset
303 303
 #endif
304 304
 #define E5_STEP_READ() bool(READ(E5_STEP_PIN))
305 305
 
306
+// E6 Stepper
307
+#ifndef E6_ENABLE_INIT
308
+  #define E6_ENABLE_INIT() SET_OUTPUT(E6_ENABLE_PIN)
309
+  #define E6_ENABLE_WRITE(STATE) WRITE(E6_ENABLE_PIN,STATE)
310
+  #define E6_ENABLE_READ() bool(READ(E6_ENABLE_PIN))
311
+#endif
312
+#ifndef E6_DIR_INIT
313
+  #define E6_DIR_INIT() SET_OUTPUT(E6_DIR_PIN)
314
+  #define E6_DIR_WRITE(STATE) WRITE(E6_DIR_PIN,STATE)
315
+  #define E6_DIR_READ() bool(READ(E6_DIR_PIN))
316
+#endif
317
+#define E6_STEP_INIT() SET_OUTPUT(E6_STEP_PIN)
318
+#ifndef E6_STEP_WRITE
319
+  #define E6_STEP_WRITE(STATE) WRITE(E6_STEP_PIN,STATE)
320
+#endif
321
+#define E6_STEP_READ() bool(READ(E6_STEP_PIN))
322
+
323
+// E7 Stepper
324
+#ifndef E7_ENABLE_INIT
325
+  #define E7_ENABLE_INIT() SET_OUTPUT(E7_ENABLE_PIN)
326
+  #define E7_ENABLE_WRITE(STATE) WRITE(E7_ENABLE_PIN,STATE)
327
+  #define E7_ENABLE_READ() bool(READ(E7_ENABLE_PIN))
328
+#endif
329
+#ifndef E7_DIR_INIT
330
+  #define E7_DIR_INIT() SET_OUTPUT(E7_DIR_PIN)
331
+  #define E7_DIR_WRITE(STATE) WRITE(E7_DIR_PIN,STATE)
332
+  #define E7_DIR_READ() bool(READ(E7_DIR_PIN))
333
+#endif
334
+#define E7_STEP_INIT() SET_OUTPUT(E7_STEP_PIN)
335
+#ifndef E7_STEP_WRITE
336
+  #define E7_STEP_WRITE(STATE) WRITE(E7_STEP_PIN,STATE)
337
+#endif
338
+#define E7_STEP_READ() bool(READ(E7_STEP_PIN))
339
+
306 340
 /**
307 341
  * Extruder indirection for the single E axis
308 342
  */
309 343
 #if ENABLED(SWITCHING_EXTRUDER) // One stepper driver per two extruders, reversed on odd index
310
-  #if EXTRUDERS > 5
344
+  #if EXTRUDERS > 7
345
+    #define E_STEP_WRITE(E,V) do{ if (E < 2) { E0_STEP_WRITE(V); } else if (E < 4) { E1_STEP_WRITE(V); } else if (E < 6) { E2_STEP_WRITE(V); } else { E3_STEP_WRITE(V); } }while(0)
346
+    #define   NORM_E_DIR(E)   do{ switch (E) { \
347
+        case 0: E0_DIR_WRITE(!INVERT_E0_DIR); break; case 1: E0_DIR_WRITE( INVERT_E0_DIR); break; \
348
+        case 2: E1_DIR_WRITE(!INVERT_E1_DIR); break; case 3: E1_DIR_WRITE( INVERT_E1_DIR); break; \
349
+        case 4: E2_DIR_WRITE(!INVERT_E2_DIR); break; case 5: E2_DIR_WRITE( INVERT_E2_DIR); break; \
350
+        case 6: E3_DIR_WRITE( INVERT_E3_DIR); break; case 7: E3_DIR_WRITE( INVERT_E3_DIR); break; \
351
+      } }while(0)
352
+    #define    REV_E_DIR(E)   do{ switch (E) { \
353
+        case 0: E0_DIR_WRITE( INVERT_E0_DIR); break; case 1: E0_DIR_WRITE(!INVERT_E0_DIR); break; \
354
+        case 2: E1_DIR_WRITE( INVERT_E1_DIR); break; case 3: E1_DIR_WRITE(!INVERT_E1_DIR); break; \
355
+        case 4: E2_DIR_WRITE( INVERT_E2_DIR); break; case 5: E2_DIR_WRITE(!INVERT_E2_DIR); break; \
356
+        case 6: E3_DIR_WRITE(!INVERT_E3_DIR); break; case 7: E3_DIR_WRITE(!INVERT_E3_DIR); break; \
357
+      } }while(0)
358
+  #elif EXTRUDERS > 6
359
+    #define E_STEP_WRITE(E,V) do{ if (E < 2) { E0_STEP_WRITE(V); } else if (E < 4) { E1_STEP_WRITE(V); } else if (E < 6) { E2_STEP_WRITE(V); } else { E3_STEP_WRITE(V); } }while(0)
360
+    #define   NORM_E_DIR(E)   do{ switch (E) { \
361
+        case 0: E0_DIR_WRITE(!INVERT_E0_DIR); break; case 1: E0_DIR_WRITE( INVERT_E0_DIR); break; \
362
+        case 2: E1_DIR_WRITE(!INVERT_E1_DIR); break; case 3: E1_DIR_WRITE( INVERT_E1_DIR); break; \
363
+        case 4: E2_DIR_WRITE(!INVERT_E2_DIR); break; case 5: E2_DIR_WRITE( INVERT_E2_DIR); break; \
364
+        case 6: E3_DIR_WRITE( INVERT_E3_DIR); break; \
365
+      } }while(0)
366
+    #define    REV_E_DIR(E)   do{ switch (E) { \
367
+        case 0: E0_DIR_WRITE( INVERT_E0_DIR); break; case 1: E0_DIR_WRITE(!INVERT_E0_DIR); break; \
368
+        case 2: E1_DIR_WRITE( INVERT_E1_DIR); break; case 3: E1_DIR_WRITE(!INVERT_E1_DIR); break; \
369
+        case 4: E2_DIR_WRITE( INVERT_E2_DIR); break; case 5: E2_DIR_WRITE(!INVERT_E2_DIR); break; \
370
+        case 6: E3_DIR_WRITE(!INVERT_E3_DIR); } }while(0)
371
+  #elif EXTRUDERS > 5
311 372
     #define E_STEP_WRITE(E,V) do{ if (E < 2) { E0_STEP_WRITE(V); } else if (E < 4) { E1_STEP_WRITE(V); } else { E2_STEP_WRITE(V); } }while(0)
312
-    #define   NORM_E_DIR(E)   do{ switch (E) { case 0: E0_DIR_WRITE(!INVERT_E0_DIR); break; case 1: E0_DIR_WRITE( INVERT_E0_DIR); break; case 2: E1_DIR_WRITE(!INVERT_E1_DIR); break; case 3: E1_DIR_WRITE( INVERT_E1_DIR); break; case 4: E2_DIR_WRITE(!INVERT_E2_DIR); case 5: E2_DIR_WRITE( INVERT_E2_DIR); } }while(0)
313
-    #define    REV_E_DIR(E)   do{ switch (E) { case 0: E0_DIR_WRITE( INVERT_E0_DIR); break; case 1: E0_DIR_WRITE(!INVERT_E0_DIR); break; case 2: E1_DIR_WRITE( INVERT_E1_DIR); break; case 3: E1_DIR_WRITE(!INVERT_E1_DIR); break; case 4: E2_DIR_WRITE( INVERT_E2_DIR); case 5: E2_DIR_WRITE(!INVERT_E2_DIR); } }while(0)
373
+    #define   NORM_E_DIR(E)   do{ switch (E) { \
374
+        case 0: E0_DIR_WRITE(!INVERT_E0_DIR); break; case 1: E0_DIR_WRITE( INVERT_E0_DIR); break; \
375
+        case 2: E1_DIR_WRITE(!INVERT_E1_DIR); break; case 3: E1_DIR_WRITE( INVERT_E1_DIR); break; \
376
+        case 4: E2_DIR_WRITE(!INVERT_E2_DIR); break; case 5: E2_DIR_WRITE( INVERT_E2_DIR); break; \
377
+      } }while(0)
378
+    #define    REV_E_DIR(E)   do{ switch (E) { \
379
+        case 0: E0_DIR_WRITE( INVERT_E0_DIR); break; case 1: E0_DIR_WRITE(!INVERT_E0_DIR); break; \
380
+        case 2: E1_DIR_WRITE( INVERT_E1_DIR); break; case 3: E1_DIR_WRITE(!INVERT_E1_DIR); break; \
381
+        case 4: E2_DIR_WRITE( INVERT_E2_DIR); break; case 5: E2_DIR_WRITE(!INVERT_E2_DIR); break; \
382
+      } }while(0)
314 383
   #elif EXTRUDERS > 4
315 384
     #define E_STEP_WRITE(E,V) do{ if (E < 2) { E0_STEP_WRITE(V); } else if (E < 4) { E1_STEP_WRITE(V); } else { E2_STEP_WRITE(V); } }while(0)
316
-    #define   NORM_E_DIR(E)   do{ switch (E) { case 0: E0_DIR_WRITE(!INVERT_E0_DIR); break; case 1: E0_DIR_WRITE( INVERT_E0_DIR); break; case 2: E1_DIR_WRITE(!INVERT_E1_DIR); break; case 3: E1_DIR_WRITE( INVERT_E1_DIR); break; case 4: E2_DIR_WRITE(!INVERT_E2_DIR); } }while(0)
317
-    #define    REV_E_DIR(E)   do{ switch (E) { case 0: E0_DIR_WRITE( INVERT_E0_DIR); break; case 1: E0_DIR_WRITE(!INVERT_E0_DIR); break; case 2: E1_DIR_WRITE( INVERT_E1_DIR); break; case 3: E1_DIR_WRITE(!INVERT_E1_DIR); break; case 4: E2_DIR_WRITE( INVERT_E2_DIR); } }while(0)
385
+    #define   NORM_E_DIR(E)   do{ switch (E) { \
386
+        case 0: E0_DIR_WRITE(!INVERT_E0_DIR); break; case 1: E0_DIR_WRITE( INVERT_E0_DIR); break; \
387
+        case 2: E1_DIR_WRITE(!INVERT_E1_DIR); break; case 3: E1_DIR_WRITE( INVERT_E1_DIR); break; \
388
+        case 4: E2_DIR_WRITE(!INVERT_E2_DIR); break; \
389
+      } }while(0)
390
+    #define    REV_E_DIR(E)   do{ switch (E) { \
391
+        case 0: E0_DIR_WRITE( INVERT_E0_DIR); break; case 1: E0_DIR_WRITE(!INVERT_E0_DIR); break; \
392
+        case 2: E1_DIR_WRITE( INVERT_E1_DIR); break; case 3: E1_DIR_WRITE(!INVERT_E1_DIR); break; \
393
+        case 4: E2_DIR_WRITE( INVERT_E2_DIR); break; \
394
+      } }while(0)
318 395
   #elif EXTRUDERS > 3
319 396
     #define E_STEP_WRITE(E,V) do{ if (E < 2) { E0_STEP_WRITE(V); } else { E1_STEP_WRITE(V); } }while(0)
320
-    #define   NORM_E_DIR(E)   do{ switch (E) { case 0: E0_DIR_WRITE(!INVERT_E0_DIR); break; case 1: E0_DIR_WRITE( INVERT_E0_DIR); break; case 2: E1_DIR_WRITE(!INVERT_E1_DIR); break; case 3: E1_DIR_WRITE( INVERT_E1_DIR); } }while(0)
321
-    #define    REV_E_DIR(E)   do{ switch (E) { case 0: E0_DIR_WRITE( INVERT_E0_DIR); break; case 1: E0_DIR_WRITE(!INVERT_E0_DIR); break; case 2: E1_DIR_WRITE( INVERT_E1_DIR); break; case 3: E1_DIR_WRITE(!INVERT_E1_DIR); } }while(0)
397
+    #define   NORM_E_DIR(E)   do{ switch (E) { \
398
+        case 0: E0_DIR_WRITE(!INVERT_E0_DIR); break; case 1: E0_DIR_WRITE( INVERT_E0_DIR); break; \
399
+        case 2: E1_DIR_WRITE(!INVERT_E1_DIR); break; case 3: E1_DIR_WRITE( INVERT_E1_DIR); break; \
400
+      } }while(0)
401
+    #define    REV_E_DIR(E)   do{ switch (E) { \
402
+        case 0: E0_DIR_WRITE( INVERT_E0_DIR); break; case 1: E0_DIR_WRITE(!INVERT_E0_DIR); break; \
403
+        case 2: E1_DIR_WRITE( INVERT_E1_DIR); break; case 3: E1_DIR_WRITE(!INVERT_E1_DIR); break; \
404
+      } }while(0)
322 405
   #elif EXTRUDERS > 2
323 406
     #define E_STEP_WRITE(E,V) do{ if (E < 2) { E0_STEP_WRITE(V); } else { E1_STEP_WRITE(V); } }while(0)
324
-    #define   NORM_E_DIR(E)   do{ switch (E) { case 0: E0_DIR_WRITE(!INVERT_E0_DIR); break; case 1: E0_DIR_WRITE( INVERT_E0_DIR); break; case 2: E1_DIR_WRITE(!INVERT_E1_DIR); } }while(0)
325
-    #define    REV_E_DIR(E)   do{ switch (E) { case 0: E0_DIR_WRITE( INVERT_E0_DIR); break; case 1: E0_DIR_WRITE(!INVERT_E0_DIR); break; case 2: E1_DIR_WRITE( INVERT_E1_DIR); } }while(0)
407
+    #define   NORM_E_DIR(E)   do{ switch (E) { \
408
+        case 0: E0_DIR_WRITE(!INVERT_E0_DIR); break; case 1: E0_DIR_WRITE( INVERT_E0_DIR); break; \
409
+        case 2: E1_DIR_WRITE(!INVERT_E1_DIR); break; \
410
+      } }while(0)
411
+    #define    REV_E_DIR(E)   do{ switch (E) { \
412
+        case 0: E0_DIR_WRITE( INVERT_E0_DIR); break; case 1: E0_DIR_WRITE(!INVERT_E0_DIR); break; \
413
+        case 2: E1_DIR_WRITE( INVERT_E1_DIR); break; \
414
+      } }while(0)
326 415
   #else
327 416
     #define E_STEP_WRITE(E,V) E0_STEP_WRITE(V)
328 417
     #define   NORM_E_DIR(E)   do{ E0_DIR_WRITE(E ?  INVERT_E0_DIR : !INVERT_E0_DIR); }while(0)
@@ -340,23 +429,100 @@ void reset_stepper_drivers();    // Called by settings.load / settings.reset
340 429
 
341 430
 #elif E_STEPPERS > 1
342 431
 
343
-  #if E_STEPPERS > 5
344
-    #define _E_STEP_WRITE(E,V) do{ switch (E) { case 0: E0_STEP_WRITE(V); break; case 1: E1_STEP_WRITE(V); break; case 2: E2_STEP_WRITE(V); break; case 3: E3_STEP_WRITE(V); break; case 4: E4_STEP_WRITE(V); case 5: E5_STEP_WRITE(V); } }while(0)
345
-    #define   _NORM_E_DIR(E)   do{ switch (E) { case 0: E0_DIR_WRITE(!INVERT_E0_DIR); break; case 1: E1_DIR_WRITE(!INVERT_E1_DIR); break; case 2: E2_DIR_WRITE(!INVERT_E2_DIR); break; case 3: E3_DIR_WRITE(!INVERT_E3_DIR); break; case 4: E4_DIR_WRITE(!INVERT_E4_DIR); case 5: E5_DIR_WRITE(!INVERT_E5_DIR); } }while(0)
346
-    #define    _REV_E_DIR(E)   do{ switch (E) { case 0: E0_DIR_WRITE( INVERT_E0_DIR); break; case 1: E1_DIR_WRITE( INVERT_E1_DIR); break; case 2: E2_DIR_WRITE( INVERT_E2_DIR); break; case 3: E3_DIR_WRITE( INVERT_E3_DIR); break; case 4: E4_DIR_WRITE( INVERT_E4_DIR); case 5: E5_DIR_WRITE( INVERT_E5_DIR); } }while(0)
432
+  #if E_STEPPERS > 7
433
+
434
+    #define _E_STEP_WRITE(E,V) do{ switch (E) { \
435
+        case 0: E0_STEP_WRITE(V); break; case 1: E1_STEP_WRITE(V); break; case 2: E2_STEP_WRITE(V); break; case 3: E3_STEP_WRITE(V); break; \
436
+        case 4: E4_STEP_WRITE(V); break; case 5: E5_STEP_WRITE(V); break; case 6: E6_STEP_WRITE(V); break; case 7: E7_STEP_WRITE(V); break; \
437
+      } }while(0)
438
+    #define   _NORM_E_DIR(E)   do{ switch (E) { \
439
+        case 0: E0_DIR_WRITE(!INVERT_E0_DIR); break; case 1: E1_DIR_WRITE(!INVERT_E1_DIR); break; \
440
+        case 2: E2_DIR_WRITE(!INVERT_E2_DIR); break; case 3: E3_DIR_WRITE(!INVERT_E3_DIR); break; \
441
+        case 4: E4_DIR_WRITE(!INVERT_E4_DIR); break; case 5: E5_DIR_WRITE(!INVERT_E5_DIR); break; \
442
+        case 6: E6_DIR_WRITE(!INVERT_E6_DIR); break; case 7: E7_DIR_WRITE(!INVERT_E7_DIR); break; \
443
+      } }while(0)
444
+    #define    _REV_E_DIR(E)   do{ switch (E) { \
445
+        case 0: E0_DIR_WRITE( INVERT_E0_DIR); break; case 1: E1_DIR_WRITE( INVERT_E1_DIR); break; \
446
+        case 2: E2_DIR_WRITE( INVERT_E2_DIR); break; case 3: E3_DIR_WRITE( INVERT_E3_DIR); break; \
447
+        case 4: E4_DIR_WRITE( INVERT_E4_DIR); break; case 5: E5_DIR_WRITE( INVERT_E5_DIR); break; \
448
+        case 6: E6_DIR_WRITE( INVERT_E6_DIR); break; case 7: E7_DIR_WRITE( INVERT_E7_DIR); break; \
449
+      } }while(0)
450
+
451
+  #elif E_STEPPERS > 6
452
+
453
+    #define _E_STEP_WRITE(E,V) do{ switch (E) { \
454
+        case 0: E0_STEP_WRITE(V); break; case 1: E1_STEP_WRITE(V); break; case 2: E2_STEP_WRITE(V); break; case 3: E3_STEP_WRITE(V); break; \
455
+        case 4: E4_STEP_WRITE(V); break; case 5: E5_STEP_WRITE(V); break; case 6: E6_STEP_WRITE(V); break; \
456
+      } }while(0)
457
+    #define   _NORM_E_DIR(E)   do{ switch (E) { \
458
+        case 0: E0_DIR_WRITE(!INVERT_E0_DIR); break; case 1: E1_DIR_WRITE(!INVERT_E1_DIR); break; \
459
+        case 2: E2_DIR_WRITE(!INVERT_E2_DIR); break; case 3: E3_DIR_WRITE(!INVERT_E3_DIR); break; \
460
+        case 4: E4_DIR_WRITE(!INVERT_E4_DIR); break; case 5: E5_DIR_WRITE(!INVERT_E5_DIR); break; \
461
+        case 6: E6_DIR_WRITE(!INVERT_E6_DIR); break; \
462
+      } }while(0)
463
+    #define    _REV_E_DIR(E)   do{ switch (E) { \
464
+        case 0: E0_DIR_WRITE( INVERT_E0_DIR); break; case 1: E1_DIR_WRITE( INVERT_E1_DIR); break; \
465
+        case 2: E2_DIR_WRITE( INVERT_E2_DIR); break; case 3: E3_DIR_WRITE( INVERT_E3_DIR); break; \
466
+        case 4: E4_DIR_WRITE( INVERT_E4_DIR); break; case 5: E5_DIR_WRITE( INVERT_E5_DIR); break; \
467
+        case 6: E6_DIR_WRITE( INVERT_E6_DIR); break; \
468
+      } }while(0)
469
+
470
+  #elif E_STEPPERS > 5
471
+
472
+    #define _E_STEP_WRITE(E,V) do{ switch (E) { \
473
+        case 0: E0_STEP_WRITE(V); break; case 1: E1_STEP_WRITE(V); break; case 2: E2_STEP_WRITE(V); break; case 3: E3_STEP_WRITE(V); break; \
474
+        case 4: E4_STEP_WRITE(V); break; case 5: E5_STEP_WRITE(V); break; \
475
+      } }while(0)
476
+    #define   _NORM_E_DIR(E)   do{ switch (E) { \
477
+        case 0: E0_DIR_WRITE(!INVERT_E0_DIR); break; case 1: E1_DIR_WRITE(!INVERT_E1_DIR); break; \
478
+        case 2: E2_DIR_WRITE(!INVERT_E2_DIR); break; case 3: E3_DIR_WRITE(!INVERT_E3_DIR); break; \
479
+        case 4: E4_DIR_WRITE(!INVERT_E4_DIR); break; case 5: E5_DIR_WRITE(!INVERT_E5_DIR); break; \
480
+      } }while(0)
481
+    #define    _REV_E_DIR(E)   do{ switch (E) { \
482
+        case 0: E0_DIR_WRITE( INVERT_E0_DIR); break; case 1: E1_DIR_WRITE( INVERT_E1_DIR); break; \
483
+        case 2: E2_DIR_WRITE( INVERT_E2_DIR); break; case 3: E3_DIR_WRITE( INVERT_E3_DIR); break; \
484
+        case 4: E4_DIR_WRITE( INVERT_E4_DIR); break; case 5: E5_DIR_WRITE( INVERT_E5_DIR); break; \
485
+      } }while(0)
486
+
347 487
   #elif E_STEPPERS > 4
348
-    #define _E_STEP_WRITE(E,V) do{ switch (E) { case 0: E0_STEP_WRITE(V); break; case 1: E1_STEP_WRITE(V); break; case 2: E2_STEP_WRITE(V); break; case 3: E3_STEP_WRITE(V); break; case 4: E4_STEP_WRITE(V); } }while(0)
349
-    #define   _NORM_E_DIR(E)   do{ switch (E) { case 0: E0_DIR_WRITE(!INVERT_E0_DIR); break; case 1: E1_DIR_WRITE(!INVERT_E1_DIR); break; case 2: E2_DIR_WRITE(!INVERT_E2_DIR); break; case 3: E3_DIR_WRITE(!INVERT_E3_DIR); break; case 4: E4_DIR_WRITE(!INVERT_E4_DIR); } }while(0)
350
-    #define    _REV_E_DIR(E)   do{ switch (E) { case 0: E0_DIR_WRITE( INVERT_E0_DIR); break; case 1: E1_DIR_WRITE( INVERT_E1_DIR); break; case 2: E2_DIR_WRITE( INVERT_E2_DIR); break; case 3: E3_DIR_WRITE( INVERT_E3_DIR); break; case 4: E4_DIR_WRITE( INVERT_E4_DIR); } }while(0)
488
+
489
+    #define _E_STEP_WRITE(E,V) do{ switch (E) { \
490
+        case 0: E0_STEP_WRITE(V); break; case 1: E1_STEP_WRITE(V); break; case 2: E2_STEP_WRITE(V); break; case 3: E3_STEP_WRITE(V); break; \
491
+        case 4: E4_STEP_WRITE(V); break; \
492
+      } }while(0)
493
+    #define   _NORM_E_DIR(E)   do{ switch (E) { \
494
+        case 0: E0_DIR_WRITE(!INVERT_E0_DIR); break; case 1: E1_DIR_WRITE(!INVERT_E1_DIR); break; \
495
+        case 2: E2_DIR_WRITE(!INVERT_E2_DIR); break; case 3: E3_DIR_WRITE(!INVERT_E3_DIR); break; \
496
+        case 4: E4_DIR_WRITE(!INVERT_E4_DIR); break; \
497
+      } }while(0)
498
+    #define    _REV_E_DIR(E)   do{ switch (E) { \
499
+        case 0: E0_DIR_WRITE( INVERT_E0_DIR); break; case 1: E1_DIR_WRITE( INVERT_E1_DIR); break; \
500
+        case 2: E2_DIR_WRITE( INVERT_E2_DIR); break; case 3: E3_DIR_WRITE( INVERT_E3_DIR); break; \
501
+        case 4: E4_DIR_WRITE( INVERT_E4_DIR); break; \
502
+      } }while(0)
503
+
351 504
   #elif E_STEPPERS > 3
352
-    #define _E_STEP_WRITE(E,V) do{ switch (E) { case 0: E0_STEP_WRITE(V); break; case 1: E1_STEP_WRITE(V); break; case 2: E2_STEP_WRITE(V); break; case 3: E3_STEP_WRITE(V); } }while(0)
353
-    #define   _NORM_E_DIR(E)   do{ switch (E) { case 0: E0_DIR_WRITE(!INVERT_E0_DIR); break; case 1: E1_DIR_WRITE(!INVERT_E1_DIR); break; case 2: E2_DIR_WRITE(!INVERT_E2_DIR); break; case 3: E3_DIR_WRITE(!INVERT_E3_DIR); } }while(0)
354
-    #define    _REV_E_DIR(E)   do{ switch (E) { case 0: E0_DIR_WRITE( INVERT_E0_DIR); break; case 1: E1_DIR_WRITE( INVERT_E1_DIR); break; case 2: E2_DIR_WRITE( INVERT_E2_DIR); break; case 3: E3_DIR_WRITE( INVERT_E3_DIR); } }while(0)
505
+
506
+    #define _E_STEP_WRITE(E,V) do{ switch (E) { \
507
+        case 0: E0_STEP_WRITE(V); break; case 1: E1_STEP_WRITE(V); break; case 2: E2_STEP_WRITE(V); break; case 3: E3_STEP_WRITE(V); break; \
508
+      } }while(0)
509
+    #define   _NORM_E_DIR(E)   do{ switch (E) { \
510
+        case 0: E0_DIR_WRITE(!INVERT_E0_DIR); break; case 1: E1_DIR_WRITE(!INVERT_E1_DIR); break; \
511
+        case 2: E2_DIR_WRITE(!INVERT_E2_DIR); break; case 3: E3_DIR_WRITE(!INVERT_E3_DIR); break; \
512
+      } }while(0)
513
+    #define    _REV_E_DIR(E)   do{ switch (E) { \
514
+        case 0: E0_DIR_WRITE( INVERT_E0_DIR); break; case 1: E1_DIR_WRITE( INVERT_E1_DIR); break; \
515
+        case 2: E2_DIR_WRITE( INVERT_E2_DIR); break; case 3: E3_DIR_WRITE( INVERT_E3_DIR); break; \
516
+      } }while(0)
517
+
355 518
   #elif E_STEPPERS > 2
519
+
356 520
     #define _E_STEP_WRITE(E,V) do{ switch (E) { case 0: E0_STEP_WRITE(V); break; case 1: E1_STEP_WRITE(V); break; case 2: E2_STEP_WRITE(V); } }while(0)
357 521
     #define   _NORM_E_DIR(E)   do{ switch (E) { case 0: E0_DIR_WRITE(!INVERT_E0_DIR); break; case 1: E1_DIR_WRITE(!INVERT_E1_DIR); break; case 2: E2_DIR_WRITE(!INVERT_E2_DIR); } }while(0)
358 522
     #define    _REV_E_DIR(E)   do{ switch (E) { case 0: E0_DIR_WRITE( INVERT_E0_DIR); break; case 1: E1_DIR_WRITE( INVERT_E1_DIR); break; case 2: E2_DIR_WRITE( INVERT_E2_DIR); } }while(0)
523
+
359 524
   #else
525
+
360 526
     #define _E_STEP_WRITE(E,V) do{ if (E == 0) { E0_STEP_WRITE(V); } else { E1_STEP_WRITE(V); } }while(0)
361 527
     #define   _NORM_E_DIR(E)   do{ if (E == 0) { E0_DIR_WRITE(!INVERT_E0_DIR); } else { E1_DIR_WRITE(!INVERT_E1_DIR); } }while(0)
362 528
     #define    _REV_E_DIR(E)   do{ if (E == 0) { E0_DIR_WRITE( INVERT_E0_DIR); } else { E1_DIR_WRITE( INVERT_E1_DIR); } }while(0)
@@ -376,7 +542,15 @@ void reset_stepper_drivers();    // Called by settings.load / settings.reset
376 542
     #define E_STEP_WRITE(E,V) do{ if (extruder_duplication_enabled) { DUPE(STEP,V); } else _E_STEP_WRITE(E,V); }while(0)
377 543
 
378 544
     #if E_STEPPERS > 2
379
-      #if E_STEPPERS > 5
545
+      #if E_STEPPERS > 7
546
+        #define DUPE(T,V)     do{ _DUPE(0,T,V); _DUPE(1,T,V); _DUPE(2,T,V); _DUPE(3,T,V); _DUPE(4,T,V); _DUPE(5,T,V); _DUPE(6,T,V); _DUPE(7,T,V); }while(0)
547
+        #define NORM_E_DIR(E) do{ if (extruder_duplication_enabled) { NDIR(0); NDIR(1); NDIR(2); NDIR(3); NDIR(4); NDIR(5); NDIR(6); NDIR(7); } else _NORM_E_DIR(E); }while(0)
548
+        #define REV_E_DIR(E)  do{ if (extruder_duplication_enabled) { RDIR(0); RDIR(1); RDIR(2); RDIR(3); RDIR(4); RDIR(5); RDIR(6); RDIR(7); } else  _REV_E_DIR(E); }while(0)
549
+      #elif E_STEPPERS > 6
550
+        #define DUPE(T,V)     do{ _DUPE(0,T,V); _DUPE(1,T,V); _DUPE(2,T,V); _DUPE(3,T,V); _DUPE(4,T,V); _DUPE(5,T,V); _DUPE(6,T,V); }while(0)
551
+        #define NORM_E_DIR(E) do{ if (extruder_duplication_enabled) { NDIR(0); NDIR(1); NDIR(2); NDIR(3); NDIR(4); NDIR(5); NDIR(6); } else _NORM_E_DIR(E); }while(0)
552
+        #define REV_E_DIR(E)  do{ if (extruder_duplication_enabled) { RDIR(0); RDIR(1); RDIR(2); RDIR(3); RDIR(4); RDIR(5); RDIR(6); } else  _REV_E_DIR(E); }while(0)
553
+      #elif E_STEPPERS > 5
380 554
         #define DUPE(T,V)     do{ _DUPE(0,T,V); _DUPE(1,T,V); _DUPE(2,T,V); _DUPE(3,T,V); _DUPE(4,T,V); _DUPE(5,T,V); }while(0)
381 555
         #define NORM_E_DIR(E) do{ if (extruder_duplication_enabled) { NDIR(0); NDIR(1); NDIR(2); NDIR(3); NDIR(4); NDIR(5); } else _NORM_E_DIR(E); }while(0)
382 556
         #define REV_E_DIR(E)  do{ if (extruder_duplication_enabled) { RDIR(0); RDIR(1); RDIR(2); RDIR(3); RDIR(4); RDIR(5); } else  _REV_E_DIR(E); }while(0)
@@ -604,12 +778,42 @@ void reset_stepper_drivers();    // Called by settings.load / settings.reset
604 778
   #define E5_disable() NOOP
605 779
 #endif
606 780
 
781
+#if AXIS_DRIVER_TYPE_E6(L6470)
782
+  extern L6470 stepperE6;
783
+  #define  E6_enable() NOOP
784
+  #define E6_disable() do{ stepperE6.free(); CBI(axis_known_position, E_AXIS); }while(0)
785
+#elif E_STEPPERS > 6 && HAS_E6_ENABLE
786
+  #define  E6_enable() E6_ENABLE_WRITE( E_ENABLE_ON)
787
+  #define E6_disable() E6_ENABLE_WRITE(!E_ENABLE_ON)
788
+#else
789
+  #define  E6_enable() NOOP
790
+  #define E6_disable() NOOP
791
+#endif
792
+
793
+#if AXIS_DRIVER_TYPE_E7(L6470)
794
+  extern L6470 stepperE7;
795
+  #define  E7_enable() NOOP
796
+  #define E7_disable() do{ stepperE7.free(); CBI(axis_known_position, E_AXIS); }while(0)
797
+#elif E_STEPPERS > 7 && HAS_E7_ENABLE
798
+  #define  E7_enable() E7_ENABLE_WRITE( E_ENABLE_ON)
799
+  #define E7_disable() E7_ENABLE_WRITE(!E_ENABLE_ON)
800
+#else
801
+  #define  E7_enable() NOOP
802
+  #define E7_disable() NOOP
803
+#endif
804
+
607 805
 #if ENABLED(MIXING_EXTRUDER)
608 806
 
609 807
   /**
610 808
    * Mixing steppers synchronize their enable (and direction) together
611 809
    */
612
-  #if MIXING_STEPPERS > 5
810
+  #if MIXING_STEPPERS > 7
811
+    #define  enable_E0() { E0_enable();  E1_enable();  E2_enable();  E3_enable();  E4_enable();  E5_enable();  E6_enable();  E7_enable(); }
812
+    #define disable_E0() { E0_disable(); E1_disable(); E2_disable(); E3_disable(); E4_disable(); E5_disable(); E6_disable(); E7_disable(); }
813
+  #elif MIXING_STEPPERS > 6
814
+    #define  enable_E0() { E0_enable();  E1_enable();  E2_enable();  E3_enable();  E4_enable();  E5_enable();  E6_enable(); }
815
+    #define disable_E0() { E0_disable(); E1_disable(); E2_disable(); E3_disable(); E4_disable(); E5_disable(); E6_disable(); }
816
+  #elif MIXING_STEPPERS > 5
613 817
     #define  enable_E0() { E0_enable();  E1_enable();  E2_enable();  E3_enable();  E4_enable();  E5_enable(); }
614 818
     #define disable_E0() { E0_disable(); E1_disable(); E2_disable(); E3_disable(); E4_disable(); E5_disable(); }
615 819
   #elif MIXING_STEPPERS > 4
@@ -635,6 +839,10 @@ void reset_stepper_drivers();    // Called by settings.load / settings.reset
635 839
   #define disable_E4() NOOP
636 840
   #define  enable_E5() NOOP
637 841
   #define disable_E5() NOOP
842
+  #define  enable_E6() NOOP
843
+  #define disable_E6() NOOP
844
+  #define  enable_E7() NOOP
845
+  #define disable_E7() NOOP
638 846
 
639 847
 #else // !MIXING_EXTRUDER
640 848
 
@@ -686,4 +894,20 @@ void reset_stepper_drivers();    // Called by settings.load / settings.reset
686 894
     #define disable_E5() NOOP
687 895
   #endif
688 896
 
897
+  #if E_STEPPERS > 6 && HAS_E6_ENABLE
898
+    #define  enable_E6() E6_enable()
899
+    #define disable_E6() E6_disable()
900
+  #else
901
+    #define  enable_E6() NOOP
902
+    #define disable_E6() NOOP
903
+  #endif
904
+
905
+  #if E_STEPPERS > 7 && HAS_E7_ENABLE
906
+    #define  enable_E7() E7_enable()
907
+    #define disable_E7() E7_disable()
908
+  #else
909
+    #define  enable_E7() NOOP
910
+    #define disable_E7() NOOP
911
+  #endif
912
+
689 913
 #endif // !MIXING_EXTRUDER

+ 40
- 0
Marlin/src/module/stepper/trinamic.cpp View File

@@ -301,6 +301,20 @@ enum StealthIndex : uint8_t { STEALTH_AXIS_XY, STEALTH_AXIS_Z, STEALTH_AXIS_E };
301 301
       TMC_UART_DEFINE_E(SW, 5);
302 302
     #endif
303 303
   #endif
304
+  #if AXIS_HAS_UART(E6)
305
+    #ifdef E6_HARDWARE_SERIAL
306
+      TMC_UART_DEFINE_E(HW, 6);
307
+    #else
308
+      TMC_UART_DEFINE_E(SW, 6);
309
+    #endif
310
+  #endif
311
+  #if AXIS_HAS_UART(E7)
312
+    #ifdef E7_HARDWARE_SERIAL
313
+      TMC_UART_DEFINE_E(HW, 7);
314
+    #else
315
+      TMC_UART_DEFINE_E(SW, 7);
316
+    #endif
317
+  #endif
304 318
 
305 319
   void tmc_serial_begin() {
306 320
     #if AXIS_HAS_UART(X)
@@ -401,6 +415,20 @@ enum StealthIndex : uint8_t { STEALTH_AXIS_XY, STEALTH_AXIS_Z, STEALTH_AXIS_E };
401 415
         stepperE5.beginSerial(TMC_BAUD_RATE);
402 416
       #endif
403 417
     #endif
418
+    #if AXIS_HAS_UART(E6)
419
+      #ifdef E6_HARDWARE_SERIAL
420
+        E6_HARDWARE_SERIAL.begin(TMC_BAUD_RATE);
421
+      #else
422
+        stepperE6.beginSerial(TMC_BAUD_RATE);
423
+      #endif
424
+    #endif
425
+    #if AXIS_HAS_UART(E7)
426
+      #ifdef E7_HARDWARE_SERIAL
427
+        E7_HARDWARE_SERIAL.begin(TMC_BAUD_RATE);
428
+      #else
429
+        stepperE7.beginSerial(TMC_BAUD_RATE);
430
+      #endif
431
+    #endif
404 432
   }
405 433
 #endif
406 434
 
@@ -654,6 +682,12 @@ void restore_trinamic_drivers() {
654 682
   #if AXIS_IS_TMC(E5)
655 683
     stepperE5.push();
656 684
   #endif
685
+  #if AXIS_IS_TMC(E6)
686
+    stepperE6.push();
687
+  #endif
688
+  #if AXIS_IS_TMC(E7)
689
+    stepperE7.push();
690
+  #endif
657 691
 }
658 692
 
659 693
 void reset_trinamic_drivers() {
@@ -719,6 +753,12 @@ void reset_trinamic_drivers() {
719 753
   #if AXIS_IS_TMC(E5)
720 754
     _TMC_INIT(E5, STEALTH_AXIS_E);
721 755
   #endif
756
+  #if AXIS_IS_TMC(E6)
757
+    _TMC_INIT(E6, STEALTH_AXIS_E);
758
+  #endif
759
+  #if AXIS_IS_TMC(E7)
760
+    _TMC_INIT(E7, STEALTH_AXIS_E);
761
+  #endif
722 762
 
723 763
   #if USE_SENSORLESS
724 764
     #if X_SENSORLESS

+ 28
- 0
Marlin/src/module/stepper/trinamic.h View File

@@ -58,6 +58,8 @@
58 58
 #define TMC_E3_LABEL 'E', '3'
59 59
 #define TMC_E4_LABEL 'E', '4'
60 60
 #define TMC_E5_LABEL 'E', '5'
61
+#define TMC_E6_LABEL 'E', '6'
62
+#define TMC_E7_LABEL 'E', '7'
61 63
 
62 64
 #define __TMC_CLASS(TYPE, L, I, A) TMCMarlin<CLASS_##TYPE, L, I, A>
63 65
 #define _TMC_CLASS(TYPE, LandI, A) __TMC_CLASS(TYPE, LandI, A)
@@ -266,3 +268,29 @@ void reset_trinamic_drivers();
266 268
     #define E5_STEP_WRITE(STATE) do{ if(STATE) TOGGLE(E5_STEP_PIN); }while(0)
267 269
   #endif
268 270
 #endif
271
+
272
+// E6 Stepper
273
+#if AXIS_IS_TMC(E6)
274
+  extern TMC_CLASS_E(6) stepperE6;
275
+  #if ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E6)
276
+    #define E6_ENABLE_INIT() NOOP
277
+    #define E6_ENABLE_WRITE(STATE) stepperE6.toff((STATE)==E_ENABLE_ON ? chopper_timing.toff : 0)
278
+    #define E6_ENABLE_READ() stepperE6.isEnabled()
279
+  #endif
280
+  #if AXIS_HAS_SQUARE_WAVE(E6)
281
+    #define E6_STEP_WRITE(STATE) do{ if(STATE) TOGGLE(E6_STEP_PIN); }while(0)
282
+  #endif
283
+#endif
284
+
285
+// E7 Stepper
286
+#if AXIS_IS_TMC(E7)
287
+  extern TMC_CLASS_E(7) stepperE7;
288
+  #if ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E7)
289
+    #define E7_ENABLE_INIT() NOOP
290
+    #define E7_ENABLE_WRITE(STATE) stepperE7.toff((STATE)==E_ENABLE_ON ? chopper_timing.toff : 0)
291
+    #define E7_ENABLE_READ() stepperE7.isEnabled()
292
+  #endif
293
+  #if AXIS_HAS_SQUARE_WAVE(E7)
294
+    #define E7_STEP_WRITE(STATE) do{ if(STATE) TOGGLE(E7_STEP_PIN); }while(0)
295
+  #endif
296
+#endif

+ 176
- 6
Marlin/src/module/temperature.cpp View File

@@ -303,9 +303,11 @@ volatile bool Temperature::temp_meas_ready = false;
303 303
                          sensor_heater_2 { HEATER_2_RAW_LO_TEMP, HEATER_2_RAW_HI_TEMP, 0, 16383 },
304 304
                          sensor_heater_3 { HEATER_3_RAW_LO_TEMP, HEATER_3_RAW_HI_TEMP, 0, 16383 },
305 305
                          sensor_heater_4 { HEATER_4_RAW_LO_TEMP, HEATER_4_RAW_HI_TEMP, 0, 16383 },
306
-                         sensor_heater_5 { HEATER_5_RAW_LO_TEMP, HEATER_5_RAW_HI_TEMP, 0, 16383 };
306
+                         sensor_heater_5 { HEATER_5_RAW_LO_TEMP, HEATER_5_RAW_HI_TEMP, 0, 16383 },
307
+                         sensor_heater_6 { HEATER_6_RAW_LO_TEMP, HEATER_6_RAW_HI_TEMP, 0, 16383 },
308
+                         sensor_heater_7 { HEATER_7_RAW_LO_TEMP, HEATER_7_RAW_HI_TEMP, 0, 16383 };
307 309
 
308
-  temp_range_t Temperature::temp_range[HOTENDS] = ARRAY_BY_HOTENDS(sensor_heater_0, sensor_heater_1, sensor_heater_2, sensor_heater_3, sensor_heater_4, sensor_heater_5);
310
+  temp_range_t Temperature::temp_range[HOTENDS] = ARRAY_BY_HOTENDS(sensor_heater_0, sensor_heater_1, sensor_heater_2, sensor_heater_3, sensor_heater_4, sensor_heater_5, sensor_heater_6, sensor_heater_7);
309 311
 #endif
310 312
 
311 313
 #ifdef MAX_CONSECUTIVE_LOW_TEMPERATURE_ERROR_ALLOWED
@@ -686,6 +688,12 @@ int16_t Temperature::getHeaterPower(const heater_ind_t heater_id) {
686 688
               , REPEAT2(4,_EFAN,4) 4
687 689
               #if HOTENDS > 5
688 690
                 , REPEAT2(5,_EFAN,5) 5
691
+                #if HOTENDS > 6
692
+                  , REPEAT2(6,_EFAN,6) 6
693
+                  #if HOTENDS > 7
694
+                    , REPEAT2(7,_EFAN,7) 7
695
+                  #endif
696
+                #endif
689 697
               #endif
690 698
             #endif
691 699
           #endif
@@ -751,6 +759,12 @@ int16_t Temperature::getHeaterPower(const heater_ind_t heater_id) {
751 759
         #if HAS_AUTO_FAN_5
752 760
           case 5: _UPDATE_AUTO_FAN(E5, fan_on, EXTRUDER_AUTO_FAN_SPEED); break;
753 761
         #endif
762
+        #if HAS_AUTO_FAN_6
763
+          case 6: _UPDATE_AUTO_FAN(E6, fan_on, EXTRUDER_AUTO_FAN_SPEED); break;
764
+        #endif
765
+        #if HAS_AUTO_FAN_7
766
+          case 7: _UPDATE_AUTO_FAN(E7, fan_on, EXTRUDER_AUTO_FAN_SPEED); break;
767
+        #endif
754 768
         #if HAS_AUTO_CHAMBER_FAN && !AUTO_CHAMBER_IS_E
755 769
           case CHAMBER_FAN_INDEX: _UPDATE_AUTO_FAN(CHAMBER, fan_on, CHAMBER_AUTO_FAN_SPEED); break;
756 770
         #endif
@@ -893,7 +907,6 @@ void Temperature::min_temp_error(const heater_ind_t heater) {
893 907
               pid_output += work_pid[ee].Kc;
894 908
             }
895 909
           #endif // PID_EXTRUSION_SCALING
896
-
897 910
           #if ENABLED(PID_FAN_SCALING)
898 911
             if (thermalManager.fan_speed[active_extruder] > PID_FAN_SCALING_MIN_SPEED) {
899 912
               work_pid[ee].Kf = PID_PARAM(Kf, ee) + (PID_FAN_SCALING_LIN_FACTOR) * thermalManager.fan_speed[active_extruder];
@@ -902,7 +915,6 @@ void Temperature::min_temp_error(const heater_ind_t heater) {
902 915
             //pid_output -= work_pid[ee].Ki;
903 916
             //pid_output += work_pid[ee].Ki * work_pid[ee].Kf
904 917
           #endif // PID_FAN_SCALING
905
-
906 918
           LIMIT(pid_output, 0, PID_MAX);
907 919
         }
908 920
         temp_dState[ee] = temp_hotend[ee].celsius;
@@ -1286,6 +1298,12 @@ void Temperature::manage_heater() {
1286 1298
       #if ENABLED(HEATER_5_USER_THERMISTOR)
1287 1299
         { true, 0, 0, HOTEND5_PULLUP_RESISTOR_OHMS, HOTEND5_RESISTANCE_25C_OHMS, 0, 0, HOTEND5_BETA, 0 },
1288 1300
       #endif
1301
+      #if ENABLED(HEATER_6_USER_THERMISTOR)
1302
+        { true, 0, 0, HOTEND6_PULLUP_RESISTOR_OHMS, HOTEND6_RESISTANCE_25C_OHMS, 0, 0, HOTEND6_BETA, 0 },
1303
+      #endif
1304
+      #if ENABLED(HEATER_7_USER_THERMISTOR)
1305
+        { true, 0, 0, HOTEND7_PULLUP_RESISTOR_OHMS, HOTEND7_RESISTANCE_25C_OHMS, 0, 0, HOTEND7_BETA, 0 },
1306
+      #endif
1289 1307
       #if ENABLED(HEATER_BED_USER_THERMISTOR)
1290 1308
         { true, 0, 0, BED_PULLUP_RESISTOR_OHMS, BED_RESISTANCE_25C_OHMS, 0, 0, BED_BETA, 0 },
1291 1309
       #endif
@@ -1331,6 +1349,12 @@ void Temperature::manage_heater() {
1331 1349
       #if ENABLED(HEATER_5_USER_THERMISTOR)
1332 1350
         t_index == CTI_HOTEND_5 ? PSTR("HOTEND 5") :
1333 1351
       #endif
1352
+      #if ENABLED(HEATER_6_USER_THERMISTOR)
1353
+        t_index == CTI_HOTEND_6 ? PSTR("HOTEND 6") :
1354
+      #endif
1355
+      #if ENABLED(HEATER_7_USER_THERMISTOR)
1356
+        t_index == CTI_HOTEND_7 ? PSTR("HOTEND 7") :
1357
+      #endif
1334 1358
       #if ENABLED(HEATER_BED_USER_THERMISTOR)
1335 1359
         t_index == CTI_BED ? PSTR("BED") :
1336 1360
       #endif
@@ -1476,6 +1500,26 @@ void Temperature::manage_heater() {
1476 1500
         #else
1477 1501
           break;
1478 1502
         #endif
1503
+      case 6:
1504
+        #if ENABLED(HEATER_6_USER_THERMISTOR)
1505
+          return user_thermistor_to_deg_c(CTI_HOTEND_6, raw);
1506
+        #elif ENABLED(HEATER_6_USES_AD595)
1507
+          return TEMP_AD595(raw);
1508
+        #elif ENABLED(HEATER_6_USES_AD8495)
1509
+          return TEMP_AD8495(raw);
1510
+        #else
1511
+          break;
1512
+        #endif
1513
+      case 7:
1514
+        #if ENABLED(HEATER_7_USER_THERMISTOR)
1515
+          return user_thermistor_to_deg_c(CTI_HOTEND_7, raw);
1516
+        #elif ENABLED(HEATER_7_USES_AD595)
1517
+          return TEMP_AD595(raw);
1518
+        #elif ENABLED(HEATER_7_USES_AD8495)
1519
+          return TEMP_AD8495(raw);
1520
+        #else
1521
+          break;
1522
+        #endif
1479 1523
       default: break;
1480 1524
     }
1481 1525
 
@@ -1633,8 +1677,9 @@ void Temperature::init() {
1633 1677
   #endif
1634 1678
 
1635 1679
   #if MB(RUMBA)
1636
-    #define _AD(N) (ANY(HEATER_##N##_USES_AD595, HEATER_##N##_USES_AD8495))
1637
-    #if _AD(0) || _AD(1) || _AD(2) || _AD(3) || _AD(4) || _AD(5) || _AD(BED) || _AD(CHAMBER)
1680
+    #define _AD(N) ANY(HEATER_##N##_USES_AD595, HEATER_##N##_USES_AD8495)
1681
+    #if  _AD(0) || _AD(1) || _AD(2) /* RUMBA has 3 E plugs // || _AD(3) || _AD(4) || _AD(5) || _AD(6) || _AD(7) */ \
1682
+      || _AD(BED) || _AD(CHAMBER)
1638 1683
       // Disable RUMBA JTAG in case the thermocouple extension is plugged on top of JTAG connector
1639 1684
       MCUCR = _BV(JTD);
1640 1685
       MCUCR = _BV(JTD);
@@ -1668,6 +1713,12 @@ void Temperature::init() {
1668 1713
   #if HAS_HEATER_5
1669 1714
     OUT_WRITE(HEATER_5_PIN, HEATER_5_INVERTING);
1670 1715
   #endif
1716
+  #if HAS_HEATER_6
1717
+    OUT_WRITE(HEATER_6_PIN, HEATER_6_INVERTING);
1718
+  #endif
1719
+  #if HAS_HEATER_7
1720
+    OUT_WRITE(HEATER_7_PIN, HEATER_7_INVERTING);
1721
+  #endif
1671 1722
 
1672 1723
   #if HAS_HEATED_BED
1673 1724
     #ifdef ALFAWISE_UX0
@@ -1690,6 +1741,21 @@ void Temperature::init() {
1690 1741
   #if HAS_FAN2
1691 1742
     INIT_FAN_PIN(FAN2_PIN);
1692 1743
   #endif
1744
+  #if HAS_FAN3
1745
+    INIT_FAN_PIN(FAN3_PIN);
1746
+  #endif
1747
+  #if HAS_FAN4
1748
+    INIT_FAN_PIN(FAN4_PIN);
1749
+  #endif
1750
+  #if HAS_FAN5
1751
+    INIT_FAN_PIN(FAN5_PIN);
1752
+  #endif
1753
+  #if HAS_FAN6
1754
+    INIT_FAN_PIN(FAN6_PIN);
1755
+  #endif
1756
+  #if HAS_FAN7
1757
+    INIT_FAN_PIN(FAN7_PIN);
1758
+  #endif
1693 1759
   #if ENABLED(USE_CONTROLLER_FAN)
1694 1760
     INIT_FAN_PIN(CONTROLLER_FAN_PIN);
1695 1761
   #endif
@@ -1731,6 +1797,12 @@ void Temperature::init() {
1731 1797
   #if HAS_TEMP_ADC_5
1732 1798
     HAL_ANALOG_SELECT(TEMP_5_PIN);
1733 1799
   #endif
1800
+  #if HAS_TEMP_ADC_6
1801
+    HAL_ANALOG_SELECT(TEMP_6_PIN);
1802
+  #endif
1803
+  #if HAS_TEMP_ADC_7
1804
+    HAL_ANALOG_SELECT(TEMP_7_PIN);
1805
+  #endif
1734 1806
   #if HAS_JOY_ADC_X
1735 1807
     HAL_ANALOG_SELECT(JOY_X_PIN);
1736 1808
   #endif
@@ -1780,6 +1852,12 @@ void Temperature::init() {
1780 1852
   #if HAS_AUTO_FAN_5 && !(_EFANOVERLAP(5,0) || _EFANOVERLAP(5,1) || _EFANOVERLAP(5,2) || _EFANOVERLAP(5,3) || _EFANOVERLAP(5,4))
1781 1853
     INIT_E_AUTO_FAN_PIN(E5_AUTO_FAN_PIN);
1782 1854
   #endif
1855
+  #if HAS_AUTO_FAN_6 && !(_EFANOVERLAP(6,0) || _EFANOVERLAP(6,1) || _EFANOVERLAP(6,2) || _EFANOVERLAP(6,3) || _EFANOVERLAP(6,4) || _EFANOVERLAP(6,5))
1856
+    INIT_E_AUTO_FAN_PIN(E6_AUTO_FAN_PIN);
1857
+  #endif
1858
+  #if HAS_AUTO_FAN_7 && !(_EFANOVERLAP(7,0) || _EFANOVERLAP(7,1) || _EFANOVERLAP(7,2) || _EFANOVERLAP(7,3) || _EFANOVERLAP(7,4) || _EFANOVERLAP(7,5) || _EFANOVERLAP(7,6))
1859
+    INIT_E_AUTO_FAN_PIN(E7_AUTO_FAN_PIN);
1860
+  #endif
1783 1861
   #if HAS_AUTO_CHAMBER_FAN && !AUTO_CHAMBER_IS_E
1784 1862
     INIT_CHAMBER_AUTO_FAN_PIN(CHAMBER_AUTO_FAN_PIN);
1785 1863
   #endif
@@ -1841,6 +1919,22 @@ void Temperature::init() {
1841 1919
               #ifdef HEATER_5_MAXTEMP
1842 1920
                 _TEMP_MAX_E(5);
1843 1921
               #endif
1922
+              #if HOTENDS > 6
1923
+                #ifdef HEATER_6_MINTEMP
1924
+                  _TEMP_MIN_E(6);
1925
+                #endif
1926
+                #ifdef HEATER_6_MAXTEMP
1927
+                  _TEMP_MAX_E(6);
1928
+                #endif
1929
+                #if HOTENDS > 7
1930
+                  #ifdef HEATER_7_MINTEMP
1931
+                    _TEMP_MIN_E(7);
1932
+                  #endif
1933
+                  #ifdef HEATER_7_MAXTEMP
1934
+                    _TEMP_MAX_E(7);
1935
+                  #endif
1936
+                #endif // HOTENDS > 7
1937
+              #endif // HOTENDS > 6
1844 1938
             #endif // HOTENDS > 5
1845 1939
           #endif // HOTENDS > 4
1846 1940
         #endif // HOTENDS > 3
@@ -2232,6 +2326,12 @@ void Temperature::set_current_temp_raw() {
2232 2326
           temp_hotend[4].update();
2233 2327
           #if HAS_TEMP_ADC_5
2234 2328
             temp_hotend[5].update();
2329
+            #if HAS_TEMP_ADC_6
2330
+              temp_hotend[6].update();
2331
+              #if HAS_TEMP_ADC_7
2332
+                temp_hotend[7].update();
2333
+              #endif // HAS_TEMP_ADC_7
2334
+            #endif // HAS_TEMP_ADC_6
2235 2335
           #endif // HAS_TEMP_ADC_5
2236 2336
         #endif // HAS_TEMP_ADC_4
2237 2337
       #endif // HAS_TEMP_ADC_3
@@ -2508,6 +2608,21 @@ void Temperature::tick() {
2508 2608
         #if HAS_FAN2
2509 2609
           _FAN_PWM(2);
2510 2610
         #endif
2611
+        #if HAS_FAN3
2612
+          _FAN_PWM(3);
2613
+        #endif
2614
+        #if HAS_FAN4
2615
+          _FAN_PWM(4);
2616
+        #endif
2617
+        #if HAS_FAN5
2618
+          _FAN_PWM(5);
2619
+        #endif
2620
+        #if HAS_FAN6
2621
+          _FAN_PWM(6);
2622
+        #endif
2623
+        #if HAS_FAN7
2624
+          _FAN_PWM(7);
2625
+        #endif
2511 2626
       #endif
2512 2627
     }
2513 2628
     else {
@@ -2535,6 +2650,21 @@ void Temperature::tick() {
2535 2650
         #if HAS_FAN2
2536 2651
           if (soft_pwm_count_fan[2] <= pwm_count_tmp) WRITE_FAN(2, LOW);
2537 2652
         #endif
2653
+        #if HAS_FAN3
2654
+          if (soft_pwm_count_fan[3] <= pwm_count_tmp) WRITE_FAN(3, LOW);
2655
+        #endif
2656
+        #if HAS_FAN4
2657
+          if (soft_pwm_count_fan[4] <= pwm_count_tmp) WRITE_FAN(4, LOW);
2658
+        #endif
2659
+        #if HAS_FAN5
2660
+          if (soft_pwm_count_fan[5] <= pwm_count_tmp) WRITE_FAN(5, LOW);
2661
+        #endif
2662
+        #if HAS_FAN6
2663
+          if (soft_pwm_count_fan[6] <= pwm_count_tmp) WRITE_FAN(6, LOW);
2664
+        #endif
2665
+        #if HAS_FAN7
2666
+          if (soft_pwm_count_fan[7] <= pwm_count_tmp) WRITE_FAN(7, LOW);
2667
+        #endif
2538 2668
       #endif
2539 2669
     }
2540 2670
 
@@ -2599,6 +2729,21 @@ void Temperature::tick() {
2599 2729
         #if HAS_FAN2
2600 2730
           _PWM_FAN(2);
2601 2731
         #endif
2732
+        #if HAS_FAN3
2733
+          _FAN_PWM(3);
2734
+        #endif
2735
+        #if HAS_FAN4
2736
+          _FAN_PWM(4);
2737
+        #endif
2738
+        #if HAS_FAN5
2739
+          _FAN_PWM(5);
2740
+        #endif
2741
+        #if HAS_FAN6
2742
+          _FAN_PWM(6);
2743
+        #endif
2744
+        #if HAS_FAN7
2745
+          _FAN_PWM(7);
2746
+        #endif
2602 2747
       }
2603 2748
       #if HAS_FAN0
2604 2749
         if (soft_pwm_count_fan[0] <= pwm_count_tmp) WRITE_FAN(0, LOW);
@@ -2609,6 +2754,21 @@ void Temperature::tick() {
2609 2754
       #if HAS_FAN2
2610 2755
         if (soft_pwm_count_fan[2] <= pwm_count_tmp) WRITE_FAN(2, LOW);
2611 2756
       #endif
2757
+      #if HAS_FAN3
2758
+        if (soft_pwm_count_fan[3] <= pwm_count_tmp) WRITE_FAN(3, LOW);
2759
+      #endif
2760
+      #if HAS_FAN4
2761
+        if (soft_pwm_count_fan[4] <= pwm_count_tmp) WRITE_FAN(4, LOW);
2762
+      #endif
2763
+      #if HAS_FAN5
2764
+        if (soft_pwm_count_fan[5] <= pwm_count_tmp) WRITE_FAN(5, LOW);
2765
+      #endif
2766
+      #if HAS_FAN6
2767
+        if (soft_pwm_count_fan[6] <= pwm_count_tmp) WRITE_FAN(6, LOW);
2768
+      #endif
2769
+      #if HAS_FAN7
2770
+        if (soft_pwm_count_fan[7] <= pwm_count_tmp) WRITE_FAN(7, LOW);
2771
+      #endif
2612 2772
     #endif // FAN_SOFT_PWM
2613 2773
 
2614 2774
     // SOFT_PWM_SCALE to frequency:
@@ -2730,6 +2890,16 @@ void Temperature::tick() {
2730 2890
       case MeasureTemp_5: ACCUMULATE_ADC(temp_hotend[5]); break;
2731 2891
     #endif
2732 2892
 
2893
+    #if HAS_TEMP_ADC_6
2894
+      case PrepareTemp_6: HAL_START_ADC(TEMP_6_PIN); break;
2895
+      case MeasureTemp_6: ACCUMULATE_ADC(temp_hotend[6]); break;
2896
+    #endif
2897
+
2898
+    #if HAS_TEMP_ADC_7
2899
+      case PrepareTemp_7: HAL_START_ADC(TEMP_7_PIN); break;
2900
+      case MeasureTemp_7: ACCUMULATE_ADC(temp_hotend[7]); break;
2901
+    #endif
2902
+
2733 2903
     #if ENABLED(FILAMENT_WIDTH_SENSOR)
2734 2904
       case Prepare_FILWIDTH: HAL_START_ADC(FILWIDTH_PIN); break;
2735 2905
       case Measure_FILWIDTH:

+ 6
- 0
Marlin/src/module/temperature.h View File

@@ -132,6 +132,12 @@ enum ADCSensorState : char {
132 132
   #if HAS_TEMP_ADC_5
133 133
     PrepareTemp_5, MeasureTemp_5,
134 134
   #endif
135
+  #if HAS_TEMP_ADC_6
136
+    PrepareTemp_6, MeasureTemp_6,
137
+  #endif
138
+  #if HAS_TEMP_ADC_7
139
+    PrepareTemp_7, MeasureTemp_7,
140
+  #endif
135 141
   #if HAS_JOY_ADC_X
136 142
     PrepareJoy_X, MeasureJoy_X,
137 143
   #endif

+ 40
- 1
Marlin/src/module/thermistor/thermistors.h View File

@@ -39,7 +39,7 @@
39 39
 
40 40
 #define OV(N) int16_t((N) * (OVERSAMPLENR) * (THERMISTOR_TABLE_SCALE))
41 41
 
42
-#define ANY_THERMISTOR_IS(n) (THERMISTOR_HEATER_0 == n || THERMISTOR_HEATER_1 == n || THERMISTOR_HEATER_2 == n || THERMISTOR_HEATER_3 == n || THERMISTOR_HEATER_4 == n || THERMISTOR_HEATER_5 == n || THERMISTORBED == n || THERMISTORCHAMBER == n || THERMISTORPROBE == n)
42
+#define ANY_THERMISTOR_IS(n) (THERMISTOR_HEATER_0 == n || THERMISTOR_HEATER_1 == n || THERMISTOR_HEATER_2 == n || THERMISTOR_HEATER_3 == n || THERMISTOR_HEATER_4 == n || THERMISTOR_HEATER_5 == n || THERMISTOR_HEATER_6 == n || THERMISTOR_HEATER_7 == n || THERMISTORBED == n || THERMISTORCHAMBER == n || THERMISTORPROBE == n)
43 43
 
44 44
 // Pt1000 and Pt100 handling
45 45
 //
@@ -235,6 +235,26 @@
235 235
   #define HEATER_5_TEMPTABLE_LEN 0
236 236
 #endif
237 237
 
238
+#if THERMISTOR_HEATER_6
239
+  #define HEATER_6_TEMPTABLE TT_NAME(THERMISTOR_HEATER_6)
240
+  #define HEATER_6_TEMPTABLE_LEN COUNT(HEATER_6_TEMPTABLE)
241
+#elif defined(HEATER_6_USES_THERMISTOR)
242
+  #error "No heater 6 thermistor table specified"
243
+#else
244
+  #define HEATER_6_TEMPTABLE nullptr
245
+  #define HEATER_6_TEMPTABLE_LEN 0
246
+#endif
247
+
248
+#if THERMISTOR_HEATER_7
249
+  #define HEATER_7_TEMPTABLE TT_NAME(THERMISTOR_HEATER_7)
250
+  #define HEATER_7_TEMPTABLE_LEN COUNT(HEATER_7_TEMPTABLE)
251
+#elif defined(HEATER_7_USES_THERMISTOR)
252
+  #error "No heater 7 thermistor table specified"
253
+#else
254
+  #define HEATER_7_TEMPTABLE nullptr
255
+  #define HEATER_7_TEMPTABLE_LEN 0
256
+#endif
257
+
238 258
 #ifdef THERMISTORBED
239 259
   #define BED_TEMPTABLE TT_NAME(THERMISTORBED)
240 260
   #define BED_TEMPTABLE_LEN COUNT(BED_TEMPTABLE)
@@ -264,6 +284,7 @@ static_assert(
264 284
      HEATER_0_TEMPTABLE_LEN < 256 && HEATER_1_TEMPTABLE_LEN < 256
265 285
   && HEATER_2_TEMPTABLE_LEN < 256 && HEATER_3_TEMPTABLE_LEN < 256
266 286
   && HEATER_4_TEMPTABLE_LEN < 256 && HEATER_5_TEMPTABLE_LEN < 256
287
+  && HEATER_6_TEMPTABLE_LEN < 258 && HEATER_7_TEMPTABLE_LEN < 258
267 288
   &&      BED_TEMPTABLE_LEN < 256 &&  CHAMBER_TEMPTABLE_LEN < 256
268 289
   &&    PROBE_TEMPTABLE_LEN < 256,
269 290
   "Temperature conversion tables over 255 entries need special consideration."
@@ -326,6 +347,24 @@ static_assert(
326 347
     #define HEATER_5_RAW_LO_TEMP MAX_RAW_THERMISTOR_VALUE
327 348
   #endif
328 349
 #endif
350
+#ifndef HEATER_6_RAW_HI_TEMP
351
+  #if defined(REVERSE_TEMP_SENSOR_RANGE) || !defined(HEATER_6_USES_THERMISTOR)
352
+    #define HEATER_6_RAW_HI_TEMP MAX_RAW_THERMISTOR_VALUE
353
+    #define HEATER_6_RAW_LO_TEMP 0
354
+  #else
355
+    #define HEATER_6_RAW_HI_TEMP 0
356
+    #define HEATER_6_RAW_LO_TEMP MAX_RAW_THERMISTOR_VALUE
357
+  #endif
358
+#endif
359
+#ifndef HEATER_7_RAW_HI_TEMP
360
+  #if defined(REVERSE_TEMP_SENSOR_RANGE) || !defined(HEATER_7_USES_THERMISTOR)
361
+    #define HEATER_7_RAW_HI_TEMP MAX_RAW_THERMISTOR_VALUE
362
+    #define HEATER_7_RAW_LO_TEMP 0
363
+  #else
364
+    #define HEATER_7_RAW_HI_TEMP 0
365
+    #define HEATER_7_RAW_LO_TEMP MAX_RAW_THERMISTOR_VALUE
366
+  #endif
367
+#endif
329 368
 #ifndef HEATER_BED_RAW_HI_TEMP
330 369
   #if defined(REVERSE_TEMP_SENSOR_RANGE) || !defined(HEATER_BED_USES_THERMISTOR)
331 370
     #define HEATER_BED_RAW_HI_TEMP MAX_RAW_THERMISTOR_VALUE

+ 70
- 0
Marlin/src/pins/pins.h View File

@@ -534,6 +534,8 @@
534 534
   #include "stm32/pins_STEVAL_3DP001V1.h"       // STM32F4                                env:STM32F401VE_STEVAL
535 535
 #elif MB(BIGTREE_SKR_PRO_V1_1)
536 536
   #include "stm32/pins_BTT_SKR_PRO_V1_1.h"      // STM32F4                                env:BIGTREE_SKR_PRO
537
+#elif MB(BIGTREE_GTR_V1_0)
538
+  #include "stm32/pins_BTT_GTR_V1_0.h"          // STM32F4                                env:BIGTREE_GTR
537 539
 #elif MB(BIGTREE_BTT002_V1_0)
538 540
   #include "stm32/pins_BTT_BTT002_V1_0.h"       // STM32F4                                env:BIGTREE_BTT002
539 541
 #elif MB(LERDGE_K)
@@ -713,6 +715,24 @@
713 715
 #ifndef E5_MS3_PIN
714 716
   #define E5_MS3_PIN -1
715 717
 #endif
718
+#ifndef E6_MS1_PIN
719
+  #define E6_MS1_PIN -1
720
+#endif
721
+#ifndef E6_MS2_PIN
722
+  #define E6_MS2_PIN -1
723
+#endif
724
+#ifndef E6_MS3_PIN
725
+  #define E6_MS3_PIN -1
726
+#endif
727
+#ifndef E7_MS1_PIN
728
+  #define E7_MS1_PIN -1
729
+#endif
730
+#ifndef E7_MS2_PIN
731
+  #define E7_MS2_PIN -1
732
+#endif
733
+#ifndef E7_MS3_PIN
734
+  #define E7_MS3_PIN -1
735
+#endif
716 736
 
717 737
 #ifndef E0_STEP_PIN
718 738
   #define E0_STEP_PIN -1
@@ -768,6 +788,24 @@
768 788
 #ifndef E5_ENABLE_PIN
769 789
   #define E5_ENABLE_PIN -1
770 790
 #endif
791
+#ifndef E6_STEP_PIN
792
+  #define E6_STEP_PIN -1
793
+#endif
794
+#ifndef E6_DIR_PIN
795
+  #define E6_DIR_PIN -1
796
+#endif
797
+#ifndef E6_ENABLE_PIN
798
+  #define E6_ENABLE_PIN -1
799
+#endif
800
+#ifndef E7_STEP_PIN
801
+  #define E7_STEP_PIN -1
802
+#endif
803
+#ifndef E7_DIR_PIN
804
+  #define E7_DIR_PIN -1
805
+#endif
806
+#ifndef E7_ENABLE_PIN
807
+  #define E7_ENABLE_PIN -1
808
+#endif
771 809
 
772 810
 #ifndef X_CS_PIN
773 811
   #define X_CS_PIN -1
@@ -796,6 +834,12 @@
796 834
 #ifndef E5_CS_PIN
797 835
   #define E5_CS_PIN -1
798 836
 #endif
837
+#ifndef E6_CS_PIN
838
+  #define E6_CS_PIN -1
839
+#endif
840
+#ifndef E7_CS_PIN
841
+  #define E7_CS_PIN -1
842
+#endif
799 843
 
800 844
 #ifndef FAN_PIN
801 845
   #define FAN_PIN -1
@@ -839,6 +883,12 @@
839 883
 #ifndef HEATER_5_PIN
840 884
   #define HEATER_5_PIN -1
841 885
 #endif
886
+#ifndef HEATER_6_PIN
887
+  #define HEATER_6_PIN -1
888
+#endif
889
+#ifndef HEATER_7_PIN
890
+  #define HEATER_7_PIN -1
891
+#endif
842 892
 #ifndef HEATER_BED_PIN
843 893
   #define HEATER_BED_PIN -1
844 894
 #endif
@@ -861,6 +911,12 @@
861 911
 #ifndef TEMP_5_PIN
862 912
   #define TEMP_5_PIN -1
863 913
 #endif
914
+#ifndef TEMP_6_PIN
915
+  #define TEMP_6_PIN -1
916
+#endif
917
+#ifndef TEMP_7_PIN
918
+  #define TEMP_7_PIN -1
919
+#endif
864 920
 #ifndef TEMP_BED_PIN
865 921
   #define TEMP_BED_PIN -1
866 922
 #endif
@@ -940,6 +996,20 @@
940 996
     #define E5_AUTO_FAN_PIN -1
941 997
   #endif
942 998
 #endif
999
+#ifndef E6_AUTO_FAN_PIN
1000
+  #ifdef ORIG_E6_AUTO_FAN_PIN
1001
+    #define E6_AUTO_FAN_PIN ORIG_E6_AUTO_FAN_PIN
1002
+  #else
1003
+    #define E6_AUTO_FAN_PIN -1
1004
+  #endif
1005
+#endif
1006
+#ifndef E7_AUTO_FAN_PIN
1007
+  #ifdef ORIG_E7_AUTO_FAN_PIN
1008
+    #define E7_AUTO_FAN_PIN ORIG_E7_AUTO_FAN_PIN
1009
+  #else
1010
+    #define E7_AUTO_FAN_PIN -1
1011
+  #endif
1012
+#endif
943 1013
 #ifndef CHAMBER_AUTO_FAN_PIN
944 1014
   #ifdef ORIG_CHAMBER_AUTO_FAN_PIN
945 1015
     #define CHAMBER_AUTO_FAN_PIN ORIG_CHAMBER_AUTO_FAN_PIN

+ 153
- 0
Marlin/src/pins/pinsDebug_list.h View File

@@ -153,6 +153,24 @@
153 153
 #if !PIN_EXISTS(E5_MS3)
154 154
   #undef E5_MS3_PIN
155 155
 #endif
156
+#if !PIN_EXISTS(E6_MS1)
157
+  #undef E6_MS1_PIN
158
+#endif
159
+#if !PIN_EXISTS(E6_MS2)
160
+  #undef E6_MS2_PIN
161
+#endif
162
+#if !PIN_EXISTS(E6_MS3)
163
+  #undef E6_MS3_PIN
164
+#endif
165
+#if !PIN_EXISTS(E7_MS1)
166
+  #undef E7_MS1_PIN
167
+#endif
168
+#if !PIN_EXISTS(E7_MS2)
169
+  #undef E7_MS2_PIN
170
+#endif
171
+#if !PIN_EXISTS(E7_MS3)
172
+  #undef E7_MS3_PIN
173
+#endif
156 174
 
157 175
 #if !PIN_EXISTS(E0_STEP)
158 176
   #undef E0_STEP_PIN
@@ -208,6 +226,24 @@
208 226
 #if !PIN_EXISTS(E5_ENABLE)
209 227
   #undef E5_ENABLE_PIN
210 228
 #endif
229
+#if !PIN_EXISTS(E6_STEP)
230
+  #undef E6_STEP_PIN
231
+#endif
232
+#if !PIN_EXISTS(E6_DIR)
233
+  #undef E6_DIR_PIN
234
+#endif
235
+#if !PIN_EXISTS(E6_ENABLE)
236
+  #undef E6_ENABLE_PIN
237
+#endif
238
+#if !PIN_EXISTS(E7_STEP)
239
+  #undef E7_STEP_PIN
240
+#endif
241
+#if !PIN_EXISTS(E7_DIR)
242
+  #undef E7_DIR_PIN
243
+#endif
244
+#if !PIN_EXISTS(E7_ENABLE)
245
+  #undef E7_ENABLE_PIN
246
+#endif
211 247
 
212 248
 #if !PIN_EXISTS(X_CS)
213 249
   #undef X_CS_PIN
@@ -236,6 +272,12 @@
236 272
 #if !PIN_EXISTS(E5_CS)
237 273
   #undef E5_CS_PIN
238 274
 #endif
275
+#if !PIN_EXISTS(E6_CS)
276
+  #undef E6_CS_PIN
277
+#endif
278
+#if !PIN_EXISTS(E7_CS)
279
+  #undef E7_CS_PIN
280
+#endif
239 281
 
240 282
 #if !PIN_EXISTS(FAN)
241 283
   #undef FAN_PIN
@@ -247,6 +289,21 @@
247 289
 #if !PIN_EXISTS(FAN2)
248 290
   #undef FAN2_PIN
249 291
 #endif
292
+#if !PIN_EXISTS(FAN3)
293
+  #undef FAN3_PIN
294
+#endif
295
+#if !PIN_EXISTS(FAN4)
296
+  #undef FAN4_PIN
297
+#endif
298
+#if !PIN_EXISTS(FAN5)
299
+  #undef FAN5_PIN
300
+#endif
301
+#if !PIN_EXISTS(FAN6)
302
+  #undef FAN6_PIN
303
+#endif
304
+#if !PIN_EXISTS(FAN7)
305
+  #undef FAN7_PIN
306
+#endif
250 307
 #if !PIN_EXISTS(CONTROLLER_FAN)
251 308
   #undef CONTROLLER_FAN_PIN
252 309
 #endif
@@ -279,6 +336,12 @@
279 336
 #if !PIN_EXISTS(HEATER_5)
280 337
   #undef HEATER_5_PIN
281 338
 #endif
339
+#if !PIN_EXISTS(HEATER_6)
340
+  #undef HEATER_6_PIN
341
+#endif
342
+#if !PIN_EXISTS(HEATER_7)
343
+  #undef HEATER_7_PIN
344
+#endif
282 345
 #if !PIN_EXISTS(HEATER_BED)
283 346
   #undef HEATER_BED_PIN
284 347
 #endif
@@ -301,6 +364,12 @@
301 364
 #if !PIN_EXISTS(TEMP_5)
302 365
   #undef TEMP_5_PIN
303 366
 #endif
367
+#if !PIN_EXISTS(TEMP_6)
368
+  #undef TEMP_6_PIN
369
+#endif
370
+#if !PIN_EXISTS(TEMP_7)
371
+  #undef TEMP_7_PIN
372
+#endif
304 373
 #if !PIN_EXISTS(TEMP_BED)
305 374
   #undef TEMP_BED_PIN
306 375
 #endif
@@ -363,6 +432,12 @@
363 432
 #if PIN_EXISTS(TEMP_5) && TEMP_5_PIN < NUM_ANALOG_INPUTS
364 433
   REPORT_NAME_ANALOG(__LINE__, TEMP_5_PIN)
365 434
 #endif
435
+#if PIN_EXISTS(TEMP_6) && TEMP_6_PIN < NUM_ANALOG_INPUTS
436
+  REPORT_NAME_ANALOG(__LINE__, TEMP_6_PIN)
437
+#endif
438
+#if PIN_EXISTS(TEMP_7) && TEMP_7_PIN < NUM_ANALOG_INPUTS
439
+  REPORT_NAME_ANALOG(__LINE__, TEMP_7_PIN)
440
+#endif
366 441
 #if PIN_EXISTS(TEMP_BED) && TEMP_BED_PIN < NUM_ANALOG_INPUTS
367 442
   REPORT_NAME_ANALOG(__LINE__, TEMP_BED_PIN)
368 443
 #endif
@@ -686,6 +761,54 @@
686 761
 #if PIN_EXISTS(E5_STEP)
687 762
   REPORT_NAME_DIGITAL(__LINE__, E5_STEP_PIN)
688 763
 #endif
764
+#if PIN_EXISTS(E6_AUTO_FAN)
765
+  REPORT_NAME_DIGITAL(__LINE__, E6_AUTO_FAN_PIN)
766
+#endif
767
+#if PIN_EXISTS(E6_CS)
768
+  REPORT_NAME_DIGITAL(__LINE__, E6_CS_PIN)
769
+#endif
770
+#if PIN_EXISTS(E6_DIR)
771
+  REPORT_NAME_DIGITAL(__LINE__, E6_DIR_PIN)
772
+#endif
773
+#if PIN_EXISTS(E6_ENABLE)
774
+  REPORT_NAME_DIGITAL(__LINE__, E6_ENABLE_PIN)
775
+#endif
776
+#if PIN_EXISTS(E6_MS1)
777
+  REPORT_NAME_DIGITAL(__LINE__, E6_MS1_PIN)
778
+#endif
779
+#if PIN_EXISTS(E6_MS2)
780
+  REPORT_NAME_DIGITAL(__LINE__, E6_MS2_PIN)
781
+#endif
782
+#if PIN_EXISTS(E6_MS3)
783
+  REPORT_NAME_DIGITAL(__LINE__, E6_MS3_PIN)
784
+#endif
785
+#if PIN_EXISTS(E6_STEP)
786
+  REPORT_NAME_DIGITAL(__LINE__, E6_STEP_PIN)
787
+#endif
788
+#if PIN_EXISTS(E7_AUTO_FAN)
789
+  REPORT_NAME_DIGITAL(__LINE__, E7_AUTO_FAN_PIN)
790
+#endif
791
+#if PIN_EXISTS(E7_CS)
792
+  REPORT_NAME_DIGITAL(__LINE__, E7_CS_PIN)
793
+#endif
794
+#if PIN_EXISTS(E7_DIR)
795
+  REPORT_NAME_DIGITAL(__LINE__, E7_DIR_PIN)
796
+#endif
797
+#if PIN_EXISTS(E7_ENABLE)
798
+  REPORT_NAME_DIGITAL(__LINE__, E7_ENABLE_PIN)
799
+#endif
800
+#if PIN_EXISTS(E7_MS1)
801
+  REPORT_NAME_DIGITAL(__LINE__, E7_MS1_PIN)
802
+#endif
803
+#if PIN_EXISTS(E7_MS2)
804
+  REPORT_NAME_DIGITAL(__LINE__, E7_MS2_PIN)
805
+#endif
806
+#if PIN_EXISTS(E7_MS3)
807
+  REPORT_NAME_DIGITAL(__LINE__, E7_MS3_PIN)
808
+#endif
809
+#if PIN_EXISTS(E7_STEP)
810
+  REPORT_NAME_DIGITAL(__LINE__, E7_STEP_PIN)
811
+#endif
689 812
 #if defined(ENET_CRS) && ENET_CRS >= 0
690 813
   REPORT_NAME_DIGITAL(__LINE__, ENET_CRS)
691 814
 #endif
@@ -765,6 +888,18 @@
765 888
 #if PIN_EXISTS(FAN3)
766 889
   REPORT_NAME_DIGITAL(__LINE__, FAN3_PIN)
767 890
 #endif
891
+#if PIN_EXISTS(FAN4)
892
+  REPORT_NAME_DIGITAL(__LINE__, FAN4_PIN)
893
+#endif
894
+#if PIN_EXISTS(FAN5)
895
+  REPORT_NAME_DIGITAL(__LINE__, FAN5_PIN)
896
+#endif
897
+#if PIN_EXISTS(FAN6)
898
+  REPORT_NAME_DIGITAL(__LINE__, FAN6_PIN)
899
+#endif
900
+#if PIN_EXISTS(FAN7)
901
+  REPORT_NAME_DIGITAL(__LINE__, FAN7_PIN)
902
+#endif
768 903
 #if PIN_EXISTS(FIL_RUNOUT)
769 904
   REPORT_NAME_DIGITAL(__LINE__, FIL_RUNOUT_PIN)
770 905
 #endif
@@ -936,6 +1071,12 @@
936 1071
 #if PIN_EXISTS(ORIG_E5_AUTO_FAN)
937 1072
   REPORT_NAME_DIGITAL(__LINE__, ORIG_E5_AUTO_FAN_PIN)
938 1073
 #endif
1074
+#if PIN_EXISTS(ORIG_E6_AUTO_FAN)
1075
+  REPORT_NAME_DIGITAL(__LINE__, ORIG_E6_AUTO_FAN_PIN)
1076
+#endif
1077
+#if PIN_EXISTS(ORIG_E7_AUTO_FAN)
1078
+  REPORT_NAME_DIGITAL(__LINE__, ORIG_E7_AUTO_FAN_PIN)
1079
+#endif
939 1080
 #if PIN_EXISTS(PHOTOGRAPH)
940 1081
   REPORT_NAME_DIGITAL(__LINE__, PHOTOGRAPH_PIN)
941 1082
 #endif
@@ -1455,6 +1596,18 @@
1455 1596
 #if PIN_EXISTS(E5_SERIAL_RX)
1456 1597
   REPORT_NAME_DIGITAL(__LINE__, E5_SERIAL_RX_PIN)
1457 1598
 #endif
1599
+#if PIN_EXISTS(E6_SERIAL_TX)
1600
+  REPORT_NAME_DIGITAL(__LINE__, E6_SERIAL_TX_PIN)
1601
+#endif
1602
+#if PIN_EXISTS(E6_SERIAL_RX)
1603
+  REPORT_NAME_DIGITAL(__LINE__, E6_SERIAL_RX_PIN)
1604
+#endif
1605
+#if PIN_EXISTS(E7_SERIAL_TX)
1606
+  REPORT_NAME_DIGITAL(__LINE__, E7_SERIAL_TX_PIN)
1607
+#endif
1608
+#if PIN_EXISTS(E7_SERIAL_RX)
1609
+  REPORT_NAME_DIGITAL(__LINE__, E7_SERIAL_RX_PIN)
1610
+#endif
1458 1611
 #if PIN_EXISTS(L6470_CHAIN_SCK)
1459 1612
   REPORT_NAME_DIGITAL(__LINE__, L6470_CHAIN_SCK_PIN)
1460 1613
 #endif

+ 100
- 4
Marlin/src/pins/sensitive_pins.h View File

@@ -277,6 +277,54 @@
277 277
   #endif
278 278
 #endif
279 279
 
280
+#define _E6_CS
281
+#define _E6_MS2
282
+#define _E6_MS3
283
+#define _E6_MS4
284
+
285
+#if E_NEEDED(6)
286
+  #if PIN_EXISTS(E6_CS) && AXIS_HAS_SPI(E6)
287
+    #undef _E6_CS
288
+    #define _E6_CS E6_CS_PIN,
289
+  #endif
290
+  #if PIN_EXISTS(E6_MS2)
291
+    #undef _E6_MS2
292
+    #define _E6_MS2 E6_MS2_PIN,
293
+  #endif
294
+  #if PIN_EXISTS(E6_MS3)
295
+    #undef _E6_MS3
296
+    #define _E6_MS3 E6_MS3_PIN,
297
+  #endif
298
+  #if PIN_EXISTS(E6_MS4)
299
+    #undef _E6_MS4
300
+    #define _E6_MS4 E6_MS4_PIN,
301
+  #endif
302
+#endif
303
+
304
+#define _E7_CS
305
+#define _E7_MS3
306
+#define _E7_MS4
307
+#define _E7_MS5
308
+
309
+#if E_NEEDED(7)
310
+  #if PIN_EXISTS(E7_CS) && AXIS_HAS_SPI(E7)
311
+    #undef _E7_CS
312
+    #define _E7_CS E7_CS_PIN,
313
+  #endif
314
+  #if PIN_EXISTS(E7_MS3)
315
+    #undef _E7_MS3
316
+    #define _E7_MS3 E7_MS3_PIN,
317
+  #endif
318
+  #if PIN_EXISTS(E7_MS4)
319
+    #undef _E7_MS4
320
+    #define _E7_MS4 E7_MS4_PIN,
321
+  #endif
322
+  #if PIN_EXISTS(E7_MS5)
323
+    #undef _E7_MS5
324
+    #define _E7_MS5 E7_MS5_PIN,
325
+  #endif
326
+#endif
327
+
280 328
 //
281 329
 // E Steppers
282 330
 //
@@ -287,6 +335,8 @@
287 335
 #define _E3_PINS
288 336
 #define _E4_PINS
289 337
 #define _E5_PINS
338
+#define _E6_PINS
339
+#define _E7_PINS
290 340
 
291 341
 #if EXTRUDERS
292 342
   #undef _E0_PINS
@@ -303,7 +353,9 @@
303 353
       #define _E2_PINS E2_STEP_PIN, E2_DIR_PIN, E2_ENABLE_PIN, _E2_CS _E2_MS1 _E2_MS2 _E2_MS3
304 354
     #endif
305 355
   #endif
356
+
306 357
 #elif EXTRUDERS > 1 || ENABLED(MIXING_EXTRUDER)
358
+
307 359
   #undef _E1_PINS
308 360
   #define _E1_PINS E1_STEP_PIN, E1_DIR_PIN, E1_ENABLE_PIN, _E1_CS _E1_MS1 _E1_MS2 _E1_MS3
309 361
   #if EXTRUDERS > 2 || (ENABLED(MIXING_EXTRUDER) && MIXING_STEPPERS > 2)
@@ -318,10 +370,19 @@
318 370
         #if EXTRUDERS > 5 || (ENABLED(MIXING_EXTRUDER) && MIXING_STEPPERS > 5)
319 371
           #undef _E5_PINS
320 372
           #define _E5_PINS E5_STEP_PIN, E5_DIR_PIN, E5_ENABLE_PIN, _E5_CS _E5_MS1 _E5_MS2 _E5_MS3
373
+          #if EXTRUDERS > 6 || (ENABLED(MIXING_EXTRUDER) && MIXING_STEPPERS > 6)
374
+            #undef _E6_PINS
375
+            #define _E6_PINS E6_STEP_PIN, E6_DIR_PIN, E6_ENABLE_PIN, _E6_CS _E6_MS1 _E6_MS2 _E6_MS3
376
+            #if EXTRUDERS > 7 || (ENABLED(MIXING_EXTRUDER) && MIXING_STEPPERS > 7)
377
+              #undef _E7_PINS
378
+              #define _E7_PINS E7_STEP_PIN, E7_DIR_PIN, E7_ENABLE_PIN, _E7_CS _E7_MS1 _E7_MS2 _E7_MS3
379
+            #endif // EXTRUDERS > 7 || MIXING_EXTRUDER > 7
380
+          #endif // EXTRUDERS > 6 || MIXING_EXTRUDER > 6
321 381
         #endif // EXTRUDERS > 5 || MIXING_EXTRUDER > 5
322 382
       #endif // EXTRUDERS > 4 || MIXING_EXTRUDER > 4
323 383
     #endif // EXTRUDERS > 3 || MIXING_EXTRUDER > 3
324 384
   #endif // EXTRUDERS > 2 || MIXING_EXTRUDER > 2
385
+
325 386
 #endif // EXTRUDERS > 1 || MIXING_EXTRUDER
326 387
 
327 388
 //
@@ -334,6 +395,8 @@
334 395
 #define _H3_PINS
335 396
 #define _H4_PINS
336 397
 #define _H5_PINS
398
+#define _H6_PINS
399
+#define _H7_PINS
337 400
 
338 401
 #if HOTENDS
339 402
   #undef _H0_PINS
@@ -353,6 +416,14 @@
353 416
           #if HOTENDS > 5
354 417
             #undef _H5_PINS
355 418
             #define _H5_PINS HEATER_5_PIN, E5_AUTO_FAN_PIN, analogInputToDigitalPin(TEMP_5_PIN),
419
+            #if HOTENDS > 6
420
+              #undef _H6_PINS
421
+              #define _H6_PINS HEATER_6_PIN, E6_AUTO_FAN_PIN, analogInputToDigitalPin(TEMP_6_PIN),
422
+              #if HOTENDS > 7
423
+                #undef _H7_PINS
424
+                #define _H7_PINS HEATER_7_PIN, E7_AUTO_FAN_PIN, analogInputToDigitalPin(TEMP_7_PIN),
425
+              #endif // HOTENDS > 7
426
+            #endif // HOTENDS > 6
356 427
           #endif // HOTENDS > 5
357 428
         #endif // HOTENDS > 4
358 429
       #endif // HOTENDS > 3
@@ -539,6 +610,31 @@
539 610
 #else
540 611
   #define _FAN2
541 612
 #endif
613
+#if PIN_EXISTS(FAN3)
614
+  #define _FAN3 FAN3_PIN,
615
+#else
616
+  #define _FAN3
617
+#endif
618
+#if PIN_EXISTS(FAN4)
619
+  #define _FAN4 FAN4_PIN,
620
+#else
621
+  #define _FAN4
622
+#endif
623
+#if PIN_EXISTS(FAN5)
624
+  #define _FAN5 FAN5_PIN,
625
+#else
626
+  #define _FAN5
627
+#endif
628
+#if PIN_EXISTS(FAN6)
629
+  #define _FAN6 FAN6_PIN,
630
+#else
631
+  #define _FAN6
632
+#endif
633
+#if PIN_EXISTS(FAN7)
634
+  #define _FAN7 FAN7_PIN,
635
+#else
636
+  #define _FAN7
637
+#endif
542 638
 #if PIN_EXISTS(CONTROLLER_FAN)
543 639
   #define _FANC CONTROLLER_FAN_PIN,
544 640
 #else
@@ -550,9 +646,9 @@
550 646
 #endif
551 647
 
552 648
 #define SENSITIVE_PINS { \
553
-  _X_PINS _Y_PINS _Z_PINS _X2_PINS _Y2_PINS _Z2_PINS _Z3_PINS _Z4_PINS \
554
-  _Z_PROBE _E0_PINS _E1_PINS _E2_PINS _E3_PINS _E4_PINS _E5_PINS \
555
-  _BED_PINS _H0_PINS _H1_PINS _H2_PINS _H3_PINS _H4_PINS _H5_PINS \
556
-  _PS_ON _HEATER_BED _FAN0 _FAN1 _FAN2 _FANC \
649
+  _X_PINS _Y_PINS _Z_PINS _X2_PINS _Y2_PINS _Z2_PINS _Z3_PINS _Z4_PINS _Z_PROBE \
650
+  _E0_PINS _E1_PINS _E2_PINS _E3_PINS _E4_PINS _E5_PINS _E6_PINS _E7_PINS _BED_PINS \
651
+  _H0_PINS _H1_PINS _H2_PINS _H3_PINS _H4_PINS _H5_PINS _H6_PINS _H7_PINS \
652
+  _PS_ON _HEATER_BED _FAN0 _FAN1 _FAN2 _FAN3 _FAN4 _FAN5 _FAN6 _FAN7 _FANC \
557 653
   HAL_SENSITIVE_PINS \
558 654
 }

+ 391
- 0
Marlin/src/pins/stm32/pins_BTT_GTR_V1_0.h View File

@@ -0,0 +1,391 @@
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
+#pragma once
23
+
24
+#ifndef TARGET_STM32F4
25
+  #error "Oops! Select an STM32F4 board in 'Tools > Board.'"
26
+#elif HOTENDS > 8 || E_STEPPERS > 8
27
+  #error "BIGTREE GTR V1.0 supports up to 8 hotends / E-steppers."
28
+#elif HOTENDS > MAX_EXTRUDERS || E_STEPPERS > MAX_EXTRUDERS
29
+  #error "Marlin extruder/hotends limit! Increase MAX_EXTRUDERS to continue."
30
+#endif
31
+
32
+#define BOARD_INFO_NAME "BIGTREE GTR 1.0"
33
+
34
+// Use one of these or SDCard-based Emulation will be used
35
+//#define I2C_EEPROM
36
+//#define SRAM_EEPROM_EMULATION   // Use BackSRAM-based EEPROM emulation
37
+//#define FLASH_EEPROM_EMULATION  // Use Flash-based EEPROM emulation
38
+
39
+#define TP   // Enable to define servo and probe pins
40
+
41
+//
42
+// Servos
43
+//
44
+#if ENABLED(TP)
45
+  #define SERVO0_PIN       PB11
46
+#endif
47
+
48
+#define PS_ON_PIN          PH6
49
+
50
+//
51
+// Limit Switches
52
+//
53
+#define X_MIN_PIN          PF2
54
+#define X_MAX_PIN          PG14
55
+#define Y_MIN_PIN          PC13
56
+#define Y_MAX_PIN          PG9
57
+#define Z_MIN_PIN          PE0
58
+#define Z_MAX_PIN          PD3
59
+
60
+//
61
+// Pins on the extender
62
+//
63
+//#define X_MIN_PIN        PI4
64
+//#define X2_MIN_PIN       PF12
65
+//#define Y_MIN_PIN        PF4
66
+//#define Y2_MIN_PIN       PI7
67
+//#define Z_MIN_PIN        PF6
68
+
69
+#if ENABLED(TP) && !defined(Z_MIN_PROBE_PIN)
70
+  #define Z_MIN_PROBE_PIN PH11   // Z Probe must be PH11
71
+#endif
72
+
73
+//
74
+// Steppers
75
+//
76
+#define X_STEP_PIN         PC15
77
+#define X_DIR_PIN          PF0
78
+#define X_ENABLE_PIN       PF1
79
+#ifndef X_CS_PIN
80
+  #define X_CS_PIN         PC14
81
+#endif
82
+
83
+#define Y_STEP_PIN         PE3
84
+#define Y_DIR_PIN          PE2
85
+#define Y_ENABLE_PIN       PE4
86
+#ifndef Y_CS_PIN
87
+  #define Y_CS_PIN         PE1
88
+#endif
89
+
90
+#define Z_STEP_PIN         PB8
91
+#define Z_DIR_PIN          PB7   // PB7
92
+#define Z_ENABLE_PIN       PB9
93
+#ifndef Z_CS_PIN
94
+  #define Z_CS_PIN         PB5
95
+#endif
96
+
97
+#define E0_STEP_PIN        PG12
98
+#define E0_DIR_PIN         PG11
99
+#define E0_ENABLE_PIN      PG13
100
+#ifndef E0_CS_PIN
101
+  #define E0_CS_PIN        PG10
102
+#endif
103
+
104
+#define E1_STEP_PIN        PD6
105
+#define E1_DIR_PIN         PD5
106
+#define E1_ENABLE_PIN      PD7
107
+#ifndef E1_CS_PIN
108
+  #define E1_CS_PIN        PD4
109
+#endif
110
+
111
+#define E2_STEP_PIN        PD1
112
+#define E2_DIR_PIN         PD0
113
+#define E2_ENABLE_PIN      PD2
114
+#ifndef E2_CS_PIN
115
+  #define E2_CS_PIN        PC12
116
+#endif
117
+
118
+#define E3_STEP_PIN        PF3
119
+#define E3_DIR_PIN         PG3
120
+#define E3_ENABLE_PIN      PF8
121
+#ifndef E3_CS_PIN
122
+  #define E3_CS_PIN        PG4
123
+#endif
124
+
125
+#define E4_STEP_PIN        PD14
126
+#define E4_DIR_PIN         PD11
127
+#define E4_ENABLE_PIN      PG2
128
+#ifndef E4_CS_PIN
129
+  #define E4_CS_PIN        PE15
130
+#endif
131
+
132
+#define E5_STEP_PIN        PE12
133
+#define E5_DIR_PIN         PE10
134
+#define E5_ENABLE_PIN      PF14
135
+#ifndef E5_CS_PIN
136
+  #define E5_CS_PIN        PE7
137
+#endif
138
+
139
+#define E6_STEP_PIN        PG0
140
+#define E6_DIR_PIN         PG1
141
+#define E6_ENABLE_PIN      PE8
142
+#ifndef E6_CS_PIN
143
+  #define E6_CS_PIN        PF15
144
+#endif
145
+
146
+#define E7_STEP_PIN        PH12
147
+#define E7_DIR_PIN         PH15
148
+#define E7_ENABLE_PIN      PI0
149
+#ifndef E7_CS_PIN
150
+  #define E7_CS_PIN        PH14
151
+#endif
152
+
153
+//
154
+// Software SPI pins for TMC2130 stepper drivers
155
+//
156
+#if ENABLED(TMC_USE_SW_SPI)
157
+  #ifndef TMC_SW_MOSI
158
+    #define TMC_SW_MOSI    PG15
159
+  #endif
160
+  #ifndef TMC_SW_MISO
161
+    #define TMC_SW_MISO    PB6
162
+  #endif
163
+  #ifndef TMC_SW_SCK
164
+    #define TMC_SW_SCK     PB3
165
+  #endif
166
+#endif
167
+
168
+#if HAS_TMC220x
169
+  /**
170
+   * TMC2208/TMC2209 stepper drivers
171
+   *
172
+   * Hardware serial communication ports.
173
+   * If undefined software serial is used according to the pins below
174
+   */
175
+  //#define X_HARDWARE_SERIAL  Serial
176
+  //#define X2_HARDWARE_SERIAL Serial1
177
+  //#define Y_HARDWARE_SERIAL  Serial1
178
+  //#define Y2_HARDWARE_SERIAL Serial1
179
+  //#define Z_HARDWARE_SERIAL  Serial1
180
+  //#define Z2_HARDWARE_SERIAL Serial1
181
+  //#define E0_HARDWARE_SERIAL Serial1
182
+  //#define E1_HARDWARE_SERIAL Serial1
183
+  //#define E2_HARDWARE_SERIAL Serial1
184
+  //#define E3_HARDWARE_SERIAL Serial1
185
+  //#define E4_HARDWARE_SERIAL Serial1
186
+  //#define E5_HARDWARE_SERIAL Serial1
187
+  //#define E6_HARDWARE_SERIAL Serial1
188
+  //#define E7_HARDWARE_SERIAL Serial1
189
+
190
+  //
191
+  // Software serial
192
+  //
193
+  #define X_SERIAL_TX_PIN  PC14
194
+  #define X_SERIAL_RX_PIN  PC14
195
+
196
+  #define Y_SERIAL_TX_PIN  PE1
197
+  #define Y_SERIAL_RX_PIN  PE1
198
+
199
+  #define Z_SERIAL_TX_PIN  PB5
200
+  #define Z_SERIAL_RX_PIN  PB5
201
+
202
+  #define E0_SERIAL_TX_PIN PG10
203
+  #define E0_SERIAL_RX_PIN PG10
204
+
205
+  #define E1_SERIAL_TX_PIN PD4
206
+  #define E1_SERIAL_RX_PIN PD4
207
+
208
+  #define E2_SERIAL_TX_PIN PC12
209
+  #define E2_SERIAL_RX_PIN PC12
210
+
211
+  #define E3_SERIAL_TX_PIN PG4
212
+  #define E3_SERIAL_RX_PIN PG4
213
+
214
+  #define E4_SERIAL_TX_PIN PE15
215
+  #define E4_SERIAL_RX_PIN PE15
216
+
217
+  #define E5_SERIAL_TX_PIN PE7
218
+  #define E5_SERIAL_RX_PIN PE7
219
+
220
+  #define E6_SERIAL_TX_PIN PF15
221
+  #define E6_SERIAL_RX_PIN PF15
222
+
223
+  #define E7_SERIAL_TX_PIN PH14
224
+  #define E7_SERIAL_RX_PIN PH14
225
+
226
+  // Reduce baud rate to improve software serial reliability
227
+  #define TMC_BAUD_RATE 19200
228
+#endif
229
+
230
+//
231
+// Temperature Sensors
232
+//
233
+#define TEMP_0_PIN         PC1   // T1 <-> E0
234
+#define TEMP_1_PIN         PC2   // T2 <-> E1
235
+#define TEMP_2_PIN         PC3   // T3 <-> E2
236
+
237
+#define TEMP_3_PIN         PA3   // T4 <-> E3
238
+#define TEMP_4_PIN         PF9   // T5 <-> E4
239
+#define TEMP_5_PIN         PF10  // T6 <-> E5
240
+//#define TEMP_6_PIN         PF7   // T7 <-> E6
241
+//#define TEMP_7_PIN         PF5   // T8 <-> E7
242
+
243
+#define TEMP_BED_PIN       PC0   // T0 <-> Bed
244
+
245
+// SPI for Max6675 or Max31855 Thermocouple
246
+// Uses a separate SPI bus
247
+// If you have a two-way thermocouple, you can customize two THERMO_CSx_PIN pins (x:1~2)
248
+
249
+#define THERMO_SCK_PIN     PI1   // SCK
250
+#define THERMO_DO_PIN      PI2   // MISO
251
+#define THERMO_CS1_PIN     PH9   // CS1
252
+#define THERMO_CS2_PIN     PH2   // CS2
253
+
254
+#define MAX6675_SS_PIN     THERMO_CS1_PIN
255
+#define MAX6675_SS2_PIN    THERMO_CS2_PIN
256
+#define MAX6675_SCK_PIN    THERMO_SCK_PIN
257
+#define MAX6675_DO_PIN     THERMO_DO_PIN
258
+
259
+//
260
+// Heaters / Fans
261
+//
262
+#define HEATER_0_PIN       PB1   // Heater0
263
+#define HEATER_1_PIN       PA1   // Heater1
264
+#define HEATER_2_PIN       PB0   // Heater2
265
+
266
+#define HEATER_3_PIN       PD15  // Heater3
267
+#define HEATER_4_PIN       PD13  // Heater4
268
+#define HEATER_5_PIN       PD12  // Heater5
269
+//#define HEATER_6_PIN       PE13 // Heater6
270
+//#define HEATER_7_PIN       PI6  // Heater7
271
+
272
+#define HEATER_BED_PIN     PA2   // Hotbed
273
+
274
+#define FAN_PIN            PE5   // Fan0
275
+#define FAN1_PIN           PE6   // Fan1
276
+#define FAN2_PIN           PC8   // Fan2
277
+
278
+#define FAN3_PIN           PI5   // Fan3
279
+#define FAN4_PIN           PE9   // Fan4
280
+#define FAN5_PIN           PE11  // Fan5
281
+//#define FAN6_PIN           PC9   // Fan6
282
+//#define FAN7_PIN           PE14  // Fan7
283
+
284
+//
285
+// By default the onboard SD (SPI1) is enabled
286
+//
287
+#define CUSTOM_SPI_PINS
288
+#if DISABLED(CUSTOM_SPI_PINS)
289
+  #define SDSS             PB12
290
+#endif
291
+
292
+// HAL SPI1 pins group
293
+#if ENABLED(CUSTOM_SPI_PINS)
294
+  #define SDSS             PA4
295
+  #define SD_DETECT_PIN    PC4
296
+  #define LCD_SDSS         PA4
297
+
298
+  #define SCK_PIN          PA5
299
+  #define MISO_PIN         PA6
300
+  #define MOSI_PIN         PA7
301
+  #define SS_PIN           PA4   // Chip select for SD card used by Marlin
302
+#endif
303
+
304
+/**
305
+ *               _____                                             _____
306
+ *           NC | · · | GND                                    5V | · · | GND
307
+ *        RESET | · · | PB10(SD_DETECT)             (LCD_D7)  PG5 | · · | PG6  (LCD_D6)
308
+ *   (MOSI)PB15 | · · | PH10(BTN_EN2)               (LCD_D5)  PG7 | · · | PG8  (LCD_D4)
309
+ *  (SD_SS)PB12 | · · | PD10(BTN_EN1)               (LCD_RS)  PA8 | · · | PC10 (LCD_EN)
310
+ *    (SCK)PB13 | · · | PB14(MISO)                 (BTN_ENC) PA15 | · · | PC11  (BEEPER)
311
+ *                ̄ ̄                                                ̄ ̄
312
+ *               EXP2                                              EXP1
313
+ */
314
+
315
+//
316
+// LCDs and Controllers
317
+//
318
+#if HAS_SPI_LCD
319
+  #define BEEPER_PIN       PC11
320
+  #define BTN_ENC          PA15
321
+
322
+  #if ENABLED(CR10_STOCKDISPLAY)
323
+
324
+    #define LCD_PINS_RS    PA8
325
+
326
+    #define BTN_EN1        PD10
327
+    #define BTN_EN2        PH10
328
+
329
+    #define LCD_PINS_ENABLE PG7
330
+    #define LCD_PINS_D4    PG8
331
+
332
+    //#undef ST7920_DELAY_1
333
+    //#undef ST7920_DELAY_2
334
+    //#undef ST7920_DELAY_3
335
+
336
+  #else
337
+
338
+    #define LCD_PINS_RS    PA8
339
+
340
+    #define BTN_EN1        PD10
341
+    #define BTN_EN2        PH10
342
+
343
+    #if DISABLED(CUSTOM_SPI_PINS)
344
+      #define SD_DETECT_PIN PB10
345
+      #define LCD_SDSS     PB12
346
+    #endif
347
+
348
+    #define LCD_PINS_ENABLE PC10
349
+    #define LCD_PINS_D4    PG8
350
+
351
+    #if ENABLED(FYSETC_MINI_12864)
352
+      #define DOGLCD_CS    PC10
353
+      #define DOGLCD_A0    PA8
354
+      //#define LCD_BACKLIGHT_PIN -1
355
+      #define LCD_RESET_PIN PG8   // Must be high or open for LCD to operate normally.
356
+      #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0)
357
+        #ifndef RGB_LED_R_PIN
358
+          #define RGB_LED_R_PIN PG7
359
+        #endif
360
+        #ifndef RGB_LED_G_PIN
361
+          #define RGB_LED_G_PIN PG6
362
+        #endif
363
+        #ifndef RGB_LED_B_PIN
364
+          #define RGB_LED_B_PIN PG5
365
+        #endif
366
+      #elif ENABLED(FYSETC_MINI_12864_2_1)
367
+        #define NEOPIXEL_PIN    PF13
368
+      #endif
369
+    #endif // !FYSETC_MINI_12864
370
+
371
+    #if ENABLED(ULTIPANEL)
372
+      #define LCD_PINS_D5  PG7
373
+      #define LCD_PINS_D6  PG6
374
+      #define LCD_PINS_D7  PG5
375
+    #endif
376
+
377
+  #endif
378
+
379
+  // Alter timing for graphical display
380
+  #if HAS_GRAPHICAL_LCD
381
+    #define BOARD_ST7920_DELAY_1 DELAY_NS(96)
382
+    #define BOARD_ST7920_DELAY_2 DELAY_NS(48)
383
+    #define BOARD_ST7920_DELAY_3 DELAY_NS(600)
384
+  #endif
385
+
386
+  //#define DOGLCD_CS      PB12
387
+  //#define DOGLCD_A0      PA8
388
+  //#define LCD_PINS_DC    PB14
389
+  //#define DOGLCD_MOSI    PB15
390
+
391
+#endif // HAS_SPI_LCD

+ 35
- 14
buildroot/share/PlatformIO/variants/BIGTREE_SKR_PRO_1v1/PeripheralPins.c View File

@@ -90,8 +90,13 @@ const PinMap PinMap_I2C_SDA[] = {
90 90
   {PB_9,  I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C1)},
91 91
   {PB_11, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)},
92 92
   {PC_9,  I2C3, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C3)},
93
-  #if STM32F4X_PIN_NUM >= 144  //144 pins mcu, 114 gpio
94
-    {PF_0,  I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)},
93
+  #if STM32F4X_PIN_NUM >= 144   // 144 pins mcu, 114 gpio
94
+    #if STM32F4X_PIN_NUM >= 176
95
+      {PH_5,  I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)},
96
+      {PH_8,  I2C3, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C3)},
97
+  	#else
98
+      {PF_0,  I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)},
99
+    #endif
95 100
   #endif
96 101
   {NC,    NP,    0}
97 102
 };
@@ -103,8 +108,14 @@ const PinMap PinMap_I2C_SCL[] = {
103 108
   {PB_6,  I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C1)},
104 109
   {PB_8,  I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C1)},
105 110
   {PB_10, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)},
106
-  #if STM32F4X_PIN_NUM >= 144  //144 pins mcu, 114 gpio
107
-    {PF_1,  I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)},
111
+  #if STM32F4X_PIN_NUM >= 144   // 144 pins mcu, 114 gpio
112
+    #if STM32F4X_PIN_NUM >= 176
113
+      //{PF_1,  I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)},
114
+      {PH_4,  I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)},
115
+      {PH_7,  I2C3, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C3)},
116
+  	#else
117
+      {PF_1,  I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)},
118
+    #endif
108 119
   #endif
109 120
   {NC,    NP,    0}
110 121
 };
@@ -141,8 +152,10 @@ const PinMap PinMap_PWM[] = {
141 152
    */
142 153
   //{PA_0,  TIM2,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 1, 0)}, // TIM2_CH1
143 154
   //{PA_0,  TIM5,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 1, 0)}, // TIM5_CH1
144
-  //{PA_1,  TIM2,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 2, 0)}, // TIM2_CH2
145
-  //{PA_2,  TIM2,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 3, 0)}, // TIM2_CH3
155
+  {PA_1,  TIM2,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 2, 0)}, // TIM2_CH2 is bltouch analog?
156
+  {PA_2,  TIM2,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 3, 0)}, // TIM2_CH3 is bltouch analog?
157
+  //{PA_1,  TIM5,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 2, 0)}, // TIM5_CH2
158
+  //{PA_2,  TIM5,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 3, 0)}, // TIM5_CH3
146 159
   //{PA_2,  TIM9,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM9, 1, 0)}, // TIM9_CH1
147 160
   //{PA_3,  TIM2,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 4, 0)}, // TIM2_CH4
148 161
   //{PA_3,  TIM5,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 4, 0)}, // TIM5_CH4
@@ -173,7 +186,7 @@ const PinMap PinMap_PWM[] = {
173 186
   //{PB_9,  TIM4,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 4, 0)}, // TIM4_CH4
174 187
   //{PB_9,  TIM11,  STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM11, 1, 0)}, // TIM11_CH1
175 188
   //{PB_10, TIM2,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 3, 0)}, // TIM2_CH3
176
-  //{PB_11, TIM2,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 4, 0)}, // TIM2_CH4
189
+  {PB_11, TIM2,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 4, 0)}, // TIM2_CH4
177 190
   //{PB_13, TIM1,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 1)}, // TIM1_CH1N
178 191
   //{PB_14, TIM1,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N
179 192
   //{PB_14, TIM8,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 1)}, // TIM8_CH2N
@@ -186,21 +199,28 @@ const PinMap PinMap_PWM[] = {
186 199
   //{PC_7,  TIM8,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 0)}, // TIM8_CH2
187 200
   //{PC_8,  TIM3,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 3, 0)}, // TIM3_CH3
188 201
   //{PC_9,  TIM3,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 4, 0)}, // TIM3_CH4
189
-  //{PD_13, TIM4,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 2, 0)}, // TIM4_CH2
190
-  //{PD_15, TIM4,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 4, 0)}, // TIM4_CH4
202
+  {PD_13, TIM4,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 2, 0)}, // TIM4_CH2
203
+  {PD_15, TIM4,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 4, 0)}, // TIM4_CH4
191 204
   //{PE_8,  TIM1,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 1)}, // TIM1_CH1N
192
-  //{PE_9,  TIM1,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 0)}, // TIM1_CH1
205
+  {PE_9,  TIM1,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 0)}, // TIM1_CH1
193 206
   //{PE_10, TIM1,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N
194
-  //{PE_11, TIM1,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 0)}, // TIM1_CH2
207
+  {PE_11, TIM1,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 0)}, // TIM1_CH2
195 208
   //{PE_12, TIM1,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 1)}, // TIM1_CH3N
196
-  //{PE_13, TIM1,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 0)}, // TIM1_CH3
197
-  //{PE_14, TIM1,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 4, 0)}, // TIM1_CH4
209
+  {PE_13, TIM1,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 0)}, // TIM1_CH3
210
+  {PE_14, TIM1,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 4, 0)}, // TIM1_CH4
198 211
   #if STM32F4X_PIN_NUM >= 144  //144 pins mcu, 114 gpio
199 212
     //{PF_6,  TIM10,  STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM10, 1, 0)}, // TIM10_CH1
200 213
     //{PF_7,  TIM11,  STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM11, 1, 0)}, // TIM11_CH1
201 214
     //{PF_8,  TIM13,  STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM13, 1, 0)}, // TIM13_CH1
202 215
     //{PF_9,  TIM14,  STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM14, 1, 0)}, // TIM14_CH1
203 216
   #endif
217
+  #if STM32F4X_PIN_NUM >= 176  //176 pins mcu, 140 gpio
218
+    {PH_10,  TIM5,  STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 1, 0)}, // TIM5_CH1
219
+    {PH_6,  TIM12,  STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM12, 1, 0)}, // TIM12_CH1
220
+    //{PH_11,  TIM5,  STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 2, 0)}, // TIM5_CH2
221
+    {PI_5,  TIM8,  STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 0)}, // TIM8_CH1
222
+    {PI_6,  TIM8,  STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 0)}, // TIM8_CH2
223
+  #endif
204 224
   {NC,    NP,    0}
205 225
 };
206 226
 #endif
@@ -275,7 +295,8 @@ const PinMap PinMap_UART_CTS[] = {
275 295
 
276 296
 #ifdef HAL_SPI_MODULE_ENABLED
277 297
 const PinMap PinMap_SPI_MOSI[] = {
278
-  {PB_5,  SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF5_SPI1)},
298
+  //{PB_5,  SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF5_SPI1)},
299
+  {PA_7,  SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF5_SPI1)},
279 300
   {PB_15, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)},
280 301
   {PC_12, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)},
281 302
   {NC,    NP,    0}

+ 32
- 1
platformio.ini View File

@@ -586,7 +586,7 @@ lib_ignore    = Adafruit NeoPixel
586 586
 
587 587
 #
588 588
 # STM32F401VE
589
-# 'STEVAL-3DP001)' STM32F401VE board - https://www.st.com/en/evaluation-tools/steval-3dp001v1.html
589
+# 'STEVAL-3DP001V1' STM32F401VE board - https://www.st.com/en/evaluation-tools/steval-3dp001v1.html
590 590
 #
591 591
 [env:STM32F401VE_STEVAL]
592 592
 platform          = ststm32
@@ -678,6 +678,37 @@ debug_tool        = stlink
678 678
 debug_init_break  =
679 679
 
680 680
 #
681
+# Bigtreetech GTR V1.0 (STM32F407IGT6 ARM Cortex-M4)
682
+#
683
+[env:BIGTREE_GTR_V1_0]
684
+platform          = ststm32@>=5.7.0
685
+framework         = arduino
686
+platform_packages = framework-arduinoststm32@>=3.10700.191028
687
+board             = BigTree_SKR_Pro
688
+extra_scripts     = pre:buildroot/share/PlatformIO/scripts/generic_create_variant.py
689
+build_flags       = ${common.build_flags}
690
+  -DUSBCON -DUSBD_USE_CDC -DUSBD_VID=0x0483 -DUSB_PRODUCT=\"STM32F407IG\"
691
+  -DTARGET_STM32F4 -DSTM32F407IX -DVECT_TAB_OFFSET=0x8000
692
+  -DHAVE_HWSERIAL3
693
+  -DHAVE_HWSERIAL6
694
+  -DPIN_SERIAL3_RX=PD_9
695
+  -DPIN_SERIAL3_TX=PD_8
696
+  -DPIN_SERIAL6_RX=PC_7
697
+  -DPIN_SERIAL6_TX=PC_6
698
+
699
+  -IMarlin/src/HAL/HAL_STM32
700
+lib_deps          =
701
+  U8glib-HAL=https://github.com/MarlinFirmware/U8glib-HAL/archive/bugfix.zip
702
+  LiquidCrystal
703
+  TMCStepper@>=0.5.2,<1.0.0
704
+  Adafruit NeoPixel
705
+  LiquidTWI2=https://github.com/lincomatic/LiquidTWI2/archive/master.zip
706
+  Arduino-L6470=https://github.com/ameyer/Arduino-L6470/archive/dev.zip
707
+lib_ignore        = SoftwareSerial, SoftwareSerialM
708
+src_filter        = ${common.default_src_filter} +<src/HAL/HAL_STM32>
709
+monitor_speed     = 250000
710
+
711
+#
681 712
 # BigTreeTech BTT002 (STM32F407VET6 ARM Cortex-M4)
682 713
 #
683 714
 [env:BIGTREE_BTT002]

Loading…
Cancel
Save