Browse Source

Quad Z stepper support (#16277)

InsanityAutomation 4 years ago
parent
commit
0fcf2b1110
52 changed files with 1198 additions and 415 deletions
  1. 1
    0
      Marlin/Configuration.h
  2. 46
    20
      Marlin/Configuration_adv.h
  3. 16
    0
      Marlin/src/HAL/HAL_AVR/endstop_interrupts.h
  4. 6
    0
      Marlin/src/HAL/HAL_DUE/endstop_interrupts.h
  5. 6
    0
      Marlin/src/HAL/HAL_ESP32/endstop_interrupts.h
  6. 13
    1
      Marlin/src/HAL/HAL_LPC1768/endstop_interrupts.h
  7. 34
    11
      Marlin/src/HAL/HAL_SAMD51/endstop_interrupts.h
  8. 6
    0
      Marlin/src/HAL/HAL_STM32/endstop_interrupts.h
  9. 6
    0
      Marlin/src/HAL/HAL_STM32F1/endstop_interrupts.h
  10. 6
    0
      Marlin/src/HAL/HAL_STM32_F4_F7/endstop_interrupts.h
  11. 6
    0
      Marlin/src/HAL/HAL_TEENSY35_36/endstop_interrupts.h
  12. 5
    3
      Marlin/src/core/drivers.h
  13. 3
    0
      Marlin/src/core/language.h
  14. 3
    0
      Marlin/src/feature/controllerfan.cpp
  15. 22
    1
      Marlin/src/feature/tmc_util.cpp
  16. 1
    1
      Marlin/src/feature/tmc_util.h
  17. 28
    15
      Marlin/src/gcode/calibrate/G34_M422.cpp
  18. 22
    13
      Marlin/src/gcode/calibrate/M666.cpp
  19. 3
    0
      Marlin/src/gcode/feature/L6470/M122.cpp
  20. 7
    1
      Marlin/src/gcode/feature/L6470/M906.cpp
  21. 1
    0
      Marlin/src/gcode/feature/L6470/M916-918.cpp
  22. 10
    3
      Marlin/src/gcode/feature/trinamic/M569.cpp
  23. 8
    2
      Marlin/src/gcode/feature/trinamic/M906.cpp
  24. 21
    3
      Marlin/src/gcode/feature/trinamic/M911-M914.cpp
  25. 2
    2
      Marlin/src/gcode/gcode.cpp
  26. 3
    0
      Marlin/src/gcode/host/M114.cpp
  27. 1
    4
      Marlin/src/inc/Conditionals_LCD.h
  28. 5
    0
      Marlin/src/inc/Conditionals_adv.h
  29. 118
    71
      Marlin/src/inc/Conditionals_post.h
  30. 90
    62
      Marlin/src/inc/SanityCheck.h
  31. 9
    0
      Marlin/src/lcd/menu/menu_tmc.cpp
  32. 27
    7
      Marlin/src/libs/L64XX/L64XX_Marlin.cpp
  33. 1
    1
      Marlin/src/libs/L64XX/L64XX_Marlin.h
  34. 115
    69
      Marlin/src/module/configuration_store.cpp
  35. 89
    16
      Marlin/src/module/endstops.cpp
  36. 7
    3
      Marlin/src/module/endstops.h
  37. 103
    55
      Marlin/src/module/motion.cpp
  38. 95
    18
      Marlin/src/module/stepper.cpp
  39. 16
    9
      Marlin/src/module/stepper.h
  40. 3
    0
      Marlin/src/module/stepper/L64xx.cpp
  41. 17
    0
      Marlin/src/module/stepper/L64xx.h
  42. 6
    0
      Marlin/src/module/stepper/TMC26X.cpp
  43. 8
    0
      Marlin/src/module/stepper/TMC26X.h
  44. 35
    2
      Marlin/src/module/stepper/indirection.h
  45. 26
    0
      Marlin/src/module/stepper/trinamic.cpp
  46. 14
    0
      Marlin/src/module/stepper/trinamic.h
  47. 49
    2
      Marlin/src/pins/pins.h
  48. 36
    0
      Marlin/src/pins/pinsDebug_list.h
  49. 3
    7
      Marlin/src/pins/ramps/pins_RL200.h
  50. 31
    5
      Marlin/src/pins/sensitive_pins.h
  51. 5
    5
      buildroot/share/tests/DUE-tests
  52. 4
    3
      buildroot/share/tests/teensy35-tests

+ 1
- 0
Marlin/Configuration.h View File

@@ -670,6 +670,7 @@
670 670
 //#define Y2_DRIVER_TYPE A4988
671 671
 //#define Z2_DRIVER_TYPE A4988
672 672
 //#define Z3_DRIVER_TYPE A4988
673
+//#define Z4_DRIVER_TYPE A4988
673 674
 //#define E0_DRIVER_TYPE A4988
674 675
 //#define E1_DRIVER_TYPE A4988
675 676
 //#define E2_DRIVER_TYPE A4988

+ 46
- 20
Marlin/Configuration_adv.h View File

@@ -479,7 +479,7 @@
479 479
   //#define X_DUAL_ENDSTOPS
480 480
   #if ENABLED(X_DUAL_ENDSTOPS)
481 481
     #define X2_USE_ENDSTOP _XMAX_
482
-    #define X_DUAL_ENDSTOPS_ADJUSTMENT  0
482
+    #define X2_ENDSTOP_ADJUSTMENT  0
483 483
   #endif
484 484
 #endif
485 485
 
@@ -489,27 +489,28 @@
489 489
   //#define Y_DUAL_ENDSTOPS
490 490
   #if ENABLED(Y_DUAL_ENDSTOPS)
491 491
     #define Y2_USE_ENDSTOP _YMAX_
492
-    #define Y_DUAL_ENDSTOPS_ADJUSTMENT  0
492
+    #define Y2_ENDSTOP_ADJUSTMENT  0
493 493
   #endif
494 494
 #endif
495 495
 
496
-//#define Z_DUAL_STEPPER_DRIVERS
497
-#if ENABLED(Z_DUAL_STEPPER_DRIVERS)
498
-  //#define Z_DUAL_ENDSTOPS
499
-  #if ENABLED(Z_DUAL_ENDSTOPS)
500
-    #define Z2_USE_ENDSTOP _XMAX_
501
-    #define Z_DUAL_ENDSTOPS_ADJUSTMENT  0
502
-  #endif
503
-#endif
504
-
505
-//#define Z_TRIPLE_STEPPER_DRIVERS
506
-#if ENABLED(Z_TRIPLE_STEPPER_DRIVERS)
507
-  //#define Z_TRIPLE_ENDSTOPS
508
-  #if ENABLED(Z_TRIPLE_ENDSTOPS)
509
-    #define Z2_USE_ENDSTOP _XMAX_
510
-    #define Z3_USE_ENDSTOP _YMAX_
511
-    #define Z_TRIPLE_ENDSTOPS_ADJUSTMENT2  0
512
-    #define Z_TRIPLE_ENDSTOPS_ADJUSTMENT3  0
496
+//
497
+// For Z set the number of stepper drivers
498
+//
499
+#define NUM_Z_STEPPER_DRIVERS 1   // (1-4) Z options change based on how many
500
+
501
+#if NUM_Z_STEPPER_DRIVERS > 1
502
+  //#define Z_MULTI_ENDSTOPS
503
+  #if ENABLED(Z_MULTI_ENDSTOPS)
504
+    #define Z2_USE_ENDSTOP          _XMAX_
505
+    #define Z2_ENDSTOP_ADJUSTMENT   0
506
+    #if NUM_Z_STEPPER_DRIVERS >= 3
507
+      #define Z3_USE_ENDSTOP        _YMAX_
508
+      #define Z3_ENDSTOP_ADJUSTMENT 0
509
+    #endif
510
+    #if NUM_Z_STEPPER_DRIVERS >= 4
511
+      #define Z4_USE_ENDSTOP        _ZMAX_
512
+      #define Z4_ENDSTOP_ADJUSTMENT 0
513
+    #endif
513 514
   #endif
514 515
 #endif
515 516
 
@@ -1898,6 +1899,12 @@
1898 1899
     #define Z3_MICROSTEPS       16
1899 1900
   #endif
1900 1901
 
1902
+  #if AXIS_DRIVER_TYPE_Z4(TMC26X)
1903
+    #define Z4_MAX_CURRENT    1000
1904
+    #define Z4_SENSE_RESISTOR   91
1905
+    #define Z4_MICROSTEPS       16
1906
+  #endif
1907
+
1901 1908
   #if AXIS_DRIVER_TYPE_E0(TMC26X)
1902 1909
     #define E0_MAX_CURRENT    1000
1903 1910
     #define E0_SENSE_RESISTOR   91
@@ -2015,6 +2022,14 @@
2015 2022
     #define Z3_CHAIN_POS     -1
2016 2023
   #endif
2017 2024
 
2025
+  #if AXIS_IS_TMC(Z4)
2026
+    #define Z4_CURRENT      800
2027
+    #define Z4_CURRENT_HOME Z4_CURRENT
2028
+    #define Z4_MICROSTEPS    16
2029
+    #define Z4_RSENSE         0.11
2030
+    #define Z4_CHAIN_POS     -1
2031
+  #endif
2032
+
2018 2033
   #if AXIS_IS_TMC(E0)
2019 2034
     #define E0_CURRENT      800
2020 2035
     #define E0_MICROSTEPS    16
@@ -2104,6 +2119,7 @@
2104 2119
   #define Y2_SLAVE_ADDRESS 0
2105 2120
   #define Z2_SLAVE_ADDRESS 0
2106 2121
   #define Z3_SLAVE_ADDRESS 0
2122
+  #define Z4_SLAVE_ADDRESS 0
2107 2123
   #define E0_SLAVE_ADDRESS 0
2108 2124
   #define E1_SLAVE_ADDRESS 0
2109 2125
   #define E2_SLAVE_ADDRESS 0
@@ -2179,6 +2195,7 @@
2179 2195
   #define Z_HYBRID_THRESHOLD       3
2180 2196
   #define Z2_HYBRID_THRESHOLD      3
2181 2197
   #define Z3_HYBRID_THRESHOLD      3
2198
+  #define Z4_HYBRID_THRESHOLD      3
2182 2199
   #define E0_HYBRID_THRESHOLD     30
2183 2200
   #define E1_HYBRID_THRESHOLD     30
2184 2201
   #define E2_HYBRID_THRESHOLD     30
@@ -2344,6 +2361,15 @@
2344 2361
     #define Z3_SLEW_RATE         1
2345 2362
   #endif
2346 2363
 
2364
+  #if AXIS_IS_L64XX(Z4)
2365
+    #define Z4_MICROSTEPS      128
2366
+    #define Z4_OVERCURRENT    2000
2367
+    #define Z4_STALLCURRENT   1500
2368
+    #define Z4_MAX_VOLTAGE     127
2369
+    #define Z4_CHAIN_POS        -1
2370
+    #define Z4_SLEW_RATE         1
2371
+  #endif
2372
+
2347 2373
   #if AXIS_IS_L64XX(E0)
2348 2374
     #define E0_MICROSTEPS      128
2349 2375
     #define E0_OVERCURRENT    2000
@@ -2407,7 +2433,7 @@
2407 2433
    *         I not present or I0 or I1 - X, Y, Z or E0
2408 2434
    *         I2 - X2, Y2, Z2 or E1
2409 2435
    *         I3 - Z3 or E3
2410
-   *         I4 - E4
2436
+   *         I4 - Z4 or E4
2411 2437
    *         I5 - E5
2412 2438
    * M916 - Increase drive level until get thermal warning
2413 2439
    * M917 - Find minimum current thresholds

+ 16
- 0
Marlin/src/HAL/HAL_AVR/endstop_interrupts.h View File

@@ -232,6 +232,22 @@ void setup_endstop_interrupts() {
232 232
       pciSetup(Z3_MIN_PIN);
233 233
     #endif
234 234
   #endif
235
+  #if HAS_Z4_MAX
236
+    #if (digitalPinToInterrupt(Z4_MAX_PIN) != NOT_AN_INTERRUPT)
237
+      _ATTACH(Z4_MAX_PIN);
238
+    #else
239
+      static_assert(digitalPinHasPCICR(Z4_MAX_PIN), "Z4_MAX_PIN is not interrupt-capable");
240
+      pciSetup(Z4_MAX_PIN);
241
+    #endif
242
+  #endif
243
+  #if HAS_Z4_MIN
244
+    #if (digitalPinToInterrupt(Z4_MIN_PIN) != NOT_AN_INTERRUPT)
245
+      _ATTACH(Z4_MIN_PIN);
246
+    #else
247
+      static_assert(digitalPinHasPCICR(Z4_MIN_PIN), "Z4_MIN_PIN is not interrupt-capable");
248
+      pciSetup(Z4_MIN_PIN);
249
+    #endif
250
+  #endif
235 251
   #if HAS_Z_MIN_PROBE_PIN
236 252
     #if (digitalPinToInterrupt(Z_MIN_PROBE_PIN) != NOT_AN_INTERRUPT)
237 253
       _ATTACH(Z_MIN_PROBE_PIN);

+ 6
- 0
Marlin/src/HAL/HAL_DUE/endstop_interrupts.h View File

@@ -77,6 +77,12 @@ void setup_endstop_interrupts() {
77 77
   #if HAS_Z3_MIN
78 78
     _ATTACH(Z3_MIN_PIN);
79 79
   #endif
80
+  #if HAS_Z4_MAX
81
+    _ATTACH(Z4_MAX_PIN);
82
+  #endif
83
+  #if HAS_Z4_MIN
84
+    _ATTACH(Z4_MIN_PIN);
85
+  #endif
80 86
   #if HAS_Z_MIN_PROBE_PIN
81 87
     _ATTACH(Z_MIN_PROBE_PIN);
82 88
   #endif

+ 6
- 0
Marlin/src/HAL/HAL_ESP32/endstop_interrupts.h View File

@@ -72,6 +72,12 @@ void setup_endstop_interrupts() {
72 72
   #if HAS_Z3_MIN
73 73
     _ATTACH(Z3_MIN_PIN);
74 74
   #endif
75
+  #if HAS_Z4_MAX
76
+    _ATTACH(Z4_MAX_PIN);
77
+  #endif
78
+  #if HAS_Z4_MIN
79
+    _ATTACH(Z4_MIN_PIN);
80
+  #endif
75 81
   #if HAS_Z_MIN_PROBE_PIN
76 82
     _ATTACH(Z_MIN_PROBE_PIN);
77 83
   #endif

+ 13
- 1
Marlin/src/HAL/HAL_LPC1768/endstop_interrupts.h View File

@@ -93,7 +93,7 @@ void setup_endstop_interrupts() {
93 93
     _ATTACH(Z2_MIN_PIN);
94 94
   #endif
95 95
   #if HAS_Z3_MAX
96
-    #if !LPC1768_PIN_INTERRUPT_M(Z3_MIN_PIN)
96
+    #if !LPC1768_PIN_INTERRUPT_M(Z3_MAX_PIN)
97 97
       #error "Z3_MIN_PIN is not INTERRUPT-capable."
98 98
     #endif
99 99
     _ATTACH(Z3_MAX_PIN);
@@ -104,6 +104,18 @@ void setup_endstop_interrupts() {
104 104
     #endif
105 105
     _ATTACH(Z3_MIN_PIN);
106 106
   #endif
107
+  #if HAS_Z4_MAX
108
+    #if !LPC1768_PIN_INTERRUPT_M(Z4_MAX_PIN)
109
+      #error "Z4_MIN_PIN is not INTERRUPT-capable."
110
+    #endif
111
+    _ATTACH(Z4_MAX_PIN);
112
+  #endif
113
+  #if HAS_Z4_MIN
114
+    #if !LPC1768_PIN_INTERRUPT_M(Z4_MIN_PIN)
115
+      #error "Z4_MIN_PIN is not INTERRUPT-capable."
116
+    #endif
117
+    _ATTACH(Z4_MIN_PIN);
118
+  #endif
107 119
   #if HAS_Z_MIN_PROBE_PIN
108 120
     #if !LPC1768_PIN_INTERRUPT_M(Z_MIN_PROBE_PIN)
109 121
       #error "Z_MIN_PROBE_PIN is not INTERRUPT-capable."

+ 34
- 11
Marlin/src/HAL/HAL_SAMD51/endstop_interrupts.h View File

@@ -98,6 +98,16 @@
98 98
 #else
99 99
   #define MATCH_Z3_MIN_EILINE(P) false
100 100
 #endif
101
+#if HAS_Z4_MAX
102
+  #define MATCH_Z4_MAX_EILINE(P) MATCH_EILINE(P, Z4_MAX_PIN)
103
+#else
104
+  #define MATCH_Z4_MAX_EILINE(P) false
105
+#endif
106
+#if HAS_Z4_MIN
107
+  #define MATCH_Z4_MIN_EILINE(P) MATCH_EILINE(P, Z4_MIN_PIN)
108
+#else
109
+  #define MATCH_Z4_MIN_EILINE(P) false
110
+#endif
101 111
 #if HAS_Z_MIN_PROBE_PIN
102 112
   #define MATCH_Z_MIN_PROBE_EILINE(P)   MATCH_EILINE(P, Z_MIN_PROBE_PIN)
103 113
 #else
@@ -109,6 +119,7 @@
109 119
                                  && !MATCH_Z_MAX_EILINE(P) && !MATCH_Z_MIN_EILINE(P)    \
110 120
                                  && !MATCH_Z2_MAX_EILINE(P) && !MATCH_Z2_MIN_EILINE(P)  \
111 121
                                  && !MATCH_Z3_MAX_EILINE(P) && !MATCH_Z3_MIN_EILINE(P)  \
122
+                                 && !MATCH_Z4_MAX_EILINE(P) && !MATCH_Z4_MIN_EILINE(P)  \
112 123
                                  && !MATCH_Z_MIN_PROBE_EILINE(P))
113 124
 
114 125
 // One ISR for all EXT-Interrupts
@@ -117,67 +128,79 @@ void endstop_ISR() { endstops.update(); }
117 128
 void setup_endstop_interrupts() {
118 129
   #if HAS_X_MAX
119 130
     #if !AVAILABLE_EILINE(X_MAX_PIN)
120
-      static_assert(false, "X_MAX_PIN has no EXTINT line available.");
131
+      #error "X_MAX_PIN has no EXTINT line available."
121 132
     #endif
122 133
     attachInterrupt(X_MAX_PIN, endstop_ISR, CHANGE);
123 134
   #endif
124 135
   #if HAS_X_MIN
125 136
     #if !AVAILABLE_EILINE(X_MIN_PIN)
126
-      static_assert(false, "X_MIN_PIN has no EXTINT line available.");
137
+      #error "X_MIN_PIN has no EXTINT line available."
127 138
     #endif
128 139
     attachInterrupt(X_MIN_PIN, endstop_ISR, CHANGE);
129 140
   #endif
130 141
   #if HAS_Y_MAX
131 142
     #if !AVAILABLE_EILINE(Y_MAX_PIN)
132
-      static_assert(false, "Y_MAX_PIN has no EXTINT line available.");
143
+      #error "Y_MAX_PIN has no EXTINT line available."
133 144
     #endif
134 145
     attachInterrupt(Y_MAX_PIN, endstop_ISR, CHANGE);
135 146
   #endif
136 147
   #if HAS_Y_MIN
137 148
     #if !AVAILABLE_EILINE(Y_MIN_PIN)
138
-      static_assert(false, "Y_MIN_PIN has no EXTINT line available.");
149
+      #error "Y_MIN_PIN has no EXTINT line available."
139 150
     #endif
140 151
     attachInterrupt(Y_MIN_PIN, endstop_ISR, CHANGE);
141 152
   #endif
142 153
   #if HAS_Z_MAX
143 154
     #if !AVAILABLE_EILINE(Z_MAX_PIN)
144
-      static_assert(false, "Z_MAX_PIN has no EXTINT line available.");
155
+      #error "Z_MAX_PIN has no EXTINT line available."
145 156
     #endif
146 157
     attachInterrupt(Z_MAX_PIN, endstop_ISR, CHANGE);
147 158
   #endif
148 159
   #if HAS_Z_MIN
149 160
     #if !AVAILABLE_EILINE(Z_MIN_PIN)
150
-      static_assert(false, "Z_MIN_PIN has no EXTINT line available.");
161
+      #error "Z_MIN_PIN has no EXTINT line available."
151 162
     #endif
152 163
     attachInterrupt(Z_MIN_PIN, endstop_ISR, CHANGE);
153 164
   #endif
154 165
   #if HAS_Z2_MAX
155 166
     #if !AVAILABLE_EILINE(Z2_MAX_PIN)
156
-      static_assert(false, "Z2_MAX_PIN has no EXTINT line available.");
167
+      #error "Z2_MAX_PIN has no EXTINT line available."
157 168
     #endif
158 169
     attachInterrupt(Z2_MAX_PIN, endstop_ISR, CHANGE);
159 170
   #endif
160 171
   #if HAS_Z2_MIN
161 172
     #if !AVAILABLE_EILINE(Z2_MIN_PIN)
162
-      static_assert(false, "Z2_MIN_PIN has no EXTINT line available.");
173
+      #error "Z2_MIN_PIN has no EXTINT line available."
163 174
     #endif
164 175
     attachInterrupt(Z2_MIN_PIN, endstop_ISR, CHANGE);
165 176
   #endif
166 177
   #if HAS_Z3_MAX
167 178
     #if !AVAILABLE_EILINE(Z3_MAX_PIN)
168
-      static_assert(false, "Z3_MAX_PIN has no EXTINT line available.");
179
+      #error "Z3_MAX_PIN has no EXTINT line available."
169 180
     #endif
170 181
     attachInterrupt(Z3_MAX_PIN, endstop_ISR, CHANGE);
171 182
   #endif
172 183
   #if HAS_Z3_MIN
173 184
     #if !AVAILABLE_EILINE(Z3_MIN_PIN)
174
-      static_assert(false, "Z3_MIN_PIN has no EXTINT line available.");
185
+      #error "Z3_MIN_PIN has no EXTINT line available."
175 186
     #endif
176 187
     attachInterrupt(Z3_MIN_PIN, endstop_ISR, CHANGE);
177 188
   #endif
189
+  #if HAS_Z4_MAX
190
+    #if !AVAILABLE_EILINE(Z4_MAX_PIN)
191
+      #error "Z4_MAX_PIN has no EXTINT line available."
192
+    #endif
193
+    attachInterrupt(Z4_MAX_PIN, endstop_ISR, CHANGE);
194
+  #endif
195
+  #if HAS_Z4_MIN
196
+    #if !AVAILABLE_EILINE(Z4_MIN_PIN)
197
+      #error "Z4_MIN_PIN has no EXTINT line available."
198
+    #endif
199
+    attachInterrupt(Z4_MIN_PIN, endstop_ISR, CHANGE);
200
+  #endif
178 201
   #if HAS_Z_MIN_PROBE_PIN
179 202
     #if !AVAILABLE_EILINE(Z_MIN_PROBE_PIN)
180
-      static_assert(false, "Z_MIN_PROBE_PIN has no EXTINT line available.");
203
+      #error "Z_MIN_PROBE_PIN has no EXTINT line available."
181 204
     #endif
182 205
     attachInterrupt(Z_MIN_PROBE_PIN, endstop_ISR, CHANGE);
183 206
   #endif

+ 6
- 0
Marlin/src/HAL/HAL_STM32/endstop_interrupts.h View File

@@ -58,6 +58,12 @@ void setup_endstop_interrupts() {
58 58
   #if HAS_Z3_MIN
59 59
     attachInterrupt(Z3_MIN_PIN, endstop_ISR, CHANGE);
60 60
   #endif
61
+  #if HAS_Z4_MAX
62
+    attachInterrupt(Z4_MAX_PIN, endstop_ISR, CHANGE);
63
+  #endif
64
+  #if HAS_Z4_MIN
65
+    attachInterrupt(Z4_MIN_PIN, endstop_ISR, CHANGE);
66
+  #endif
61 67
   #if HAS_Z_MIN_PROBE_PIN
62 68
     attachInterrupt(Z_MIN_PROBE_PIN, endstop_ISR, CHANGE);
63 69
   #endif

+ 6
- 0
Marlin/src/HAL/HAL_STM32F1/endstop_interrupts.h View File

@@ -83,6 +83,12 @@ void setup_endstop_interrupts() {
83 83
   #if HAS_Z3_MIN
84 84
     attachInterrupt(Z3_MIN_PIN, endstop_ISR, CHANGE);
85 85
   #endif
86
+    #if HAS_Z4_MAX
87
+    attachInterrupt(Z4_MAX_PIN, endstop_ISR, CHANGE);
88
+  #endif
89
+  #if HAS_Z4_MIN
90
+    attachInterrupt(Z4_MIN_PIN, endstop_ISR, CHANGE);
91
+  #endif
86 92
   #if HAS_Z_MIN_PROBE_PIN
87 93
     attachInterrupt(Z_MIN_PROBE_PIN, endstop_ISR, CHANGE);
88 94
   #endif

+ 6
- 0
Marlin/src/HAL/HAL_STM32_F4_F7/endstop_interrupts.h View File

@@ -58,6 +58,12 @@ void setup_endstop_interrupts() {
58 58
   #if HAS_Z3_MIN
59 59
     attachInterrupt(Z3_MIN_PIN, endstop_ISR, CHANGE);
60 60
   #endif
61
+  #if HAS_Z4_MAX
62
+    attachInterrupt(Z4_MAX_PIN, endstop_ISR, CHANGE);
63
+  #endif
64
+  #if HAS_Z4_MIN
65
+    attachInterrupt(Z4_MIN_PIN, endstop_ISR, CHANGE);
66
+  #endif
61 67
   #if HAS_Z_MIN_PROBE_PIN
62 68
     attachInterrupt(Z_MIN_PROBE_PIN, endstop_ISR, CHANGE);
63 69
   #endif

+ 6
- 0
Marlin/src/HAL/HAL_TEENSY35_36/endstop_interrupts.h View File

@@ -76,6 +76,12 @@ void setup_endstop_interrupts() {
76 76
   #if HAS_Z3_MIN
77 77
     _ATTACH(Z3_MIN_PIN);
78 78
   #endif
79
+  #if HAS_Z4_MAX
80
+    _ATTACH(Z4_MAX_PIN);
81
+  #endif
82
+  #if HAS_Z4_MIN
83
+    _ATTACH(Z4_MIN_PIN);
84
+  #endif
79 85
   #if HAS_Z_MIN_PROBE_PIN
80 86
     _ATTACH(Z_MIN_PROBE_PIN);
81 87
   #endif

+ 5
- 3
Marlin/src/core/drivers.h View File

@@ -63,8 +63,9 @@
63 63
   #define AXIS_DRIVER_TYPE_X2(T) false
64 64
 #endif
65 65
 #define AXIS_DRIVER_TYPE_Y2(T) (ENABLED(Y_DUAL_STEPPER_DRIVERS) && _AXIS_DRIVER_TYPE(Y2,T))
66
-#define AXIS_DRIVER_TYPE_Z2(T) (Z_MULTI_STEPPER_DRIVERS && _AXIS_DRIVER_TYPE(Z2,T))
67
-#define AXIS_DRIVER_TYPE_Z3(T) (ENABLED(Z_TRIPLE_STEPPER_DRIVERS) && _AXIS_DRIVER_TYPE(Z3,T))
66
+#define AXIS_DRIVER_TYPE_Z2(T) (NUM_Z_STEPPER_DRIVERS >= 2 && _AXIS_DRIVER_TYPE(Z2,T))
67
+#define AXIS_DRIVER_TYPE_Z3(T) (NUM_Z_STEPPER_DRIVERS >= 3 && _AXIS_DRIVER_TYPE(Z3,T))
68
+#define AXIS_DRIVER_TYPE_Z4(T) (NUM_Z_STEPPER_DRIVERS >= 4 && _AXIS_DRIVER_TYPE(Z4,T))
68 69
 #define AXIS_DRIVER_TYPE_E0(T) (E_STEPPERS > 0 && _AXIS_DRIVER_TYPE(E0,T))
69 70
 #define AXIS_DRIVER_TYPE_E1(T) (E_STEPPERS > 1 && _AXIS_DRIVER_TYPE(E1,T))
70 71
 #define AXIS_DRIVER_TYPE_E2(T) (E_STEPPERS > 2 && _AXIS_DRIVER_TYPE(E2,T))
@@ -80,7 +81,8 @@
80 81
 
81 82
 #define HAS_DRIVER(T) (    AXIS_DRIVER_TYPE_X(T)  || AXIS_DRIVER_TYPE_X2(T) \
82 83
                         || AXIS_DRIVER_TYPE_Y(T)  || AXIS_DRIVER_TYPE_Y2(T) \
83
-                        || AXIS_DRIVER_TYPE_Z(T)  || AXIS_DRIVER_TYPE_Z2(T) || AXIS_DRIVER_TYPE_Z3(T) \
84
+                        || AXIS_DRIVER_TYPE_Z(T)  || AXIS_DRIVER_TYPE_Z2(T) \
85
+                        || AXIS_DRIVER_TYPE_Z3(T) || AXIS_DRIVER_TYPE_Z4(T) \
84 86
                         || HAS_E_DRIVER(T) )
85 87
 
86 88
 // Test for supported TMC drivers that require advanced configuration

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

@@ -195,6 +195,8 @@
195 195
 #define MSG_Z2_MAX                          "z2_max"
196 196
 #define MSG_Z3_MIN                          "z3_min"
197 197
 #define MSG_Z3_MAX                          "z3_max"
198
+#define MSG_Z4_MIN                          "z4_min"
199
+#define MSG_Z4_MAX                          "z4_max"
198 200
 #define MSG_Z_PROBE                         "z_probe"
199 201
 #define MSG_FILAMENT_RUNOUT_SENSOR          "filament"
200 202
 #define MSG_PROBE_OFFSET                    "Probe Offset"
@@ -333,6 +335,7 @@
333 335
 #define MSG_Y2 "Y2"
334 336
 #define MSG_Z2 "Z2"
335 337
 #define MSG_Z3 "Z3"
338
+#define MSG_Z4 "Z4"
336 339
 
337 340
 #define LCD_STR_A MSG_A
338 341
 #define LCD_STR_B MSG_B

+ 3
- 0
Marlin/src/feature/controllerfan.cpp View File

@@ -55,6 +55,9 @@ void controllerfan_update() {
55 55
       #if HAS_Z3_ENABLE
56 56
         || Z3_ENABLE_READ() == bool(Z_ENABLE_ON)
57 57
       #endif
58
+      #if HAS_Z4_ENABLE
59
+        || Z4_ENABLE_READ() == bool(Z_ENABLE_ON)
60
+      #endif
58 61
       #if E_STEPPERS
59 62
         #define _OR_ENABLED_E(N) || E##N##_ENABLE_READ() == bool(E_ENABLE_ON)
60 63
         REPEAT(E_STEPPERS, _OR_ENABLED_E)

+ 22
- 1
Marlin/src/feature/tmc_util.cpp View File

@@ -387,7 +387,7 @@
387 387
       }
388 388
       #endif
389 389
 
390
-      #if AXIS_IS_TMC(Z) || AXIS_IS_TMC(Z2) || AXIS_IS_TMC(Z3)
390
+      #if AXIS_IS_TMC(Z) || AXIS_IS_TMC(Z2) || AXIS_IS_TMC(Z3) || AXIS_IS_TMC(Z4)
391 391
       {
392 392
         bool result = false;
393 393
         #if AXIS_IS_TMC(Z)
@@ -399,6 +399,9 @@
399 399
         #if AXIS_IS_TMC(Z3)
400 400
           if (monitor_tmc_driver(stepperZ3, need_update_error_counters, need_debug_reporting)) result = true;
401 401
         #endif
402
+        #if AXIS_IS_TMC(Z4)
403
+          if (monitor_tmc_driver(stepperZ4, need_update_error_counters, need_debug_reporting)) result = true;
404
+        #endif
402 405
         if (result) {
403 406
           #if AXIS_IS_TMC(Z)
404 407
             step_current_down(stepperZ);
@@ -409,6 +412,9 @@
409 412
           #if AXIS_IS_TMC(Z3)
410 413
             step_current_down(stepperZ3);
411 414
           #endif
415
+          #if AXIS_IS_TMC(Z4)
416
+            step_current_down(stepperZ4);
417
+          #endif
412 418
         }
413 419
       }
414 420
       #endif
@@ -750,6 +756,9 @@
750 756
       #if AXIS_IS_TMC(Z3)
751 757
         tmc_status(stepperZ3, i);
752 758
       #endif
759
+      #if AXIS_IS_TMC(Z4)
760
+        tmc_status(stepperZ4, i);
761
+      #endif
753 762
     }
754 763
 
755 764
     if (print_e) {
@@ -805,6 +814,9 @@
805 814
       #if AXIS_IS_TMC(Z3)
806 815
         tmc_parse_drv_status(stepperZ3, i);
807 816
       #endif
817
+      #if AXIS_IS_TMC(Z4)
818
+        tmc_parse_drv_status(stepperZ4, i);
819
+      #endif
808 820
     }
809 821
 
810 822
     if (print_e) {
@@ -980,6 +992,9 @@
980 992
       #if AXIS_IS_TMC(Z3)
981 993
         tmc_get_registers(stepperZ3, i);
982 994
       #endif
995
+      #if AXIS_IS_TMC(Z4)
996
+        tmc_get_registers(stepperZ4, i);
997
+      #endif
983 998
     }
984 999
 
985 1000
     if (print_e) {
@@ -1086,6 +1101,9 @@
1086 1101
     #if AXIS_HAS_SPI(Z3)
1087 1102
       SET_CS_PIN(Z3);
1088 1103
     #endif
1104
+    #if AXIS_HAS_SPI(Z4)
1105
+      SET_CS_PIN(Z4);
1106
+    #endif
1089 1107
     #if AXIS_HAS_SPI(E0)
1090 1108
       SET_CS_PIN(E0);
1091 1109
     #endif
@@ -1160,6 +1178,9 @@ void test_tmc_connection(const bool test_x, const bool test_y, const bool test_z
1160 1178
     #if AXIS_IS_TMC(Z3)
1161 1179
       axis_connection += test_connection(stepperZ3);
1162 1180
     #endif
1181
+    #if AXIS_IS_TMC(Z4)
1182
+      axis_connection += test_connection(stepperZ4);
1183
+    #endif
1163 1184
   }
1164 1185
 
1165 1186
   if (test_e) {

+ 1
- 1
Marlin/src/feature/tmc_util.h View File

@@ -350,7 +350,7 @@ void test_tmc_connection(const bool test_x, const bool test_y, const bool test_z
350 350
 #if USE_SENSORLESS
351 351
 
352 352
   // Track enabled status of stealthChop and only re-enable where applicable
353
-  struct sensorless_t { bool x, y, z, x2, y2, z2, z3; };
353
+  struct sensorless_t { bool x, y, z, x2, y2, z2, z3, z4; };
354 354
 
355 355
   #if ENABLED(IMPROVE_HOMING_RELIABILITY)
356 356
     extern millis_t sg_guard_period;

+ 28
- 15
Marlin/src/gcode/calibrate/G34_M422.cpp View File

@@ -52,20 +52,22 @@ constexpr xy_pos_t test_z_stepper_align_xy[] = Z_STEPPER_ALIGN_XY;
52 52
 
53 53
 #if ENABLED(Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS)
54 54
 
55
-  static_assert(COUNT(test_z_stepper_align_xy) >= Z_STEPPER_COUNT,
55
+  static_assert(COUNT(test_z_stepper_align_xy) >= NUM_Z_STEPPER_DRIVERS,
56 56
     "Z_STEPPER_ALIGN_XY requires at least three {X,Y} entries (Z, Z2, Z3, ...)."
57 57
   );
58 58
 
59 59
   constexpr float test_z_stepper_align_stepper_xy[][XY] = Z_STEPPER_ALIGN_STEPPER_XY;
60 60
   static_assert(
61
-    COUNT(test_z_stepper_align_stepper_xy) == Z_STEPPER_COUNT,
61
+    COUNT(test_z_stepper_align_stepper_xy) == NUM_Z_STEPPER_DRIVERS,
62 62
     "Z_STEPPER_ALIGN_STEPPER_XY requires three {X,Y} entries (one per Z stepper)."
63 63
   );
64 64
 
65 65
 #else
66 66
 
67
-  static_assert(COUNT(test_z_stepper_align_xy) == Z_STEPPER_COUNT,
68
-    #if ENABLED(Z_TRIPLE_STEPPER_DRIVERS)
67
+  static_assert(COUNT(test_z_stepper_align_xy) == NUM_Z_STEPPER_DRIVERS,
68
+    #if NUM_Z_STEPPER_DRIVERS == 4
69
+      "Z_STEPPER_ALIGN_XY requires four {X,Y} entries (Z, Z2, Z3, and Z4)."
70
+    #elif NUM_Z_STEPPER_DRIVERS == 3
69 71
       "Z_STEPPER_ALIGN_XY requires three {X,Y} entries (Z, Z2, and Z3)."
70 72
     #else
71 73
       "Z_STEPPER_ALIGN_XY requires two {X,Y} entries (Z and Z2)."
@@ -85,10 +87,13 @@ static_assert(LTEST(0) && RTEST(0), "The 1st Z_STEPPER_ALIGN_XY X is unreachable
85 87
 static_assert(FTEST(0) && BTEST(0), "The 1st Z_STEPPER_ALIGN_XY Y is unreachable with the default probe Y offset.");
86 88
 static_assert(LTEST(1) && RTEST(1), "The 2nd Z_STEPPER_ALIGN_XY X is unreachable with the default probe X offset.");
87 89
 static_assert(FTEST(1) && BTEST(1), "The 2nd Z_STEPPER_ALIGN_XY Y is unreachable with the default probe Y offset.");
88
-
89
-#if ENABLED(Z_TRIPLE_STEPPER_DRIVERS)
90
+#if NUM_Z_STEPPER_DRIVERS >= 3
90 91
   static_assert(LTEST(2) && RTEST(2), "The 3rd Z_STEPPER_ALIGN_XY X is unreachable with the default probe X offset.");
91 92
   static_assert(FTEST(2) && BTEST(2), "The 3rd Z_STEPPER_ALIGN_XY Y is unreachable with the default probe Y offset.");
93
+  #if NUM_Z_STEPPER_DRIVERS >= 4
94
+    static_assert(LTEST(3) && RTEST(3), "The 4th Z_STEPPER_ALIGN_XY X is unreachable with the default probe X offset.");
95
+    static_assert(FTEST(3) && BTEST(3), "The 4th Z_STEPPER_ALIGN_XY Y is unreachable with the default probe Y offset.");
96
+  #endif
92 97
 #endif
93 98
 
94 99
 //
@@ -105,8 +110,11 @@ static xy_pos_t z_stepper_align_pos[] = Z_STEPPER_ALIGN_XY;
105 110
 inline void set_all_z_lock(const bool lock) {
106 111
   stepper.set_z_lock(lock);
107 112
   stepper.set_z2_lock(lock);
108
-  #if ENABLED(Z_TRIPLE_STEPPER_DRIVERS)
113
+  #if NUM_Z_STEPPER_DRIVERS >= 3
109 114
     stepper.set_z3_lock(lock);
115
+    #if NUM_Z_STEPPER_DRIVERS >= 4
116
+      stepper.set_z4_lock(lock);
117
+    #endif
110 118
   #endif
111 119
 }
112 120
 
@@ -125,6 +133,11 @@ void GcodeSuite::G34() {
125 133
 
126 134
   do { // break out on error
127 135
 
136
+    #if NUM_Z_STEPPER_DRIVERS == 4
137
+      SERIAL_ECHOLNPGM("Quad Z Stepper Leveling not Yet Supported");
138
+      break;
139
+    #endif
140
+
128 141
     const int8_t z_auto_align_iterations = parser.intval('I', Z_STEPPER_ALIGN_ITERATIONS);
129 142
     if (!WITHIN(z_auto_align_iterations, 1, 30)) {
130 143
       SERIAL_ECHOLNPGM("?(I)teration out of bounds (1-30).");
@@ -187,7 +200,7 @@ void GcodeSuite::G34() {
187 200
     // Compute a worst-case clearance height to probe from. After the first
188 201
     // iteration this will be re-calculated based on the actual bed position
189 202
     float z_probe = Z_BASIC_CLEARANCE + (G34_MAX_GRADE) * 0.01f * (
190
-      #if ENABLED(Z_TRIPLE_STEPPER_DRIVERS)
203
+      #if NUM_Z_STEPPER_DRIVERS == 3
191 204
          SQRT(_MAX(HYPOT2(z_stepper_align_pos[0].x - z_stepper_align_pos[0].y, z_stepper_align_pos[1].x - z_stepper_align_pos[1].y),
192 205
                    HYPOT2(z_stepper_align_pos[1].x - z_stepper_align_pos[1].y, z_stepper_align_pos[2].x - z_stepper_align_pos[2].y),
193 206
                    HYPOT2(z_stepper_align_pos[2].x - z_stepper_align_pos[2].y, z_stepper_align_pos[0].x - z_stepper_align_pos[0].y)))
@@ -202,7 +215,7 @@ void GcodeSuite::G34() {
202 215
     // Move the Z coordinate realm towards the positive - dirty trick
203 216
     current_position.z -= z_probe * 0.5f;
204 217
 
205
-    float last_z_align_move[Z_STEPPER_COUNT] = ARRAY_N(Z_STEPPER_COUNT, 10000.0f, 10000.0f, 10000.0f),
218
+    float last_z_align_move[NUM_Z_STEPPER_DRIVERS] = ARRAY_N(NUM_Z_STEPPER_DRIVERS, 10000.0f, 10000.0f, 10000.0f),
206 219
           z_measured[G34_PROBE_COUNT] = { 0 },
207 220
           z_maxdiff = 0.0f,
208 221
           amplification = z_auto_align_amplification;
@@ -273,7 +286,7 @@ void GcodeSuite::G34() {
273 286
         finish_incremental_LSF(&lfd);
274 287
 
275 288
         z_measured_min = 100000.0f;
276
-        for (uint8_t i = 0; i < Z_STEPPER_COUNT; ++i) {
289
+        for (uint8_t i = 0; i < NUM_Z_STEPPER_DRIVERS; ++i) {
277 290
           z_measured[i] = -(lfd.A * z_stepper_align_stepper_pos[i].x + lfd.B * z_stepper_align_stepper_pos[i].y);
278 291
           z_measured_min = _MIN(z_measured_min, z_measured[i]);
279 292
         }
@@ -283,7 +296,7 @@ void GcodeSuite::G34() {
283 296
 
284 297
       SERIAL_ECHOLNPAIR("\n"
285 298
         "DIFFERENCE Z1-Z2=", ABS(z_measured[0] - z_measured[1])
286
-        #if ENABLED(Z_TRIPLE_STEPPER_DRIVERS)
299
+        #if NUM_Z_STEPPER_DRIVERS == 3
287 300
           , " Z2-Z3=", ABS(z_measured[1] - z_measured[2])
288 301
           , " Z3-Z1=", ABS(z_measured[2] - z_measured[0])
289 302
         #endif
@@ -294,7 +307,7 @@ void GcodeSuite::G34() {
294 307
 
295 308
       bool success_break = true;
296 309
       // Correct the individual stepper offsets
297
-      for (uint8_t zstepper = 0; zstepper < Z_STEPPER_COUNT; ++zstepper) {
310
+      for (uint8_t zstepper = 0; zstepper < NUM_Z_STEPPER_DRIVERS; ++zstepper) {
298 311
         // Calculate current stepper move
299 312
         const float z_align_move = z_measured[zstepper] - z_measured_min,
300 313
                     z_align_abs = ABS(z_align_move);
@@ -324,7 +337,7 @@ void GcodeSuite::G34() {
324 337
         switch (zstepper) {
325 338
           case 0: stepper.set_z_lock(false); break;
326 339
           case 1: stepper.set_z2_lock(false); break;
327
-          #if ENABLED(Z_TRIPLE_STEPPER_DRIVERS)
340
+          #if NUM_Z_STEPPER_DRIVERS == 3
328 341
             case 2: stepper.set_z3_lock(false); break;
329 342
           #endif
330 343
         }
@@ -397,7 +410,7 @@ void GcodeSuite::M422() {
397 410
     for (uint8_t i = 0; i < G34_PROBE_COUNT; ++i)
398 411
       SERIAL_ECHOLNPAIR_P(PSTR("M422 S"), i + 1, SP_X_STR, z_stepper_align_pos[i].x, SP_Y_STR, z_stepper_align_pos[i].y);
399 412
     #if ENABLED(Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS)
400
-      for (uint8_t i = 0; i < Z_STEPPER_COUNT; ++i)
413
+      for (uint8_t i = 0; i < NUM_Z_STEPPER_DRIVERS; ++i)
401 414
         SERIAL_ECHOLNPAIR_P(PSTR("M422 W"), i + 1, SP_X_STR, z_stepper_align_stepper_pos[i].x, SP_Y_STR, z_stepper_align_stepper_pos[i].y);
402 415
     #endif
403 416
     return;
@@ -446,7 +459,7 @@ void GcodeSuite::M422() {
446 459
   else {
447 460
     #if ENABLED(Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS)
448 461
       position_index = parser.intval('W') - 1;
449
-      if (!WITHIN(position_index, 0, Z_STEPPER_COUNT - 1)) {
462
+      if (!WITHIN(position_index, 0, NUM_Z_STEPPER_DRIVERS - 1)) {
450 463
         SERIAL_ECHOLNPGM("?(W) Z-Stepper index invalid.");
451 464
         return;
452 465
       }

+ 22
- 13
Marlin/src/gcode/calibrate/M666.cpp View File

@@ -57,10 +57,11 @@
57 57
    * M666: Set Dual Endstops offsets for X, Y, and/or Z.
58 58
    *       With no parameters report current offsets.
59 59
    *
60
-   * For Triple Z Endstops:
60
+   * For Triple / Quad Z Endstops:
61 61
    *   Set Z2 Only: M666 S2 Z<offset>
62 62
    *   Set Z3 Only: M666 S3 Z<offset>
63
-   *      Set Both: M666 Z<offset>
63
+   *   Set Z4 Only: M666 S4 Z<offset>
64
+   *       Set All: M666 Z<offset>
64 65
    */
65 66
   void GcodeSuite::M666() {
66 67
     #if ENABLED(X_DUAL_ENDSTOPS)
@@ -69,15 +70,20 @@
69 70
     #if ENABLED(Y_DUAL_ENDSTOPS)
70 71
       if (parser.seenval('Y')) endstops.y2_endstop_adj = parser.value_linear_units();
71 72
     #endif
72
-    #if ENABLED(Z_TRIPLE_ENDSTOPS)
73
+    #if ENABLED(Z_MULTI_ENDSTOPS)
73 74
       if (parser.seenval('Z')) {
74
-        const float z_adj = parser.value_linear_units();
75
-        const int ind = parser.intval('S');
76
-        if (!ind || ind == 2) endstops.z2_endstop_adj = z_adj;
77
-        if (!ind || ind == 3) endstops.z3_endstop_adj = z_adj;
75
+        #if NUM_Z_STEPPER_DRIVERS >= 3
76
+          const float z_adj = parser.value_linear_units();
77
+          const int ind = parser.intval('S');
78
+          if (!ind || ind == 2) endstops.z2_endstop_adj = z_adj;
79
+          if (!ind || ind == 3) endstops.z3_endstop_adj = z_adj;
80
+          #if NUM_Z_STEPPER_DRIVERS >= 4
81
+            if (!ind || ind == 4) endstops.z4_endstop_adj = z_adj;
82
+          #endif
83
+        #else
84
+          endstops.z2_endstop_adj = parser.value_linear_units();
85
+        #endif
78 86
       }
79
-    #elif Z_MULTI_ENDSTOPS
80
-      if (parser.seen('Z')) endstops.z2_endstop_adj = parser.value_linear_units();
81 87
     #endif
82 88
     if (!parser.seen("XYZ")) {
83 89
       SERIAL_ECHOPGM("Dual Endstop Adjustment (mm): ");
@@ -87,11 +93,14 @@
87 93
       #if ENABLED(Y_DUAL_ENDSTOPS)
88 94
         SERIAL_ECHOPAIR(" Y2:", endstops.y2_endstop_adj);
89 95
       #endif
90
-      #if Z_MULTI_ENDSTOPS
96
+      #if ENABLED(Z_MULTI_ENDSTOPS)
91 97
         SERIAL_ECHOPAIR(" Z2:", endstops.z2_endstop_adj);
92
-      #endif
93
-      #if ENABLED(Z_TRIPLE_ENDSTOPS)
94
-        SERIAL_ECHOPAIR(" Z3:", endstops.z3_endstop_adj);
98
+        #if NUM_Z_STEPPER_DRIVERS >= 3
99
+          SERIAL_ECHOPAIR(" Z3:", endstops.z3_endstop_adj);
100
+          #if NUM_Z_STEPPER_DRIVERS >= 4
101
+            SERIAL_ECHOPAIR(" Z4:", endstops.z4_endstop_adj);
102
+          #endif
103
+        #endif
95 104
       #endif
96 105
       SERIAL_EOL();
97 106
     }

+ 3
- 0
Marlin/src/gcode/feature/L6470/M122.cpp View File

@@ -115,6 +115,9 @@ void GcodeSuite::M122() {
115 115
   #if AXIS_IS_L64XX(Z3)
116 116
     L6470_say_status(Z3);
117 117
   #endif
118
+  #if AXIS_IS_L64XX(Z4)
119
+    L6470_say_status(Z4);
120
+  #endif
118 121
   #if AXIS_IS_L64XX(E0)
119 122
     L6470_say_status(E0);
120 123
   #endif

+ 7
- 1
Marlin/src/gcode/feature/L6470/M906.cpp View File

@@ -44,7 +44,7 @@
44 44
  *     1 - monitor only X, Y, Z or E1
45 45
  *     2 - monitor only X2, Y2, Z2 or E2
46 46
  *     3 - monitor only Z3 or E3
47
- *     4 - monitor only E4
47
+ *     4 - monitor only Z4 or E4
48 48
  *     5 - monitor only E5
49 49
  * Xxxx, Yxxx, Zxxx, Exxx - axis to change (optional)
50 50
  *     L6474 - current in mA (4A max)
@@ -274,6 +274,9 @@ void GcodeSuite::M906() {
274 274
         #if AXIS_IS_L64XX(Z3)
275 275
           if (index == 2) L6470_SET_KVAL_HOLD(Z3);
276 276
         #endif
277
+        #if AXIS_DRIVER_TYPE_Z4(L6470)
278
+          if (index == 3) L6470_SET_KVAL_HOLD(Z4);
279
+        #endif
277 280
         break;
278 281
       case E_AXIS: {
279 282
         const int8_t target_extruder = get_target_extruder_from_command();
@@ -328,6 +331,9 @@ void GcodeSuite::M906() {
328 331
     #if AXIS_IS_L64XX(Z3)
329 332
       L64XX_REPORT_CURRENT(Z3);
330 333
     #endif
334
+    #if AXIS_IS_L64XX(Z4)
335
+      L64XX_REPORT_CURRENT(Z4);
336
+    #endif
331 337
     #if AXIS_IS_L64XX(E0)
332 338
       L64XX_REPORT_CURRENT(E0);
333 339
     #endif

+ 1
- 0
Marlin/src/gcode/feature/L6470/M916-918.cpp View File

@@ -46,6 +46,7 @@
46 46
  *     1 - monitor only X, Y, Z, E1
47 47
  *     2 - monitor only X2, Y2, Z2, E2
48 48
  *     3 - monitor only Z3, E3
49
+ *     4 - monitor only Z4, E4
49 50
  *
50 51
  * Xxxx, Yxxx, Zxxx, Exxx - axis to be monitored with displacement
51 52
  *     xxx (1-255) is distance moved on either side of current position

+ 10
- 3
Marlin/src/gcode/feature/trinamic/M569.cpp View File

@@ -44,9 +44,10 @@ void tmc_set_stealthChop(TMC &st, const bool enable) {
44 44
 static void set_stealth_status(const bool enable, const int8_t target_extruder) {
45 45
   #define TMC_SET_STEALTH(Q) tmc_set_stealthChop(stepper##Q, enable)
46 46
 
47
-  #if    AXIS_HAS_STEALTHCHOP(X) || AXIS_HAS_STEALTHCHOP(X2) \
48
-      || AXIS_HAS_STEALTHCHOP(Y) || AXIS_HAS_STEALTHCHOP(Y2) \
49
-      || AXIS_HAS_STEALTHCHOP(Z) || AXIS_HAS_STEALTHCHOP(Z2) || AXIS_HAS_STEALTHCHOP(Z3)
47
+  #if    AXIS_HAS_STEALTHCHOP(X)  || AXIS_HAS_STEALTHCHOP(X2) \
48
+      || AXIS_HAS_STEALTHCHOP(Y)  || AXIS_HAS_STEALTHCHOP(Y2) \
49
+      || AXIS_HAS_STEALTHCHOP(Z)  || AXIS_HAS_STEALTHCHOP(Z2) \
50
+      || AXIS_HAS_STEALTHCHOP(Z3) || AXIS_HAS_STEALTHCHOP(Z4)
50 51
     const uint8_t index = parser.byteval('I');
51 52
   #endif
52 53
 
@@ -78,6 +79,9 @@ static void set_stealth_status(const bool enable, const int8_t target_extruder)
78 79
         #if AXIS_HAS_STEALTHCHOP(Z3)
79 80
           if (index == 2) TMC_SET_STEALTH(Z3);
80 81
         #endif
82
+        #if AXIS_HAS_STEALTHCHOP(Z4)
83
+          if (index == 3) TMC_SET_STEALTH(Z4);
84
+        #endif
81 85
         break;
82 86
       case E_AXIS: {
83 87
         if (target_extruder < 0) return;
@@ -130,6 +134,9 @@ static void say_stealth_status() {
130 134
   #if AXIS_HAS_STEALTHCHOP(Z3)
131 135
     TMC_SAY_STEALTH_STATUS(Z3);
132 136
   #endif
137
+  #if AXIS_HAS_STEALTHCHOP(Z4)
138
+    TMC_SAY_STEALTH_STATUS(Z4);
139
+  #endif
133 140
   #if AXIS_HAS_STEALTHCHOP(E0)
134 141
     TMC_SAY_STEALTH_STATUS(E0);
135 142
   #endif

+ 8
- 2
Marlin/src/gcode/feature/trinamic/M906.cpp View File

@@ -37,7 +37,7 @@
37 37
  *   Z[current]  - Set mA current for Z driver(s)
38 38
  *   E[current]  - Set mA current for E driver(s)
39 39
  *
40
- *   I[index]    - Axis sub-index (Omit or 0 for X, Y, Z; 1 for X2, Y2, Z2; 2 for Z3.)
40
+ *   I[index]    - Axis sub-index (Omit or 0 for X, Y, Z; 1 for X2, Y2, Z2; 2 for Z3; 3 for Z4.)
41 41
  *   T[index]    - Extruder index (Zero-based. Omit for E0 only.)
42 42
  *
43 43
  * With no parameters report driver currents.
@@ -48,7 +48,7 @@ void GcodeSuite::M906() {
48 48
 
49 49
   bool report = true;
50 50
 
51
-  #if AXIS_IS_TMC(X) || AXIS_IS_TMC(X2) || AXIS_IS_TMC(Y) || AXIS_IS_TMC(Y2) || AXIS_IS_TMC(Z) || AXIS_IS_TMC(Z2) || AXIS_IS_TMC(Z3)
51
+  #if AXIS_IS_TMC(X) || AXIS_IS_TMC(X2) || AXIS_IS_TMC(Y) || AXIS_IS_TMC(Y2) || AXIS_IS_TMC(Z) || AXIS_IS_TMC(Z2) || AXIS_IS_TMC(Z3) || AXIS_IS_TMC(Z4)
52 52
     const uint8_t index = parser.byteval('I');
53 53
   #endif
54 54
 
@@ -81,6 +81,9 @@ void GcodeSuite::M906() {
81 81
         #if AXIS_IS_TMC(Z3)
82 82
           if (index == 2) TMC_SET_CURRENT(Z3);
83 83
         #endif
84
+        #if AXIS_IS_TMC(Z4)
85
+          if (index == 3) TMC_SET_CURRENT(Z4);
86
+        #endif
84 87
         break;
85 88
       case E_AXIS: {
86 89
         const int8_t target_extruder = get_target_extruder_from_command();
@@ -131,6 +134,9 @@ void GcodeSuite::M906() {
131 134
     #if AXIS_IS_TMC(Z3)
132 135
       TMC_SAY_CURRENT(Z3);
133 136
     #endif
137
+    #if AXIS_IS_TMC(Z4)
138
+      TMC_SAY_CURRENT(Z4);
139
+    #endif
134 140
     #if AXIS_IS_TMC(E0)
135 141
       TMC_SAY_CURRENT(E0);
136 142
     #endif

+ 21
- 3
Marlin/src/gcode/feature/trinamic/M911-M914.cpp View File

@@ -37,7 +37,7 @@
37 37
 
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
-  #define M91x_SOME_Z (M91x_USE(Z) || M91x_USE(Z2) || M91x_USE(Z3))
40
+  #define M91x_SOME_Z (M91x_USE(Z) || M91x_USE(Z2) || M91x_USE(Z3) || M91x_USE(Z4))
41 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))
42 42
 
43 43
   #if !M91x_SOME_X && !M91x_SOME_Y && !M91x_SOME_Z && !M91x_SOME_E
@@ -70,6 +70,9 @@
70 70
     #if M91x_USE(Z3)
71 71
       tmc_report_otpw(stepperZ3);
72 72
     #endif
73
+    #if M91x_USE(Z4)
74
+      tmc_report_otpw(stepperZ4);
75
+    #endif
73 76
     #if M91x_USE_E(0)
74 77
       tmc_report_otpw(stepperE0);
75 78
     #endif
@@ -92,7 +95,7 @@
92 95
 
93 96
   /**
94 97
    * M912: Clear TMC stepper driver overtemperature pre-warn flag held by the library
95
-   *       Specify one or more axes with X, Y, Z, X1, Y1, Z1, X2, Y2, Z2, Z3 and E[index].
98
+   *       Specify one or more axes with X, Y, Z, X1, Y1, Z1, X2, Y2, Z2, Z3, Z4 and E[index].
96 99
    *       If no axes are given, clear all.
97 100
    *
98 101
    * Examples:
@@ -160,6 +163,9 @@
160 163
       #if M91x_USE(Z3)
161 164
         if (hasNone || zval == 3 || (hasZ && zval < 0)) tmc_clear_otpw(stepperZ3);
162 165
       #endif
166
+      #if M91x_USE(Z4)
167
+        if (hasNone || zval == 4 || (hasZ && zval < 0)) tmc_clear_otpw(stepperZ4);
168
+      #endif
163 169
     #endif
164 170
 
165 171
     #if M91x_SOME_E
@@ -198,7 +204,7 @@
198 204
     #define TMC_SET_PWMTHRS_E(E) stepperE##E.set_pwm_thrs(value)
199 205
 
200 206
     bool report = true;
201
-    #if AXIS_IS_TMC(X) || AXIS_IS_TMC(X2) || AXIS_IS_TMC(Y) || AXIS_IS_TMC(Y2) || AXIS_IS_TMC(Z) || AXIS_IS_TMC(Z2) || AXIS_IS_TMC(Z3)
207
+    #if AXIS_IS_TMC(X) || AXIS_IS_TMC(X2) || AXIS_IS_TMC(Y) || AXIS_IS_TMC(Y2) || AXIS_IS_TMC(Z) || AXIS_IS_TMC(Z2) || AXIS_IS_TMC(Z3) || AXIS_IS_TMC(Z4)
202 208
       const uint8_t index = parser.byteval('I');
203 209
     #endif
204 210
     LOOP_XYZE(i) if (int32_t value = parser.longval(axis_codes[i])) {
@@ -230,6 +236,9 @@
230 236
           #if AXIS_HAS_STEALTHCHOP(Z3)
231 237
             if (index == 0 || index == 3) TMC_SET_PWMTHRS(Z,Z3);
232 238
           #endif
239
+          #if AXIS_HAS_STEALTHCHOP(Z4)
240
+            if (index == 0 || index == 4) TMC_SET_PWMTHRS(Z,Z4);
241
+          #endif
233 242
           break;
234 243
         case E_AXIS: {
235 244
           #if E_STEPPERS
@@ -282,6 +291,9 @@
282 291
       #if AXIS_HAS_STEALTHCHOP(Z3)
283 292
         TMC_SAY_PWMTHRS(Z,Z3);
284 293
       #endif
294
+      #if AXIS_HAS_STEALTHCHOP(Z4)
295
+        TMC_SAY_PWMTHRS(Z,Z4);
296
+      #endif
285 297
       #if E_STEPPERS && AXIS_HAS_STEALTHCHOP(E0)
286 298
         TMC_SAY_PWMTHRS_E(0);
287 299
       #endif
@@ -347,6 +359,9 @@
347 359
             #if AXIS_HAS_STALLGUARD(Z3)
348 360
               if (index == 0 || index == 3) stepperZ3.homing_threshold(value);
349 361
             #endif
362
+            #if AXIS_HAS_STALLGUARD(Z4)
363
+              if (index == 0 || index == 4) stepperZ4.homing_threshold(value);
364
+            #endif
350 365
             break;
351 366
         #endif
352 367
       }
@@ -379,6 +394,9 @@
379 394
         #if AXIS_HAS_STALLGUARD(Z3)
380 395
           tmc_print_sgt(stepperZ3);
381 396
         #endif
397
+        #if AXIS_HAS_STALLGUARD(Z4)
398
+          tmc_print_sgt(stepperZ4);
399
+        #endif
382 400
       #endif
383 401
     }
384 402
   }

+ 2
- 2
Marlin/src/gcode/gcode.cpp View File

@@ -566,8 +566,8 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) {
566 566
         case 665: M665(); break;                                  // M665: Set delta configurations
567 567
       #endif
568 568
 
569
-      #if ANY(DELTA, X_DUAL_ENDSTOPS, Y_DUAL_ENDSTOPS, Z_DUAL_ENDSTOPS)
570
-        case 666: M666(); break;                                  // M666: Set delta or dual endstop adjustment
569
+      #if ENABLED(DELTA) || HAS_EXTRA_ENDSTOPS
570
+        case 666: M666(); break;                                  // M666: Set delta or multiple endstop adjustment
571 571
       #endif
572 572
 
573 573
       #if ENABLED(FWRETRACT)

+ 3
- 0
Marlin/src/gcode/host/M114.cpp View File

@@ -121,6 +121,9 @@
121 121
       #if AXIS_IS_L64XX(Z3)
122 122
         REPORT_ABSOLUTE_POS(Z3);
123 123
       #endif
124
+      #if AXIS_IS_L64XX(Z4)
125
+        REPORT_ABSOLUTE_POS(Z4);
126
+      #endif
124 127
       #if AXIS_IS_L64XX(E0)
125 128
         REPORT_ABSOLUTE_POS(E0);
126 129
       #endif

+ 1
- 4
Marlin/src/inc/Conditionals_LCD.h View File

@@ -526,6 +526,7 @@
526 526
   #define GRID_MAX_POINTS ((GRID_MAX_POINTS_X) * (GRID_MAX_POINTS_Y))
527 527
 #endif
528 528
 
529
+#define HAS_EXTRA_ENDSTOPS           ANY(X_DUAL_ENDSTOPS, Y_DUAL_ENDSTOPS, Z_MULTI_ENDSTOPS)
529 530
 #define HAS_SOFTWARE_ENDSTOPS        EITHER(MIN_SOFTWARE_ENDSTOPS, MAX_SOFTWARE_ENDSTOPS)
530 531
 #define HAS_RESUME_CONTINUE          ANY(EXTENSIBLE_UI, NEWPANEL, EMERGENCY_PARSER)
531 532
 #define HAS_COLOR_LEDS               ANY(BLINKM, RGB_LED, RGBW_LED, PCA9632, PCA9533, NEOPIXEL_LED)
@@ -535,10 +536,6 @@
535 536
 #define HAS_SERVICE_INTERVALS        (ENABLED(PRINTCOUNTER) && (SERVICE_INTERVAL_1 > 0 || SERVICE_INTERVAL_2 > 0 || SERVICE_INTERVAL_3 > 0))
536 537
 #define HAS_FILAMENT_SENSOR          ENABLED(FILAMENT_RUNOUT_SENSOR)
537 538
 
538
-#define Z_MULTI_STEPPER_DRIVERS EITHER(Z_DUAL_STEPPER_DRIVERS, Z_TRIPLE_STEPPER_DRIVERS)
539
-#define Z_MULTI_ENDSTOPS        EITHER(Z_DUAL_ENDSTOPS, Z_TRIPLE_ENDSTOPS)
540
-#define HAS_EXTRA_ENDSTOPS     (EITHER(X_DUAL_ENDSTOPS, Y_DUAL_ENDSTOPS) || Z_MULTI_ENDSTOPS)
541
-
542 539
 #define HAS_GAMES     ANY(MARLIN_BRICKOUT, MARLIN_INVADERS, MARLIN_SNAKE, MARLIN_MAZE)
543 540
 #define HAS_GAME_MENU (1 < ENABLED(MARLIN_BRICKOUT) + ENABLED(MARLIN_INVADERS) + ENABLED(MARLIN_SNAKE) + ENABLED(MARLIN_MAZE))
544 541
 

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

@@ -54,6 +54,11 @@
54 54
   #undef SHOW_TEMP_ADC_VALUES
55 55
 #endif
56 56
 
57
+// Multiple Z steppers
58
+#ifndef NUM_Z_STEPPER_DRIVERS
59
+  #define NUM_Z_STEPPER_DRIVERS 1
60
+#endif
61
+
57 62
 #define HAS_CUTTER EITHER(SPINDLE_FEATURE, LASER_FEATURE)
58 63
 
59 64
 #if !defined(__AVR__) || !defined(USBCON)

+ 118
- 71
Marlin/src/inc/Conditionals_post.h View File

@@ -687,9 +687,6 @@
687 687
   #endif
688 688
 #endif
689 689
 
690
-// Is an endstop plug used for the X2 endstop?
691
-#define IS_X2_ENDSTOP(A,M) (ENABLED(X_DUAL_ENDSTOPS) && X2_USE_ENDSTOP == _##A##M##_)
692
-
693 690
 /**
694 691
  * Y_DUAL_ENDSTOPS endstop reassignment
695 692
  */
@@ -743,13 +740,11 @@
743 740
   #endif
744 741
 #endif
745 742
 
746
-// Is an endstop plug used for the Y2 endstop or the bed probe?
747
-#define IS_Y2_ENDSTOP(A,M) (ENABLED(Y_DUAL_ENDSTOPS) && Y2_USE_ENDSTOP == _##A##M##_)
748
-
749 743
 /**
750
- * Z_DUAL_ENDSTOPS endstop reassignment
744
+ * Z_MULTI_ENDSTOPS endstop reassignment
751 745
  */
752
-#if Z_MULTI_ENDSTOPS
746
+#if ENABLED(Z_MULTI_ENDSTOPS)
747
+
753 748
   #if Z_HOME_DIR > 0
754 749
     #if Z2_USE_ENDSTOP == _XMIN_
755 750
       #define Z2_MAX_ENDSTOP_INVERTING X_MIN_ENDSTOP_INVERTING
@@ -797,67 +792,108 @@
797 792
     #endif
798 793
     #define Z2_MAX_ENDSTOP_INVERTING false
799 794
   #endif
800
-#endif
801 795
 
802
-#if ENABLED(Z_TRIPLE_ENDSTOPS)
803
-  #if Z_HOME_DIR > 0
804
-    #if Z3_USE_ENDSTOP == _XMIN_
805
-      #define Z3_MAX_ENDSTOP_INVERTING X_MIN_ENDSTOP_INVERTING
806
-      #define Z3_MAX_PIN X_MIN_PIN
807
-    #elif Z3_USE_ENDSTOP == _XMAX_
808
-      #define Z3_MAX_ENDSTOP_INVERTING X_MAX_ENDSTOP_INVERTING
809
-      #define Z3_MAX_PIN X_MAX_PIN
810
-    #elif Z3_USE_ENDSTOP == _YMIN_
811
-      #define Z3_MAX_ENDSTOP_INVERTING Y_MIN_ENDSTOP_INVERTING
812
-      #define Z3_MAX_PIN Y_MIN_PIN
813
-    #elif Z3_USE_ENDSTOP == _YMAX_
814
-      #define Z3_MAX_ENDSTOP_INVERTING Y_MAX_ENDSTOP_INVERTING
815
-      #define Z3_MAX_PIN Y_MAX_PIN
816
-    #elif Z3_USE_ENDSTOP == _ZMIN_
817
-      #define Z3_MAX_ENDSTOP_INVERTING Z_MIN_ENDSTOP_INVERTING
818
-      #define Z3_MAX_PIN Z_MIN_PIN
819
-    #elif Z3_USE_ENDSTOP == _ZMAX_
820
-      #define Z3_MAX_ENDSTOP_INVERTING Z_MAX_ENDSTOP_INVERTING
821
-      #define Z3_MAX_PIN Z_MAX_PIN
796
+  #if NUM_Z_STEPPER_DRIVERS >= 3
797
+    #if Z_HOME_DIR > 0
798
+      #if Z3_USE_ENDSTOP == _XMIN_
799
+        #define Z3_MAX_ENDSTOP_INVERTING X_MIN_ENDSTOP_INVERTING
800
+        #define Z3_MAX_PIN X_MIN_PIN
801
+      #elif Z3_USE_ENDSTOP == _XMAX_
802
+        #define Z3_MAX_ENDSTOP_INVERTING X_MAX_ENDSTOP_INVERTING
803
+        #define Z3_MAX_PIN X_MAX_PIN
804
+      #elif Z3_USE_ENDSTOP == _YMIN_
805
+        #define Z3_MAX_ENDSTOP_INVERTING Y_MIN_ENDSTOP_INVERTING
806
+        #define Z3_MAX_PIN Y_MIN_PIN
807
+      #elif Z3_USE_ENDSTOP == _YMAX_
808
+        #define Z3_MAX_ENDSTOP_INVERTING Y_MAX_ENDSTOP_INVERTING
809
+        #define Z3_MAX_PIN Y_MAX_PIN
810
+      #elif Z3_USE_ENDSTOP == _ZMIN_
811
+        #define Z3_MAX_ENDSTOP_INVERTING Z_MIN_ENDSTOP_INVERTING
812
+        #define Z3_MAX_PIN Z_MIN_PIN
813
+      #elif Z3_USE_ENDSTOP == _ZMAX_
814
+        #define Z3_MAX_ENDSTOP_INVERTING Z_MAX_ENDSTOP_INVERTING
815
+        #define Z3_MAX_PIN Z_MAX_PIN
816
+      #else
817
+        #define Z3_MAX_ENDSTOP_INVERTING false
818
+      #endif
819
+      #define Z3_MIN_ENDSTOP_INVERTING false
822 820
     #else
821
+      #if Z3_USE_ENDSTOP == _XMIN_
822
+        #define Z3_MIN_ENDSTOP_INVERTING X_MIN_ENDSTOP_INVERTING
823
+        #define Z3_MIN_PIN X_MIN_PIN
824
+      #elif Z3_USE_ENDSTOP == _XMAX_
825
+        #define Z3_MIN_ENDSTOP_INVERTING X_MAX_ENDSTOP_INVERTING
826
+        #define Z3_MIN_PIN X_MAX_PIN
827
+      #elif Z3_USE_ENDSTOP == _YMIN_
828
+        #define Z3_MIN_ENDSTOP_INVERTING Y_MIN_ENDSTOP_INVERTING
829
+        #define Z3_MIN_PIN Y_MIN_PIN
830
+      #elif Z3_USE_ENDSTOP == _YMAX_
831
+        #define Z3_MIN_ENDSTOP_INVERTING Y_MAX_ENDSTOP_INVERTING
832
+        #define Z3_MIN_PIN Y_MAX_PIN
833
+      #elif Z3_USE_ENDSTOP == _ZMIN_
834
+        #define Z3_MIN_ENDSTOP_INVERTING Z_MIN_ENDSTOP_INVERTING
835
+        #define Z3_MIN_PIN Z_MIN_PIN
836
+      #elif Z3_USE_ENDSTOP == _ZMAX_
837
+        #define Z3_MIN_ENDSTOP_INVERTING Z_MAX_ENDSTOP_INVERTING
838
+        #define Z3_MIN_PIN Z_MAX_PIN
839
+      #else
840
+        #define Z3_MIN_ENDSTOP_INVERTING false
841
+      #endif
823 842
       #define Z3_MAX_ENDSTOP_INVERTING false
824 843
     #endif
825
-    #define Z3_MIN_ENDSTOP_INVERTING false
826
-  #else
827
-    #if Z3_USE_ENDSTOP == _XMIN_
828
-      #define Z3_MIN_ENDSTOP_INVERTING X_MIN_ENDSTOP_INVERTING
829
-      #define Z3_MIN_PIN X_MIN_PIN
830
-    #elif Z3_USE_ENDSTOP == _XMAX_
831
-      #define Z3_MIN_ENDSTOP_INVERTING X_MAX_ENDSTOP_INVERTING
832
-      #define Z3_MIN_PIN X_MAX_PIN
833
-    #elif Z3_USE_ENDSTOP == _YMIN_
834
-      #define Z3_MIN_ENDSTOP_INVERTING Y_MIN_ENDSTOP_INVERTING
835
-      #define Z3_MIN_PIN Y_MIN_PIN
836
-    #elif Z3_USE_ENDSTOP == _YMAX_
837
-      #define Z3_MIN_ENDSTOP_INVERTING Y_MAX_ENDSTOP_INVERTING
838
-      #define Z3_MIN_PIN Y_MAX_PIN
839
-    #elif Z3_USE_ENDSTOP == _ZMIN_
840
-      #define Z3_MIN_ENDSTOP_INVERTING Z_MIN_ENDSTOP_INVERTING
841
-      #define Z3_MIN_PIN Z_MIN_PIN
842
-    #elif Z3_USE_ENDSTOP == _ZMAX_
843
-      #define Z3_MIN_ENDSTOP_INVERTING Z_MAX_ENDSTOP_INVERTING
844
-      #define Z3_MIN_PIN Z_MAX_PIN
844
+  #endif
845
+
846
+  #if NUM_Z_STEPPER_DRIVERS >= 4
847
+    #if Z_HOME_DIR > 0
848
+      #if Z4_USE_ENDSTOP == _XMIN_
849
+        #define Z4_MAX_ENDSTOP_INVERTING X_MIN_ENDSTOP_INVERTING
850
+        #define Z4_MAX_PIN X_MIN_PIN
851
+      #elif Z4_USE_ENDSTOP == _XMAX_
852
+        #define Z4_MAX_ENDSTOP_INVERTING X_MAX_ENDSTOP_INVERTING
853
+        #define Z4_MAX_PIN X_MAX_PIN
854
+      #elif Z4_USE_ENDSTOP == _YMIN_
855
+        #define Z4_MAX_ENDSTOP_INVERTING Y_MIN_ENDSTOP_INVERTING
856
+        #define Z4_MAX_PIN Y_MIN_PIN
857
+      #elif Z4_USE_ENDSTOP == _YMAX_
858
+        #define Z4_MAX_ENDSTOP_INVERTING Y_MAX_ENDSTOP_INVERTING
859
+        #define Z4_MAX_PIN Y_MAX_PIN
860
+      #elif Z4_USE_ENDSTOP == _ZMIN_
861
+        #define Z4_MAX_ENDSTOP_INVERTING Z_MIN_ENDSTOP_INVERTING
862
+        #define Z4_MAX_PIN Z_MIN_PIN
863
+      #elif Z4_USE_ENDSTOP == _ZMAX_
864
+        #define Z4_MAX_ENDSTOP_INVERTING Z_MAX_ENDSTOP_INVERTING
865
+        #define Z4_MAX_PIN Z_MAX_PIN
866
+      #else
867
+        #define Z4_MAX_ENDSTOP_INVERTING false
868
+      #endif
869
+      #define Z4_MIN_ENDSTOP_INVERTING false
845 870
     #else
846
-      #define Z3_MIN_ENDSTOP_INVERTING false
871
+      #if Z4_USE_ENDSTOP == _XMIN_
872
+        #define Z4_MIN_ENDSTOP_INVERTING X_MIN_ENDSTOP_INVERTING
873
+        #define Z4_MIN_PIN X_MIN_PIN
874
+      #elif Z4_USE_ENDSTOP == _XMAX_
875
+        #define Z4_MIN_ENDSTOP_INVERTING X_MAX_ENDSTOP_INVERTING
876
+        #define Z4_MIN_PIN X_MAX_PIN
877
+      #elif Z4_USE_ENDSTOP == _YMIN_
878
+        #define Z4_MIN_ENDSTOP_INVERTING Y_MIN_ENDSTOP_INVERTING
879
+        #define Z4_MIN_PIN Y_MIN_PIN
880
+      #elif Z4_USE_ENDSTOP == _YMAX_
881
+        #define Z4_MIN_ENDSTOP_INVERTING Y_MAX_ENDSTOP_INVERTING
882
+        #define Z4_MIN_PIN Y_MAX_PIN
883
+      #elif Z4_USE_ENDSTOP == _ZMIN_
884
+        #define Z4_MIN_ENDSTOP_INVERTING Z_MIN_ENDSTOP_INVERTING
885
+        #define Z4_MIN_PIN Z_MIN_PIN
886
+      #elif Z4_USE_ENDSTOP == _ZMAX_
887
+        #define Z4_MIN_ENDSTOP_INVERTING Z_MAX_ENDSTOP_INVERTING
888
+        #define Z4_MIN_PIN Z_MAX_PIN
889
+      #else
890
+        #define Z4_MIN_ENDSTOP_INVERTING false
891
+      #endif
892
+      #define Z4_MAX_ENDSTOP_INVERTING false
847 893
     #endif
848
-    #define Z3_MAX_ENDSTOP_INVERTING false
849 894
   #endif
850
-#endif
851
-
852
-// Is an endstop plug used for the Z2 endstop or the bed probe?
853
-#define IS_Z2_OR_PROBE(A,M) ( \
854
-     (Z_MULTI_ENDSTOPS && Z2_USE_ENDSTOP == _##A##M##_) \
855
-  || (HAS_CUSTOM_PROBE_PIN && Z_MIN_PROBE_PIN == A##_##M##_PIN ) )
856 895
 
857
-// Is an endstop plug used for the Z3 endstop or the bed probe?
858
-#define IS_Z3_OR_PROBE(A,M) ( \
859
-     (ENABLED(Z_TRIPLE_ENDSTOPS) && Z3_USE_ENDSTOP == _##A##M##_) \
860
-  || (HAS_CUSTOM_PROBE_PIN && Z_MIN_PROBE_PIN == A##_##M##_PIN ) )
896
+#endif // Z_MULTI_ENDSTOPS
861 897
 
862 898
 /**
863 899
  * Set ENDSTOPPULLUPS for active endstop switches
@@ -947,6 +983,11 @@
947 983
 #define HAS_Z3_STEP       (PIN_EXISTS(Z3_STEP))
948 984
 #define HAS_Z3_MICROSTEPS (PIN_EXISTS(Z3_MS1))
949 985
 
986
+#define HAS_Z4_ENABLE     (PIN_EXISTS(Z4_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Z4)))
987
+#define HAS_Z4_DIR        (PIN_EXISTS(Z4_DIR))
988
+#define HAS_Z4_STEP       (PIN_EXISTS(Z4_STEP))
989
+#define HAS_Z4_MICROSTEPS (PIN_EXISTS(Z4_MS1))
990
+
950 991
 // Extruder steppers and solenoids
951 992
 #define HAS_E0_ENABLE     (PIN_EXISTS(E0_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E0)))
952 993
 #define HAS_E0_DIR        (PIN_EXISTS(E0_DIR))
@@ -999,6 +1040,7 @@
999 1040
   #define Z_SENSORLESS  (AXIS_HAS_STALLGUARD(Z)  && defined(Z_STALL_SENSITIVITY))
1000 1041
   #define Z2_SENSORLESS (AXIS_HAS_STALLGUARD(Z2) && defined(Z2_STALL_SENSITIVITY))
1001 1042
   #define Z3_SENSORLESS (AXIS_HAS_STALLGUARD(Z3) && defined(Z3_STALL_SENSITIVITY))
1043
+  #define Z4_SENSORLESS (AXIS_HAS_STALLGUARD(Z4) && defined(Z4_STALL_SENSITIVITY))
1002 1044
   #if ENABLED(SPI_ENDSTOPS)
1003 1045
     #define X_SPI_SENSORLESS X_SENSORLESS
1004 1046
     #define Y_SPI_SENSORLESS Y_SENSORLESS
@@ -1011,8 +1053,19 @@
1011 1053
     && E0_ENABLE_PIN != Y_ENABLE_PIN && E1_ENABLE_PIN != Y_ENABLE_PIN ) \
1012 1054
 )
1013 1055
 
1056
+//
1014 1057
 // Endstops and bed probe
1015
-#define _HAS_STOP(A,M) (PIN_EXISTS(A##_##M) && !IS_X2_ENDSTOP(A,M) && !IS_Y2_ENDSTOP(A,M) && !IS_Z2_OR_PROBE(A,M))
1058
+//
1059
+
1060
+// Is an endstop plug used for extra Z endstops or the probe?
1061
+#define IS_PROBE_PIN(A,M) (HAS_CUSTOM_PROBE_PIN && Z_MIN_PROBE_PIN == P)
1062
+#define IS_X2_ENDSTOP(A,M) (ENABLED(X_DUAL_ENDSTOPS) && X2_USE_ENDSTOP == _##A##M##_)
1063
+#define IS_Y2_ENDSTOP(A,M) (ENABLED(Y_DUAL_ENDSTOPS) && Y2_USE_ENDSTOP == _##A##M##_)
1064
+#define IS_Z2_ENDSTOP(A,M) (ENABLED(Z_MULTI_ENDSTOPS) && Z2_USE_ENDSTOP == _##A##M##_)
1065
+#define IS_Z3_ENDSTOP(A,M) (ENABLED(Z_MULTI_ENDSTOPS) && NUM_Z_STEPPER_DRIVERS >= 3 && Z3_USE_ENDSTOP == _##A##M##_)
1066
+#define IS_Z4_ENDSTOP(A,M) (ENABLED(Z_MULTI_ENDSTOPS) && NUM_Z_STEPPER_DRIVERS >= 4 && Z4_USE_ENDSTOP == _##A##M##_)
1067
+
1068
+#define _HAS_STOP(A,M) (PIN_EXISTS(A##_##M) && !IS_PROBE_PIN(A,M) && !IS_X2_ENDSTOP(A,M) && !IS_Y2_ENDSTOP(A,M) && !IS_Z2_ENDSTOP(A,M) && !IS_Z3_ENDSTOP(A,M) && !IS_Z4_ENDSTOP(A,M))
1016 1069
 #define HAS_X_MIN _HAS_STOP(X,MIN)
1017 1070
 #define HAS_X_MAX _HAS_STOP(X,MAX)
1018 1071
 #define HAS_Y_MIN _HAS_STOP(Y,MIN)
@@ -1027,6 +1080,8 @@
1027 1080
 #define HAS_Z2_MAX (PIN_EXISTS(Z2_MAX))
1028 1081
 #define HAS_Z3_MIN (PIN_EXISTS(Z3_MIN))
1029 1082
 #define HAS_Z3_MAX (PIN_EXISTS(Z3_MAX))
1083
+#define HAS_Z4_MIN (PIN_EXISTS(Z4_MIN))
1084
+#define HAS_Z4_MAX (PIN_EXISTS(Z4_MAX))
1030 1085
 #define HAS_Z_MIN_PROBE_PIN (HAS_CUSTOM_PROBE_PIN && PIN_EXISTS(Z_MIN_PROBE))
1031 1086
 #define HAS_CALIBRATION_PIN (PIN_EXISTS(CALIBRATION))
1032 1087
 
@@ -1147,7 +1202,7 @@
1147 1202
 #define HAS_DIGIPOTSS         (PIN_EXISTS(DIGIPOTSS))
1148 1203
 #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)
1149 1204
 
1150
-#define HAS_SOME_Z_MICROSTEPS (HAS_Z_MICROSTEPS || HAS_Z2_MICROSTEPS || HAS_Z3_MICROSTEPS)
1205
+#define HAS_SOME_Z_MICROSTEPS (HAS_Z_MICROSTEPS || HAS_Z2_MICROSTEPS || HAS_Z3_MICROSTEPS || HAS_Z4_MICROSTEPS)
1151 1206
 #define HAS_SOME_E_MICROSTEPS (HAS_E0_MICROSTEPS || HAS_E1_MICROSTEPS || HAS_E2_MICROSTEPS || HAS_E3_MICROSTEPS || HAS_E4_MICROSTEPS || HAS_E5_MICROSTEPS)
1152 1207
 #define HAS_MICROSTEPS (HAS_X_MICROSTEPS || HAS_X2_MICROSTEPS || HAS_Y_MICROSTEPS || HAS_Y2_MICROSTEPS || HAS_SOME_Z_MICROSTEPS || HAS_SOME_E_MICROSTEPS)
1153 1208
 
@@ -1753,14 +1808,6 @@
1753 1808
 // If platform requires early initialization of watchdog to properly boot
1754 1809
 #define EARLY_WATCHDOG (ENABLED(USE_WATCHDOG) && defined(ARDUINO_ARCH_SAM))
1755 1810
 
1756
-#if ENABLED(Z_TRIPLE_STEPPER_DRIVERS)
1757
-  #define Z_STEPPER_COUNT 3
1758
-#elif ENABLED(Z_DUAL_STEPPER_DRIVERS)
1759
-  #define Z_STEPPER_COUNT 2
1760
-#else
1761
-  #define Z_STEPPER_COUNT 1
1762
-#endif
1763
-
1764 1811
 #if HAS_SPI_LCD
1765 1812
   // Get LCD character width/height, which may be overridden by pins, configs, etc.
1766 1813
   #ifndef LCD_WIDTH

+ 90
- 62
Marlin/src/inc/SanityCheck.h View File

@@ -426,6 +426,28 @@
426 426
   #error "HOME_USING_SPREADCYCLE is now obsolete. Please remove it from Configuration_adv.h."
427 427
 #elif defined(DGUS_LCD)
428 428
   #error "DGUS_LCD is now DGUS_LCD_UI_(ORIGIN|FYSETC|HIPRECY). Please update your configuration."
429
+#elif defined(X_DUAL_ENDSTOPS_ADJUSTMENT)
430
+  #error "X_DUAL_ENDSTOPS_ADJUSTMENT is now X2_ENDSTOP_ADJUSTMENT. Please update Configuration_adv.h."
431
+#elif defined(Y_DUAL_ENDSTOPS_ADJUSTMENT)
432
+  #error "Y_DUAL_ENDSTOPS_ADJUSTMENT is now Y2_ENDSTOP_ADJUSTMENT. Please update Configuration_adv.h."
433
+#elif defined(Z_DUAL_ENDSTOPS_ADJUSTMENT)
434
+  #error "Z_DUAL_ENDSTOPS_ADJUSTMENT is now Z2_ENDSTOP_ADJUSTMENT. Please update Configuration_adv.h."
435
+#elif defined(Z_TRIPLE_ENDSTOPS_ADJUSTMENT2) || defined(Z_TRIPLE_ENDSTOPS_ADJUSTMENT3)
436
+  #error "Z_TRIPLE_ENDSTOPS_ADJUSTMENT[23] is now Z[23]_ENDSTOP_ADJUSTMENT. Please update Configuration_adv.h."
437
+#elif defined(Z_QUAD_ENDSTOPS_ADJUSTMENT2) || defined(Z_QUAD_ENDSTOPS_ADJUSTMENT3) || defined(Z_QUAD_ENDSTOPS_ADJUSTMENT4)
438
+  #error "Z_QUAD_ENDSTOPS_ADJUSTMENT[234] is now Z[234]_ENDSTOP_ADJUSTMENT. Please update Configuration_adv.h."
439
+#elif defined(Z_DUAL_STEPPER_DRIVERS)
440
+  #error "Z_DUAL_STEPPER_DRIVERS is now NUM_Z_STEPPER_DRIVERS with a value of 2. Please update Configuration_adv.h."
441
+#elif defined(Z_TRIPLE_STEPPER_DRIVERS)
442
+  #error "Z_TRIPLE_STEPPER_DRIVERS is now NUM_Z_STEPPER_DRIVERS with a value of 3. Please update Configuration_adv.h."
443
+#elif defined(Z_QUAD_STEPPER_DRIVERS)
444
+  #error "Z_QUAD_STEPPER_DRIVERS is now NUM_Z_STEPPER_DRIVERS with a value of 4. Please update Configuration_adv.h."
445
+#elif defined(Z_DUAL_ENDSTOPS)
446
+  #error "Z_DUAL_ENDSTOPS is now Z_MULTI_ENDSTOPS. Please update Configuration_adv.h."
447
+#elif defined(Z_TRIPLE_ENDSTOPS)
448
+  #error "Z_TRIPLE_ENDSTOPS is now Z_MULTI_ENDSTOPS. Please update Configuration_adv.h."
449
+#elif defined(Z_QUAD_ENDSTOPS)
450
+  #error "Z_QUAD_ENDSTOPS is now Z_MULTI_ENDSTOPS. Please update Configuration_adv.h."
429 451
 #endif
430 452
 
431 453
 /**
@@ -473,22 +495,27 @@
473 495
 #endif
474 496
 
475 497
 /**
476
- * Dual / Triple Stepper Drivers
498
+ * Multiple Stepper Drivers Per Axis
477 499
  */
478
-#if BOTH(X_DUAL_STEPPER_DRIVERS, DUAL_X_CARRIAGE)
479
-  #error "DUAL_X_CARRIAGE is not compatible with X_DUAL_STEPPER_DRIVERS."
480
-#elif ENABLED(X_DUAL_STEPPER_DRIVERS) && !(HAS_X2_ENABLE && HAS_X2_STEP && HAS_X2_DIR)
481
-  #error "X_DUAL_STEPPER_DRIVERS requires X2 pins (and an extra E plug)."
482
-#elif ENABLED(Y_DUAL_STEPPER_DRIVERS) && !(HAS_Y2_ENABLE && HAS_Y2_STEP && HAS_Y2_DIR)
483
-  #error "Y_DUAL_STEPPER_DRIVERS requires Y2 pins (and an extra E plug)."
484
-#elif ENABLED(Z_DUAL_STEPPER_DRIVERS)
485
-  #if ENABLED(Z_TRIPLE_STEPPER_DRIVERS)
486
-    #error "Please select either Z_TRIPLE_STEPPER_DRIVERS or Z_DUAL_STEPPER_DRIVERS, not both."
487
-  #elif !(HAS_Z2_ENABLE && HAS_Z2_STEP && HAS_Z2_DIR)
488
-    #error "Z_DUAL_STEPPER_DRIVERS requires Z2 pins (and an extra E plug)."
500
+#define GOOD_AXIS_PINS(A) (HAS_##A##_ENABLE && HAS_##A##_STEP && HAS_##A##_DIR)
501
+#if ENABLED(X_DUAL_STEPPER_DRIVERS)
502
+  #if ENABLED(DUAL_X_CARRIAGE)
503
+    #error "DUAL_X_CARRIAGE is not compatible with X_DUAL_STEPPER_DRIVERS."
504
+  #elif !GOOD_AXIS_PINS(X)
505
+    #error "X_DUAL_STEPPER_DRIVERS requires X2 pins to be defined."
489 506
   #endif
490
-#elif ENABLED(Z_TRIPLE_STEPPER_DRIVERS) && !(HAS_Z2_ENABLE && HAS_Z2_STEP && HAS_Z2_DIR && HAS_Z3_ENABLE && HAS_Z3_STEP && HAS_Z3_DIR)
491
-  #error "Z_TRIPLE_STEPPER_DRIVERS requires Z3 pins (and two extra E plugs)."
507
+#endif
508
+
509
+#if ENABLED(Y_DUAL_STEPPER_DRIVERS) && !GOOD_AXIS_PINS(Y)
510
+  #error "Y_DUAL_STEPPER_DRIVERS requires Y2 pins to be defined."
511
+#elif !WITHIN(NUM_Z_STEPPER_DRIVERS, 1, 4)
512
+  #error "NUM_Z_STEPPER_DRIVERS must be an integer from 1 to 4."
513
+#elif NUM_Z_STEPPER_DRIVERS == 2 && !GOOD_AXIS_PINS(Z2)
514
+  #error "If NUM_Z_STEPPER_DRIVERS is 2, you must define stepper pins for Z2."
515
+#elif NUM_Z_STEPPER_DRIVERS == 3 && !(GOOD_AXIS_PINS(Z2) && GOOD_AXIS_PINS(Z3))
516
+  #error "If NUM_Z_STEPPER_DRIVERS is 3, you must define stepper pins for Z2 and Z3."
517
+#elif NUM_Z_STEPPER_DRIVERS == 4 && !(GOOD_AXIS_PINS(Z2) && GOOD_AXIS_PINS(Z3) && GOOD_AXIS_PINS(Z4))
518
+  #error "If NUM_Z_STEPPER_DRIVERS is 4, you must define stepper pins for Z2, Z3, and Z4."
492 519
 #endif
493 520
 
494 521
 /**
@@ -1393,7 +1420,7 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS
1393 1420
     #error "DUAL_X_CARRIAGE requires 2 (or more) extruders."
1394 1421
   #elif CORE_IS_XY || CORE_IS_XZ
1395 1422
     #error "DUAL_X_CARRIAGE cannot be used with COREXY, COREYX, COREXZ, or COREZX."
1396
-  #elif !(HAS_X2_ENABLE && HAS_X2_STEP && HAS_X2_DIR)
1423
+  #elif !GOOD_AXIS_PINS(X2)
1397 1424
     #error "DUAL_X_CARRIAGE requires X2 stepper pins to be defined."
1398 1425
   #elif !HAS_X_MAX
1399 1426
     #error "DUAL_X_CARRIAGE requires USE_XMAX_PLUG and an X Max Endstop."
@@ -1404,6 +1431,8 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS
1404 1431
   #endif
1405 1432
 #endif
1406 1433
 
1434
+#undef GOOD_AXIS_PINS
1435
+
1407 1436
 /**
1408 1437
  * Make sure auto fan pins don't conflict with the fan pin
1409 1438
  */
@@ -1695,7 +1724,7 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS
1695 1724
   #error "Enable USE_ZMAX_PLUG when homing Z to MAX."
1696 1725
 #endif
1697 1726
 
1698
-// Dual endstops requirements
1727
+// Dual/multiple endstops requirements
1699 1728
 #if ENABLED(X_DUAL_ENDSTOPS)
1700 1729
   #if !X2_USE_ENDSTOP
1701 1730
     #error "You must set X2_USE_ENDSTOP with X_DUAL_ENDSTOPS."
@@ -1738,9 +1767,10 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS
1738 1767
     #error "Y_DUAL_ENDSTOPS is not compatible with DELTA."
1739 1768
   #endif
1740 1769
 #endif
1741
-#if ENABLED(Z_DUAL_ENDSTOPS)
1770
+
1771
+#if ENABLED(Z_MULTI_ENDSTOPS)
1742 1772
   #if !Z2_USE_ENDSTOP
1743
-    #error "You must set Z2_USE_ENDSTOP with Z_DUAL_ENDSTOPS."
1773
+    #error "You must set Z2_USE_ENDSTOP with Z_MULTI_ENDSTOPS when NUM_Z_STEPPER_DRIVERS >= 2."
1744 1774
   #elif Z2_USE_ENDSTOP == _XMIN_ && DISABLED(USE_XMIN_PLUG)
1745 1775
     #error "USE_XMIN_PLUG is required when Z2_USE_ENDSTOP is _XMIN_."
1746 1776
   #elif Z2_USE_ENDSTOP == _XMAX_ && DISABLED(USE_XMAX_PLUG)
@@ -1756,47 +1786,45 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS
1756 1786
   #elif !HAS_Z2_MIN && !HAS_Z2_MAX
1757 1787
     #error "Z2_USE_ENDSTOP has been assigned to a nonexistent endstop!"
1758 1788
   #elif ENABLED(DELTA)
1759
-    #error "Z_DUAL_ENDSTOPS is not compatible with DELTA."
1789
+    #error "Z_MULTI_ENDSTOPS is not compatible with DELTA."
1790
+  #endif
1791
+  #if NUM_Z_STEPPER_DRIVERS >= 3
1792
+    #if !Z3_USE_ENDSTOP
1793
+      #error "You must set Z3_USE_ENDSTOP with Z_MULTI_ENDSTOPS when NUM_Z_STEPPER_DRIVERS >= 3."
1794
+    #elif Z3_USE_ENDSTOP == _XMIN_ && DISABLED(USE_XMIN_PLUG)
1795
+      #error "USE_XMIN_PLUG is required when Z3_USE_ENDSTOP is _XMIN_."
1796
+    #elif Z3_USE_ENDSTOP == _XMAX_ && DISABLED(USE_XMAX_PLUG)
1797
+      #error "USE_XMAX_PLUG is required when Z3_USE_ENDSTOP is _XMAX_."
1798
+    #elif Z3_USE_ENDSTOP == _YMIN_ && DISABLED(USE_YMIN_PLUG)
1799
+      #error "USE_YMIN_PLUG is required when Z3_USE_ENDSTOP is _YMIN_."
1800
+    #elif Z3_USE_ENDSTOP == _YMAX_ && DISABLED(USE_YMAX_PLUG)
1801
+      #error "USE_YMAX_PLUG is required when Z3_USE_ENDSTOP is _YMAX_."
1802
+    #elif Z3_USE_ENDSTOP == _ZMIN_ && DISABLED(USE_ZMIN_PLUG)
1803
+      #error "USE_ZMIN_PLUG is required when Z3_USE_ENDSTOP is _ZMIN_."
1804
+    #elif Z3_USE_ENDSTOP == _ZMAX_ && DISABLED(USE_ZMAX_PLUG)
1805
+      #error "USE_ZMAX_PLUG is required when Z3_USE_ENDSTOP is _ZMAX_."
1806
+    #elif !HAS_Z3_MIN && !HAS_Z3_MAX
1807
+      #error "Z3_USE_ENDSTOP has been assigned to a nonexistent endstop!"
1808
+    #endif
1760 1809
   #endif
1761
-#endif
1762
-#if ENABLED(Z_TRIPLE_ENDSTOPS)
1763
-  #if !Z2_USE_ENDSTOP
1764
-    #error "You must set Z2_USE_ENDSTOP with Z_TRIPLE_ENDSTOPS."
1765
-  #elif Z2_USE_ENDSTOP == _XMIN_ && DISABLED(USE_XMIN_PLUG)
1766
-    #error "USE_XMIN_PLUG is required when Z2_USE_ENDSTOP is _XMIN_."
1767
-  #elif Z2_USE_ENDSTOP == _XMAX_ && DISABLED(USE_XMAX_PLUG)
1768
-    #error "USE_XMAX_PLUG is required when Z2_USE_ENDSTOP is _XMAX_."
1769
-  #elif Z2_USE_ENDSTOP == _YMIN_ && DISABLED(USE_YMIN_PLUG)
1770
-    #error "USE_YMIN_PLUG is required when Z2_USE_ENDSTOP is _YMIN_."
1771
-  #elif Z2_USE_ENDSTOP == _YMAX_ && DISABLED(USE_YMAX_PLUG)
1772
-    #error "USE_YMAX_PLUG is required when Z2_USE_ENDSTOP is _YMAX_."
1773
-  #elif Z2_USE_ENDSTOP == _ZMIN_ && DISABLED(USE_ZMIN_PLUG)
1774
-    #error "USE_ZMIN_PLUG is required when Z2_USE_ENDSTOP is _ZMIN_."
1775
-  #elif Z2_USE_ENDSTOP == _ZMAX_ && DISABLED(USE_ZMAX_PLUG)
1776
-    #error "USE_ZMAX_PLUG is required when Z2_USE_ENDSTOP is _ZMAX_."
1777
-  #elif !HAS_Z2_MIN && !HAS_Z2_MAX
1778
-    #error "Z2_USE_ENDSTOP has been assigned to a nonexistent endstop!"
1779
-  #elif ENABLED(DELTA)
1780
-    #error "Z_TRIPLE_ENDSTOPS is not compatible with DELTA."
1781
-  #endif
1782
-  #if !Z3_USE_ENDSTOP
1783
-    #error "You must set Z3_USE_ENDSTOP with Z_TRIPLE_ENDSTOPS."
1784
-  #elif Z3_USE_ENDSTOP == _XMIN_ && DISABLED(USE_XMIN_PLUG)
1785
-    #error "USE_XMIN_PLUG is required when Z3_USE_ENDSTOP is _XMIN_."
1786
-  #elif Z3_USE_ENDSTOP == _XMAX_ && DISABLED(USE_XMAX_PLUG)
1787
-    #error "USE_XMAX_PLUG is required when Z3_USE_ENDSTOP is _XMAX_."
1788
-  #elif Z3_USE_ENDSTOP == _YMIN_ && DISABLED(USE_YMIN_PLUG)
1789
-    #error "USE_YMIN_PLUG is required when Z3_USE_ENDSTOP is _YMIN_."
1790
-  #elif Z3_USE_ENDSTOP == _YMAX_ && DISABLED(USE_YMAX_PLUG)
1791
-    #error "USE_YMAX_PLUG is required when Z3_USE_ENDSTOP is _YMAX_."
1792
-  #elif Z3_USE_ENDSTOP == _ZMIN_ && DISABLED(USE_ZMIN_PLUG)
1793
-    #error "USE_ZMIN_PLUG is required when Z3_USE_ENDSTOP is _ZMIN_."
1794
-  #elif Z3_USE_ENDSTOP == _ZMAX_ && DISABLED(USE_ZMAX_PLUG)
1795
-    #error "USE_ZMAX_PLUG is required when Z3_USE_ENDSTOP is _ZMAX_."
1796
-  #elif !HAS_Z3_MIN && !HAS_Z3_MAX
1797
-    #error "Z3_USE_ENDSTOP has been assigned to a nonexistent endstop!"
1798
-  #elif ENABLED(DELTA)
1799
-    #error "Z_TRIPLE_ENDSTOPS is not compatible with DELTA."
1810
+  #if NUM_Z_STEPPER_DRIVERS >= 4
1811
+    #if !Z4_USE_ENDSTOP
1812
+      #error "You must set Z4_USE_ENDSTOP with Z_MULTI_ENDSTOPS when NUM_Z_STEPPER_DRIVERS >= 4."
1813
+    #elif Z4_USE_ENDSTOP == _XMIN_ && DISABLED(USE_XMIN_PLUG)
1814
+      #error "USE_XMIN_PLUG is required when Z4_USE_ENDSTOP is _XMIN_."
1815
+    #elif Z4_USE_ENDSTOP == _XMAX_ && DISABLED(USE_XMAX_PLUG)
1816
+      #error "USE_XMAX_PLUG is required when Z4_USE_ENDSTOP is _XMAX_."
1817
+    #elif Z4_USE_ENDSTOP == _YMIN_ && DISABLED(USE_YMIN_PLUG)
1818
+      #error "USE_YMIN_PLUG is required when Z4_USE_ENDSTOP is _YMIN_."
1819
+    #elif Z4_USE_ENDSTOP == _YMAX_ && DISABLED(USE_YMAX_PLUG)
1820
+      #error "USE_YMAX_PLUG is required when Z4_USE_ENDSTOP is _YMAX_."
1821
+    #elif Z4_USE_ENDSTOP == _ZMIN_ && DISABLED(USE_ZMIN_PLUG)
1822
+      #error "USE_ZMIN_PLUG is required when Z4_USE_ENDSTOP is _ZMIN_."
1823
+    #elif Z4_USE_ENDSTOP == _ZMAX_ && DISABLED(USE_ZMAX_PLUG)
1824
+      #error "USE_ZMAX_PLUG is required when Z4_USE_ENDSTOP is _ZMAX_."
1825
+    #elif !HAS_Z4_MIN && !HAS_Z4_MAX
1826
+      #error "Z4_USE_ENDSTOP has been assigned to a nonexistent endstop!"
1827
+    #endif
1800 1828
   #endif
1801 1829
 #endif
1802 1830
 
@@ -2321,12 +2349,12 @@ static_assert(   _ARR_TEST(3,0) && _ARR_TEST(3,1) && _ARR_TEST(3,2)
2321 2349
 #endif
2322 2350
 
2323 2351
 #if ENABLED(Z_STEPPER_AUTO_ALIGN)
2324
-  #if !Z_MULTI_STEPPER_DRIVERS
2325
-    #error "Z_STEPPER_AUTO_ALIGN requires Z_DUAL_STEPPER_DRIVERS or Z_TRIPLE_STEPPER_DRIVERS."
2352
+  #if NUM_Z_STEPPER_DRIVERS <= 1
2353
+    #error "Z_STEPPER_AUTO_ALIGN requires NUM_Z_STEPPER_DRIVERS greater than 1."
2326 2354
   #elif !HAS_BED_PROBE
2327 2355
     #error "Z_STEPPER_AUTO_ALIGN requires a Z-bed probe."
2328
-  #elif ENABLED(Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS) && DISABLED(Z_TRIPLE_STEPPER_DRIVERS)
2329
-    #error "Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS requires Z_TRIPLE_STEPPER_DRIVERS."
2356
+  #elif ENABLED(Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS) && NUM_Z_STEPPER_DRIVERS != 3
2357
+    #error "Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS requires NUM_Z_STEPPER_DRIVERS to be 3."
2330 2358
   #endif
2331 2359
 #endif
2332 2360
 

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

@@ -58,6 +58,9 @@ void menu_tmc_current() {
58 58
   #if AXIS_IS_TMC(Z3)
59 59
     TMC_EDIT_STORED_I_RMS(Z3, MSG_Z3);
60 60
   #endif
61
+  #if AXIS_IS_TMC(Z4)
62
+    TMC_EDIT_STORED_I_RMS(Z4, MSG_Z4);
63
+  #endif
61 64
   #if AXIS_IS_TMC(E0)
62 65
     TMC_EDIT_STORED_I_RMS(E0, LCD_STR_E0);
63 66
   #endif
@@ -107,6 +110,9 @@ void menu_tmc_current() {
107 110
     #if AXIS_HAS_STEALTHCHOP(Z3)
108 111
       TMC_EDIT_STORED_HYBRID_THRS(Z3, MSG_Z3);
109 112
     #endif
113
+    #if AXIS_HAS_STEALTHCHOP(Z4)
114
+      TMC_EDIT_STORED_HYBRID_THRS(Z4, MSG_Z4);
115
+    #endif
110 116
     #if AXIS_HAS_STEALTHCHOP(E0)
111 117
       TMC_EDIT_STORED_HYBRID_THRS(E0, LCD_STR_E0);
112 118
     #endif
@@ -183,6 +189,9 @@ void menu_tmc_current() {
183 189
     #if AXIS_HAS_STEALTHCHOP(Z3)
184 190
       TMC_EDIT_STEP_MODE(Z3, MSG_Z3);
185 191
     #endif
192
+    #if AXIS_HAS_STEALTHCHOP(Z4)
193
+      TMC_EDIT_STEP_MODE(Z4, MSG_Z4);
194
+    #endif
186 195
     #if AXIS_HAS_STEALTHCHOP(E0)
187 196
       TMC_EDIT_STEP_MODE(E0, LCD_STR_E0);
188 197
     #endif

+ 27
- 7
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", "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" };
43 43
 
44 44
 #define DEBUG_OUT ENABLED(L6470_CHITCHAT)
45 45
 #include "../../core/debug_out.h"
@@ -61,12 +61,14 @@ uint8_t L64XX_Marlin::index_to_dir[MAX_L64XX] = { (INVERT_X_DIR),
61 61
                                                   #endif
62 62
                                                   (INVERT_Z_DIR),                         //  5 Z2
63 63
                                                   (INVERT_Z_DIR),                         //  6 Z3
64
-                                                  (INVERT_E0_DIR),                        //  7 E0
65
-                                                  (INVERT_E1_DIR),                        //  8 E1
66
-                                                  (INVERT_E2_DIR),                        //  9 E2
67
-                                                  (INVERT_E3_DIR),                        // 10 E3
68
-                                                  (INVERT_E4_DIR),                        // 11 E4
69
-                                                  (INVERT_E5_DIR),                        // 12 E5
64
+                                                  (INVERT_Z_DIR),                         //  7 Z4
65
+
66
+                                                  (INVERT_E0_DIR),                        //  8 E0
67
+                                                  (INVERT_E1_DIR),                        //  9 E1
68
+                                                  (INVERT_E2_DIR),                        // 10 E2
69
+                                                  (INVERT_E3_DIR),                        // 11 E3
70
+                                                  (INVERT_E4_DIR),                        // 12 E4
71
+                                                  (INVERT_E5_DIR),                        // 13 E5
70 72
                                                 };
71 73
 
72 74
 volatile uint8_t L64XX_Marlin::spi_abort = false;
@@ -101,6 +103,9 @@ void L6470_populate_chain_array() {
101 103
   #if AXIS_IS_L64XX(Z3)
102 104
     _L6470_INIT_SPI(Z3);
103 105
   #endif
106
+  #if AXIS_IS_L64XX(Z4)
107
+    _L6470_INIT_SPI(Z4);
108
+  #endif
104 109
   #if AXIS_IS_L64XX(E0)
105 110
     _L6470_INIT_SPI(E0);
106 111
   #endif
@@ -211,6 +216,9 @@ uint16_t L64XX_Marlin::get_status(const L64XX_axis_t axis) {
211 216
     #if AXIS_IS_L64XX(Z3)
212 217
       case Z3: return STATUS_L6470(Z3);
213 218
     #endif
219
+    #if AXIS_IS_L64XX(Z4)
220
+      case Z4: return STATUS_L6470(Z4);
221
+    #endif
214 222
     #if AXIS_IS_L64XX(E0)
215 223
       case E0: return STATUS_L6470(E0);
216 224
     #endif
@@ -261,6 +269,9 @@ uint32_t L64XX_Marlin::get_param(const L64XX_axis_t axis, const uint8_t param) {
261 269
     #if AXIS_IS_L64XX(Z3)
262 270
       case Z3: return GET_L6470_PARAM(Z3);
263 271
     #endif
272
+    #if AXIS_IS_L64XX(Z4)
273
+      case Z4: return GET_L6470_PARAM(Z4);
274
+    #endif
264 275
     #if AXIS_IS_L64XX(E0)
265 276
       case E0: return GET_L6470_PARAM(E0);
266 277
     #endif
@@ -311,6 +322,9 @@ void L64XX_Marlin::set_param(const L64XX_axis_t axis, const uint8_t param, const
311 322
     #if AXIS_IS_L64XX(Z3)
312 323
       case Z3: SET_L6470_PARAM(Z3); break;
313 324
     #endif
325
+    #if AXIS_IS_L64XX(Z4)
326
+      case Z4: SET_L6470_PARAM(Z4); break;
327
+    #endif
314 328
     #if AXIS_IS_L64XX(E0)
315 329
       case E0: SET_L6470_PARAM(E0); break;
316 330
     #endif
@@ -684,6 +698,9 @@ void L64XX_Marlin::say_axis(const L64XX_axis_t axis, const uint8_t label/*=true*
684 698
     #if AXIS_IS_L64XX(Z3)
685 699
       {  6, 0, 0, 0, 0, 0, 0 },
686 700
     #endif
701
+    #if AXIS_IS_L64XX(Z4)
702
+      {  6, 0, 0, 0, 0, 0, 0 },
703
+    #endif
687 704
     #if AXIS_IS_L64XX(E0)
688 705
       {  7, 0, 0, 0, 0, 0, 0 },
689 706
     #endif
@@ -858,6 +875,9 @@ void L64XX_Marlin::say_axis(const L64XX_axis_t axis, const uint8_t label/*=true*
858 875
         #if AXIS_IS_L64XX(Z3)
859 876
           monitor_update(Z3);
860 877
         #endif
878
+        #if AXIS_IS_L64XX(Z4)
879
+          monitor_update(Z4);
880
+        #endif
861 881
         #if AXIS_IS_L64XX(E0)
862 882
           monitor_update(E0);
863 883
         #endif

+ 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, 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, MAX_L64XX };
39 39
 
40 40
 class L64XX_Marlin : public L64XXHelper {
41 41
 public:

+ 115
- 69
Marlin/src/module/configuration_store.cpp View File

@@ -37,7 +37,7 @@
37 37
  */
38 38
 
39 39
 // Change EEPROM version if the structure changes
40
-#define EEPROM_VERSION "V74"
40
+#define EEPROM_VERSION "V75"
41 41
 #define EEPROM_OFFSET 100
42 42
 
43 43
 // Check the integrity of data offsets.
@@ -120,10 +120,10 @@
120 120
 
121 121
 #pragma pack(push, 1) // No padding between variables
122 122
 
123
-typedef struct { uint16_t X, Y, Z, X2, Y2, Z2, Z3, E0, E1, E2, E3, E4, E5; } tmc_stepper_current_t;
124
-typedef struct { uint32_t X, Y, Z, X2, Y2, Z2, Z3, E0, E1, E2, E3, E4, E5; } tmc_hybrid_threshold_t;
123
+typedef struct { uint16_t X, Y, Z, X2, Y2, Z2, Z3, Z4, E0, E1, E2, E3, E4, E5; } tmc_stepper_current_t;
124
+typedef struct { uint32_t X, Y, Z, X2, Y2, Z2, Z3, Z4, E0, E1, E2, E3, E4, E5; } tmc_hybrid_threshold_t;
125 125
 typedef struct {  int16_t X, Y, Z, X2;                                     } tmc_sgt_t;
126
-typedef struct {     bool X, Y, Z, X2, Y2, Z2, Z3, E0, E1, E2, E3, E4, E5; } tmc_stealth_enabled_t;
126
+typedef struct {     bool X, Y, Z, X2, Y2, Z2, Z3, Z4, E0, E1, E2, E3, E4, E5; } tmc_stealth_enabled_t;
127 127
 
128 128
 // Limit an index to an array size
129 129
 #define ALIM(I,ARR) _MIN(I, COUNT(ARR) - 1)
@@ -243,11 +243,12 @@ typedef struct SettingsDataStruct {
243 243
           delta_diagonal_rod,                           // M665 L
244 244
           delta_segments_per_second;                    // M665 S
245 245
     abc_float_t delta_tower_angle_trim;                 // M665 XYZ
246
-  #elif EITHER(X_DUAL_ENDSTOPS, Y_DUAL_ENDSTOPS) || Z_MULTI_ENDSTOPS
246
+  #elif HAS_EXTRA_ENDSTOPS
247 247
     float x2_endstop_adj,                               // M666 X
248 248
           y2_endstop_adj,                               // M666 Y
249
-          z2_endstop_adj,                               // M666 Z (S2)
250
-          z3_endstop_adj;                               // M666 Z (S3)
249
+          z2_endstop_adj,                               // M666 (S2) Z
250
+          z3_endstop_adj,                               // M666 (S3) Z
251
+          z4_endstop_adj;                               // M666 (S4) Z
251 252
   #endif
252 253
 
253 254
   //
@@ -300,10 +301,10 @@ typedef struct SettingsDataStruct {
300 301
   //
301 302
   // HAS_TRINAMIC
302 303
   //
303
-  tmc_stepper_current_t tmc_stepper_current;            // M906 X Y Z X2 Y2 Z2 Z3 E0 E1 E2 E3 E4 E5
304
-  tmc_hybrid_threshold_t tmc_hybrid_threshold;          // M913 X Y Z X2 Y2 Z2 Z3 E0 E1 E2 E3 E4 E5
304
+  tmc_stepper_current_t tmc_stepper_current;            // M906 X Y Z X2 Y2 Z2 Z3 Z4 E0 E1 E2 E3 E4 E5
305
+  tmc_hybrid_threshold_t tmc_hybrid_threshold;          // M913 X Y Z X2 Y2 Z2 Z3 Z4 E0 E1 E2 E3 E4 E5
305 306
   tmc_sgt_t tmc_sgt;                                    // M914 X Y Z X2
306
-  tmc_stealth_enabled_t tmc_stealth_enabled;            // M569 X Y Z X2 Y2 Z2 Z3 E0 E1 E2 E3 E4 E5
307
+  tmc_stealth_enabled_t tmc_stealth_enabled;            // M569 X Y Z X2 Y2 Z2 Z3 Z4 E0 E1 E2 E3 E4 E5
307 308
 
308 309
   //
309 310
   // LIN_ADVANCE
@@ -756,7 +757,7 @@ void MarlinSettings::postprocess() {
756 757
         EEPROM_WRITE(delta_segments_per_second); // 1 float
757 758
         EEPROM_WRITE(delta_tower_angle_trim);    // 3 floats
758 759
 
759
-      #elif EITHER(X_DUAL_ENDSTOPS, Y_DUAL_ENDSTOPS) || Z_MULTI_ENDSTOPS
760
+      #elif HAS_EXTRA_ENDSTOPS
760 761
 
761 762
         _FIELD_TEST(x2_endstop_adj);
762 763
 
@@ -774,18 +775,24 @@ void MarlinSettings::postprocess() {
774 775
           EEPROM_WRITE(dummy);
775 776
         #endif
776 777
 
777
-        #if Z_MULTI_ENDSTOPS
778
+        #if ENABLED(Z_MULTI_ENDSTOPS)
778 779
           EEPROM_WRITE(endstops.z2_endstop_adj);   // 1 float
779 780
         #else
780 781
           EEPROM_WRITE(dummy);
781 782
         #endif
782 783
 
783
-        #if ENABLED(Z_TRIPLE_ENDSTOPS)
784
+        #if ENABLED(Z_MULTI_ENDSTOPS) && NUM_Z_STEPPER_DRIVERS >= 3
784 785
           EEPROM_WRITE(endstops.z3_endstop_adj);   // 1 float
785 786
         #else
786 787
           EEPROM_WRITE(dummy);
787 788
         #endif
788 789
 
790
+        #if ENABLED(Z_MULTI_ENDSTOPS) && NUM_Z_STEPPER_DRIVERS >= 4
791
+          EEPROM_WRITE(endstops.z4_endstop_adj);   // 1 float
792
+        #else
793
+          EEPROM_WRITE(dummy);
794
+        #endif
795
+
789 796
       #endif
790 797
     }
791 798
 
@@ -974,6 +981,9 @@ void MarlinSettings::postprocess() {
974 981
         #if AXIS_IS_TMC(Z3)
975 982
           tmc_stepper_current.Z3 = stepperZ3.getMilliamps();
976 983
         #endif
984
+        #if AXIS_IS_TMC(Z4)
985
+          tmc_stepper_current.Z4 = stepperZ4.getMilliamps();
986
+        #endif
977 987
         #if MAX_EXTRUDERS
978 988
           #if AXIS_IS_TMC(E0)
979 989
             tmc_stepper_current.E0 = stepperE0.getMilliamps();
@@ -1037,6 +1047,9 @@ void MarlinSettings::postprocess() {
1037 1047
         #if AXIS_HAS_STEALTHCHOP(Z3)
1038 1048
           tmc_hybrid_threshold.Z3 = stepperZ3.get_pwm_thrs();
1039 1049
         #endif
1050
+        #if AXIS_HAS_STEALTHCHOP(Z4)
1051
+          tmc_hybrid_threshold.Z4 = stepperZ4.get_pwm_thrs();
1052
+        #endif
1040 1053
         #if MAX_EXTRUDERS
1041 1054
           #if AXIS_HAS_STEALTHCHOP(E0)
1042 1055
             tmc_hybrid_threshold.E0 = stepperE0.get_pwm_thrs();
@@ -1070,7 +1083,7 @@ void MarlinSettings::postprocess() {
1070 1083
       #else
1071 1084
         const tmc_hybrid_threshold_t tmc_hybrid_threshold = {
1072 1085
           .X  = 100, .Y  = 100, .Z  =   3,
1073
-          .X2 = 100, .Y2 = 100, .Z2 =   3, .Z3 =   3,
1086
+          .X2 = 100, .Y2 = 100, .Z2 =   3, .Z3 =   3, .Z4 = 3,
1074 1087
           .E0 =  30, .E1 =  30, .E2 =  30,
1075 1088
           .E3 =  30, .E4 =  30, .E5 =  30
1076 1089
         };
@@ -1130,6 +1143,9 @@ void MarlinSettings::postprocess() {
1130 1143
         #if AXIS_HAS_STEALTHCHOP(Z3)
1131 1144
           tmc_stealth_enabled.Z3 = stepperZ3.get_stealthChop_status();
1132 1145
         #endif
1146
+        #if AXIS_HAS_STEALTHCHOP(Z4)
1147
+          tmc_stealth_enabled.Z4 = stepperZ4.get_stealthChop_status();
1148
+        #endif
1133 1149
         #if MAX_EXTRUDERS
1134 1150
           #if AXIS_HAS_STEALTHCHOP(E0)
1135 1151
             tmc_stealth_enabled.E0 = stepperE0.get_stealthChop_status();
@@ -1585,7 +1601,7 @@ void MarlinSettings::postprocess() {
1585 1601
           EEPROM_READ(delta_segments_per_second); // 1 float
1586 1602
           EEPROM_READ(delta_tower_angle_trim);    // 3 floats
1587 1603
 
1588
-        #elif EITHER(X_DUAL_ENDSTOPS, Y_DUAL_ENDSTOPS) || Z_MULTI_ENDSTOPS
1604
+        #elif HAS_EXTRA_ENDSTOPS
1589 1605
 
1590 1606
           _FIELD_TEST(x2_endstop_adj);
1591 1607
 
@@ -1599,16 +1615,21 @@ void MarlinSettings::postprocess() {
1599 1615
           #else
1600 1616
             EEPROM_READ(dummy);
1601 1617
           #endif
1602
-          #if Z_MULTI_ENDSTOPS
1618
+          #if ENABLED(Z_MULTI_ENDSTOPS)
1603 1619
             EEPROM_READ(endstops.z2_endstop_adj); // 1 float
1604 1620
           #else
1605 1621
             EEPROM_READ(dummy);
1606 1622
           #endif
1607
-          #if ENABLED(Z_TRIPLE_ENDSTOPS)
1623
+          #if ENABLED(Z_MULTI_ENDSTOPS) && NUM_Z_STEPPER_DRIVERS >= 3
1608 1624
             EEPROM_READ(endstops.z3_endstop_adj); // 1 float
1609 1625
           #else
1610 1626
             EEPROM_READ(dummy);
1611 1627
           #endif
1628
+          #if ENABLED(Z_MULTI_ENDSTOPS) && NUM_Z_STEPPER_DRIVERS >= 4
1629
+            EEPROM_READ(endstops.z4_endstop_adj); // 1 float
1630
+          #else
1631
+            EEPROM_READ(dummy);
1632
+          #endif
1612 1633
 
1613 1634
         #endif
1614 1635
       }
@@ -1800,6 +1821,9 @@ void MarlinSettings::postprocess() {
1800 1821
             #if AXIS_IS_TMC(Z3)
1801 1822
               SET_CURR(Z3);
1802 1823
             #endif
1824
+            #if AXIS_IS_TMC(Z4)
1825
+              SET_CURR(Z4);
1826
+            #endif
1803 1827
             #if AXIS_IS_TMC(E0)
1804 1828
               SET_CURR(E0);
1805 1829
             #endif
@@ -1851,6 +1875,9 @@ void MarlinSettings::postprocess() {
1851 1875
             #if AXIS_HAS_STEALTHCHOP(Z3)
1852 1876
               stepperZ3.set_pwm_thrs(tmc_hybrid_threshold.Z3);
1853 1877
             #endif
1878
+            #if AXIS_HAS_STEALTHCHOP(Z4)
1879
+              stepperZ4.set_pwm_thrs(tmc_hybrid_threshold.Z4);
1880
+            #endif
1854 1881
             #if AXIS_HAS_STEALTHCHOP(E0)
1855 1882
               stepperE0.set_pwm_thrs(tmc_hybrid_threshold.E0);
1856 1883
             #endif
@@ -1877,7 +1904,7 @@ void MarlinSettings::postprocess() {
1877 1904
       // TMC StallGuard threshold.
1878 1905
       // X and X2 use the same value
1879 1906
       // Y and Y2 use the same value
1880
-      // Z, Z2 and Z3 use the same value
1907
+      // Z, Z2, Z3 and Z4 use the same value
1881 1908
       //
1882 1909
       {
1883 1910
         tmc_sgt_t tmc_sgt;
@@ -1914,6 +1941,9 @@ void MarlinSettings::postprocess() {
1914 1941
               #if AXIS_HAS_STALLGUARD(Z3)
1915 1942
                 stepperZ3.homing_threshold(tmc_sgt.Z);
1916 1943
               #endif
1944
+              #if AXIS_HAS_STALLGUARD(Z4)
1945
+                stepperZ4.homing_threshold(tmc_sgt.Z);
1946
+              #endif
1917 1947
             #endif
1918 1948
           }
1919 1949
         #endif
@@ -1951,6 +1981,9 @@ void MarlinSettings::postprocess() {
1951 1981
             #if AXIS_HAS_STEALTHCHOP(Z3)
1952 1982
               SET_STEPPING_MODE(Z3);
1953 1983
             #endif
1984
+            #if AXIS_HAS_STEALTHCHOP(Z4)
1985
+              SET_STEPPING_MODE(Z4);
1986
+            #endif
1954 1987
             #if AXIS_HAS_STEALTHCHOP(E0)
1955 1988
               SET_STEPPING_MODE(E0);
1956 1989
             #endif
@@ -2433,51 +2466,39 @@ void MarlinSettings::reset() {
2433 2466
     delta_segments_per_second = DELTA_SEGMENTS_PER_SECOND;
2434 2467
     delta_tower_angle_trim = dta;
2435 2468
 
2436
-  #elif EITHER(X_DUAL_ENDSTOPS, Y_DUAL_ENDSTOPS) || Z_MULTI_ENDSTOPS
2469
+  #endif
2437 2470
 
2438
-    #if ENABLED(X_DUAL_ENDSTOPS)
2439
-      endstops.x2_endstop_adj = (
2440
-        #ifdef X_DUAL_ENDSTOPS_ADJUSTMENT
2441
-          X_DUAL_ENDSTOPS_ADJUSTMENT
2442
-        #else
2443
-          0
2444
-        #endif
2445
-      );
2446
-    #endif
2447
-    #if ENABLED(Y_DUAL_ENDSTOPS)
2448
-      endstops.y2_endstop_adj = (
2449
-        #ifdef Y_DUAL_ENDSTOPS_ADJUSTMENT
2450
-          Y_DUAL_ENDSTOPS_ADJUSTMENT
2451
-        #else
2452
-          0
2453
-        #endif
2454
-      );
2471
+  #if ENABLED(X_DUAL_ENDSTOPS)
2472
+    #ifndef X2_ENDSTOP_ADJUSTMENT
2473
+      #define X2_ENDSTOP_ADJUSTMENT 0
2455 2474
     #endif
2456
-    #if ENABLED(Z_DUAL_ENDSTOPS)
2457
-      endstops.z2_endstop_adj = (
2458
-        #ifdef Z_DUAL_ENDSTOPS_ADJUSTMENT
2459
-          Z_DUAL_ENDSTOPS_ADJUSTMENT
2460
-        #else
2461
-          0
2462
-        #endif
2463
-      );
2464
-    #elif ENABLED(Z_TRIPLE_ENDSTOPS)
2465
-      endstops.z2_endstop_adj = (
2466
-        #ifdef Z_TRIPLE_ENDSTOPS_ADJUSTMENT2
2467
-          Z_TRIPLE_ENDSTOPS_ADJUSTMENT2
2468
-        #else
2469
-          0
2470
-        #endif
2471
-      );
2472
-      endstops.z3_endstop_adj = (
2473
-        #ifdef Z_TRIPLE_ENDSTOPS_ADJUSTMENT3
2474
-          Z_TRIPLE_ENDSTOPS_ADJUSTMENT3
2475
-        #else
2476
-          0
2477
-        #endif
2478
-      );
2475
+    endstops.x2_endstop_adj = X2_ENDSTOP_ADJUSTMENT;
2476
+  #endif
2477
+
2478
+  #if ENABLED(Y_DUAL_ENDSTOPS)
2479
+    #ifndef Y2_ENDSTOP_ADJUSTMENT
2480
+      #define Y2_ENDSTOP_ADJUSTMENT 0
2479 2481
     #endif
2482
+    endstops.y2_endstop_adj = Y2_ENDSTOP_ADJUSTMENT;
2483
+  #endif
2480 2484
 
2485
+  #if ENABLED(Z_MULTI_ENDSTOPS)
2486
+    #ifndef Z2_ENDSTOP_ADJUSTMENT
2487
+      #define Z2_ENDSTOP_ADJUSTMENT 0
2488
+    #endif
2489
+    endstops.z2_endstop_adj = Z2_ENDSTOP_ADJUSTMENT;
2490
+    #if NUM_Z_STEPPER_DRIVERS >= 3
2491
+      #ifndef Z3_ENDSTOP_ADJUSTMENT
2492
+        #define Z3_ENDSTOP_ADJUSTMENT 0
2493
+      #endif
2494
+      endstops.z3_endstop_adj = Z3_ENDSTOP_ADJUSTMENT;
2495
+    #endif
2496
+    #if NUM_Z_STEPPER_DRIVERS >= 4
2497
+      #ifndef Z4_ENDSTOP_ADJUSTMENT
2498
+        #define Z4_ENDSTOP_ADJUSTMENT 0
2499
+      #endif
2500
+      endstops.z4_endstop_adj = Z4_ENDSTOP_ADJUSTMENT;
2501
+    #endif
2481 2502
   #endif
2482 2503
 
2483 2504
   //
@@ -3016,25 +3037,30 @@ void MarlinSettings::reset() {
3016 3037
         , SP_Z_STR, LINEAR_UNIT(delta_tower_angle_trim.c)
3017 3038
       );
3018 3039
 
3019
-    #elif EITHER(X_DUAL_ENDSTOPS, Y_DUAL_ENDSTOPS) || Z_MULTI_ENDSTOPS
3040
+    #elif HAS_EXTRA_ENDSTOPS
3020 3041
 
3021 3042
       CONFIG_ECHO_HEADING("Endstop adjustment:");
3022 3043
       CONFIG_ECHO_START();
3023 3044
       SERIAL_ECHOPGM("  M666");
3024 3045
       #if ENABLED(X_DUAL_ENDSTOPS)
3025
-        SERIAL_ECHOPAIR_P(SP_X_STR, LINEAR_UNIT(endstops.x2_endstop_adj));
3046
+        SERIAL_ECHOLNPAIR_P(SP_X_STR, LINEAR_UNIT(endstops.x2_endstop_adj));
3026 3047
       #endif
3027 3048
       #if ENABLED(Y_DUAL_ENDSTOPS)
3028
-        SERIAL_ECHOPAIR_P(SP_Y_STR, LINEAR_UNIT(endstops.y2_endstop_adj));
3049
+        SERIAL_ECHOLNPAIR_P(SP_Y_STR, LINEAR_UNIT(endstops.y2_endstop_adj));
3029 3050
       #endif
3030
-      #if ENABLED(Z_TRIPLE_ENDSTOPS)
3031
-        SERIAL_ECHOLNPAIR("S1 Z", LINEAR_UNIT(endstops.z2_endstop_adj));
3032
-        CONFIG_ECHO_START();
3033
-        SERIAL_ECHOPAIR("  M666 S2 Z", LINEAR_UNIT(endstops.z3_endstop_adj));
3034
-      #elif ENABLED(Z_DUAL_ENDSTOPS)
3035
-        SERIAL_ECHOPAIR_P(SP_Z_STR, LINEAR_UNIT(endstops.z2_endstop_adj));
3051
+      #if ENABLED(Z_MULTI_ENDSTOPS)
3052
+        #if NUM_Z_STEPPER_DRIVERS >= 3
3053
+          SERIAL_ECHOPAIR(" S2 Z", LINEAR_UNIT(endstops.z3_endstop_adj));
3054
+          CONFIG_ECHO_START();
3055
+          SERIAL_ECHOPAIR("  M666 S3 Z", LINEAR_UNIT(endstops.z3_endstop_adj));
3056
+          #if NUM_Z_STEPPER_DRIVERS >= 4
3057
+            CONFIG_ECHO_START();
3058
+            SERIAL_ECHOPAIR("  M666 S4 Z", LINEAR_UNIT(endstops.z4_endstop_adj));
3059
+          #endif
3060
+        #else
3061
+          SERIAL_ECHOLNPAIR_P(SP_Z_STR, LINEAR_UNIT(endstops.z2_endstop_adj));
3062
+        #endif
3036 3063
       #endif
3037
-      SERIAL_EOL();
3038 3064
 
3039 3065
     #endif // [XYZ]_DUAL_ENDSTOPS
3040 3066
 
@@ -3218,6 +3244,11 @@ void MarlinSettings::reset() {
3218 3244
         SERIAL_ECHOLNPAIR(" I2 Z", stepperZ3.getMilliamps());
3219 3245
       #endif
3220 3246
 
3247
+      #if AXIS_IS_TMC(Z4)
3248
+        say_M906(forReplay);
3249
+        SERIAL_ECHOLNPAIR(" I3 Z", stepperZ4.getMilliamps());
3250
+      #endif
3251
+
3221 3252
       #if AXIS_IS_TMC(E0)
3222 3253
         say_M906(forReplay);
3223 3254
         SERIAL_ECHOLNPAIR(" T0 E", stepperE0.getMilliamps());
@@ -3287,6 +3318,11 @@ void MarlinSettings::reset() {
3287 3318
           SERIAL_ECHOLNPAIR(" I2 Z", stepperZ3.get_pwm_thrs());
3288 3319
         #endif
3289 3320
 
3321
+        #if AXIS_HAS_STEALTHCHOP(Z4)
3322
+          say_M913(forReplay);
3323
+          SERIAL_ECHOLNPAIR(" I3 Z", stepperZ4.get_pwm_thrs());
3324
+        #endif
3325
+
3290 3326
         #if AXIS_HAS_STEALTHCHOP(E0)
3291 3327
           say_M913(forReplay);
3292 3328
           SERIAL_ECHOLNPAIR(" T0 E", stepperE0.get_pwm_thrs());
@@ -3356,6 +3392,12 @@ void MarlinSettings::reset() {
3356 3392
           SERIAL_ECHOLNPAIR(" I2 Z", stepperZ3.homing_threshold());
3357 3393
         #endif
3358 3394
 
3395
+        #if Z4_SENSORLESS
3396
+          CONFIG_ECHO_START();
3397
+          say_M914();
3398
+          SERIAL_ECHOLNPAIR(" I3 Z", stepperZ4.homing_threshold());
3399
+        #endif
3400
+
3359 3401
       #endif // USE_SENSORLESS
3360 3402
 
3361 3403
       /**
@@ -3415,6 +3457,10 @@ void MarlinSettings::reset() {
3415 3457
           if (stepperZ3.get_stealthChop_status()) { say_M569(forReplay, PSTR("I2 Z"), true); }
3416 3458
         #endif
3417 3459
 
3460
+        #if AXIS_HAS_STEALTHCHOP(Z4)
3461
+          if (stepperZ4.get_stealthChop_status()) { say_M569(forReplay, PSTR("I3 Z"), true); }
3462
+        #endif
3463
+
3418 3464
         #if AXIS_HAS_STEALTHCHOP(E0)
3419 3465
           if (stepperE0.get_stealthChop_status()) { say_M569(forReplay, PSTR("T0 E"), true); }
3420 3466
         #endif

+ 89
- 16
Marlin/src/module/endstops.cpp View File

@@ -73,11 +73,14 @@ Endstops::esbits_t Endstops::live_state = 0;
73 73
 #if ENABLED(Y_DUAL_ENDSTOPS)
74 74
   float Endstops::y2_endstop_adj;
75 75
 #endif
76
-#if Z_MULTI_ENDSTOPS
76
+#if ENABLED(Z_MULTI_ENDSTOPS)
77 77
   float Endstops::z2_endstop_adj;
78
-#endif
79
-#if ENABLED(Z_TRIPLE_ENDSTOPS)
80
-  float Endstops::z3_endstop_adj;
78
+  #if NUM_Z_STEPPER_DRIVERS >= 3
79
+    float Endstops::z3_endstop_adj;
80
+    #if NUM_Z_STEPPER_DRIVERS >= 4
81
+      float Endstops::z4_endstop_adj;
82
+    #endif
83
+  #endif
81 84
 #endif
82 85
 
83 86
 #if ENABLED(SPI_ENDSTOPS)
@@ -163,6 +166,16 @@ void Endstops::init() {
163 166
     #endif
164 167
   #endif
165 168
 
169
+  #if HAS_Z4_MIN
170
+    #if ENABLED(ENDSTOPPULLUP_ZMIN)
171
+      SET_INPUT_PULLUP(Z4_MIN_PIN);
172
+    #elif ENABLED(ENDSTOPPULLDOWN_ZMIN)
173
+      SET_INPUT_PULLDOWN(Z4_MIN_PIN);
174
+    #else
175
+      SET_INPUT(Z4_MIN_PIN);
176
+    #endif
177
+  #endif
178
+
166 179
   #if HAS_X_MAX
167 180
     #if ENABLED(ENDSTOPPULLUP_XMAX)
168 181
       SET_INPUT_PULLUP(X_MAX_PIN);
@@ -233,6 +246,16 @@ void Endstops::init() {
233 246
     #endif
234 247
   #endif
235 248
 
249
+  #if HAS_Z4_MAX
250
+    #if ENABLED(ENDSTOPPULLUP_ZMAX)
251
+      SET_INPUT_PULLUP(Z4_MAX_PIN);
252
+    #elif ENABLED(ENDSTOPPULLDOWN_ZMAX)
253
+      SET_INPUT_PULLDOWN(Z4_MAX_PIN);
254
+    #else
255
+      SET_INPUT(Z4_MAX_PIN);
256
+    #endif
257
+  #endif
258
+
236 259
   #if HAS_CALIBRATION_PIN
237 260
     #if ENABLED(CALIBRATION_PIN_PULLUP)
238 261
       SET_INPUT_PULLUP(CALIBRATION_PIN);
@@ -435,6 +458,9 @@ void _O2 Endstops::report_states() {
435 458
   #if HAS_Z3_MIN
436 459
     ES_REPORT(Z3_MIN);
437 460
   #endif
461
+  #if HAS_Z4_MIN
462
+    ES_REPORT(Z4_MIN);
463
+  #endif
438 464
   #if HAS_Z_MAX
439 465
     ES_REPORT(Z_MAX);
440 466
   #endif
@@ -444,6 +470,9 @@ void _O2 Endstops::report_states() {
444 470
   #if HAS_Z3_MAX
445 471
     ES_REPORT(Z3_MAX);
446 472
   #endif
473
+  #if HAS_Z4_MAX
474
+    ES_REPORT(Z4_MAX);
475
+  #endif
447 476
   #if HAS_CUSTOM_PROBE_PIN
448 477
     print_es_state(READ(Z_MIN_PROBE_PIN) != Z_MIN_PROBE_ENDSTOP_INVERTING, PSTR(MSG_Z_PROBE));
449 478
   #endif
@@ -584,19 +613,26 @@ void Endstops::update() {
584 613
 
585 614
   #if HAS_Z_MIN && !Z_SPI_SENSORLESS
586 615
     UPDATE_ENDSTOP_BIT(Z, MIN);
587
-    #if Z_MULTI_ENDSTOPS
616
+    #if ENABLED(Z_MULTI_ENDSTOPS)
588 617
       #if HAS_Z2_MIN
589 618
         UPDATE_ENDSTOP_BIT(Z2, MIN);
590 619
       #else
591 620
         COPY_LIVE_STATE(Z_MIN, Z2_MIN);
592 621
       #endif
593
-      #if ENABLED(Z_TRIPLE_ENDSTOPS)
622
+      #if NUM_Z_STEPPER_DRIVERS >= 3
594 623
         #if HAS_Z3_MIN
595 624
           UPDATE_ENDSTOP_BIT(Z3, MIN);
596 625
         #else
597 626
           COPY_LIVE_STATE(Z_MIN, Z3_MIN);
598 627
         #endif
599 628
       #endif
629
+      #if NUM_Z_STEPPER_DRIVERS >= 4
630
+        #if HAS_Z4_MIN
631
+          UPDATE_ENDSTOP_BIT(Z4, MIN);
632
+        #else
633
+          COPY_LIVE_STATE(Z_MIN, Z4_MIN);
634
+        #endif
635
+      #endif
600 636
     #endif
601 637
   #endif
602 638
 
@@ -607,20 +643,27 @@ void Endstops::update() {
607 643
 
608 644
   #if HAS_Z_MAX && !Z_SPI_SENSORLESS
609 645
     // Check both Z dual endstops
610
-    #if Z_MULTI_ENDSTOPS
646
+    #if ENABLED(Z_MULTI_ENDSTOPS)
611 647
       UPDATE_ENDSTOP_BIT(Z, MAX);
612 648
       #if HAS_Z2_MAX
613 649
         UPDATE_ENDSTOP_BIT(Z2, MAX);
614 650
       #else
615 651
         COPY_LIVE_STATE(Z_MAX, Z2_MAX);
616 652
       #endif
617
-      #if ENABLED(Z_TRIPLE_ENDSTOPS)
653
+      #if NUM_Z_STEPPER_DRIVERS >= 3
618 654
         #if HAS_Z3_MAX
619 655
           UPDATE_ENDSTOP_BIT(Z3, MAX);
620 656
         #else
621 657
           COPY_LIVE_STATE(Z_MAX, Z3_MAX);
622 658
         #endif
623 659
       #endif
660
+      #if NUM_Z_STEPPER_DRIVERS >= 4
661
+        #if HAS_Z4_MAX
662
+          UPDATE_ENDSTOP_BIT(Z4, MAX);
663
+        #else
664
+          COPY_LIVE_STATE(Z_MAX, Z4_MAX);
665
+        #endif
666
+      #endif
624 667
     #elif !HAS_CUSTOM_PROBE_PIN || Z_MAX_PIN != Z_MIN_PROBE_PIN
625 668
       // If this pin isn't the bed probe it's the Z endstop
626 669
       UPDATE_ENDSTOP_BIT(Z, MAX);
@@ -686,6 +729,16 @@ void Endstops::update() {
686 729
     } \
687 730
   }while(0)
688 731
 
732
+  #define PROCESS_QUAD_ENDSTOP(AXIS1, AXIS2, AXIS3, AXIS4, MINMAX) do { \
733
+    const byte quad_hit = TEST_ENDSTOP(_ENDSTOP(AXIS1, MINMAX)) | (TEST_ENDSTOP(_ENDSTOP(AXIS2, MINMAX)) << 1) | (TEST_ENDSTOP(_ENDSTOP(AXIS3, MINMAX)) << 2) | (TEST_ENDSTOP(_ENDSTOP(AXIS4, MINMAX)) << 3); \
734
+    if (quad_hit) { \
735
+      _ENDSTOP_HIT(AXIS1, MINMAX); \
736
+      /* if not performing home or if both endstops were trigged during homing... */ \
737
+      if (!stepper.separate_multi_axis || quad_hit == 0b1111) \
738
+        planner.endstop_triggered(_AXIS(AXIS1)); \
739
+    } \
740
+  }while(0)
741
+
689 742
   #if ENABLED(G38_PROBE_TARGET) && PIN_EXISTS(Z_MIN_PROBE) && !(CORE_IS_XY || CORE_IS_XZ)
690 743
     #if ENABLED(G38_PROBE_AWAY)
691 744
       #define _G38_OPEN_STATE (G38_move >= 4)
@@ -747,10 +800,14 @@ void Endstops::update() {
747 800
   if (stepper.axis_is_moving(Z_AXIS)) {
748 801
     if (stepper.motor_direction(Z_AXIS_HEAD)) { // Z -direction. Gantry down, bed up.
749 802
       #if HAS_Z_MIN || (Z_SPI_SENSORLESS && Z_HOME_DIR < 0)
750
-        #if ENABLED(Z_TRIPLE_ENDSTOPS)
751
-          PROCESS_TRIPLE_ENDSTOP(Z, Z2, Z3, MIN);
752
-        #elif ENABLED(Z_DUAL_ENDSTOPS)
753
-          PROCESS_DUAL_ENDSTOP(Z, Z2, MIN);
803
+        #if ENABLED(Z_MULTI_ENDSTOPS)
804
+          #if NUM_Z_STEPPER_DRIVERS == 4
805
+            PROCESS_QUAD_ENDSTOP(Z, Z2, Z3, Z4, MIN);
806
+          #elif NUM_Z_STEPPER_DRIVERS == 3
807
+            PROCESS_TRIPLE_ENDSTOP(Z, Z2, Z3, MIN);
808
+          #else
809
+            PROCESS_DUAL_ENDSTOP(Z, Z2, MIN);
810
+          #endif
754 811
         #else
755 812
           #if ENABLED(Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN)
756 813
             if (z_probe_enabled) PROCESS_ENDSTOP(Z, MIN);
@@ -769,10 +826,14 @@ void Endstops::update() {
769 826
     }
770 827
     else { // Z +direction. Gantry up, bed down.
771 828
       #if HAS_Z_MAX || (Z_SPI_SENSORLESS && Z_HOME_DIR > 0)
772
-        #if ENABLED(Z_TRIPLE_ENDSTOPS)
773
-          PROCESS_TRIPLE_ENDSTOP(Z, Z2, Z3, MAX);
774
-        #elif ENABLED(Z_DUAL_ENDSTOPS)
775
-          PROCESS_DUAL_ENDSTOP(Z, Z2, MAX);
829
+        #if ENABLED(Z_MULTI_ENDSTOPS)
830
+          #if NUM_Z_STEPPER_DRIVERS == 4
831
+            PROCESS_QUAD_ENDSTOP(Z, Z2, Z3, Z4, MAX);
832
+          #elif NUM_Z_STEPPER_DRIVERS == 3
833
+            PROCESS_TRIPLE_ENDSTOP(Z, Z2, Z3, MAX);
834
+          #else
835
+            PROCESS_DUAL_ENDSTOP(Z, Z2, MAX);
836
+          #endif
776 837
         #elif !HAS_CUSTOM_PROBE_PIN || Z_MAX_PIN != Z_MIN_PROBE_PIN
777 838
           // If this pin is not hijacked for the bed probe
778 839
           // then it belongs to the Z endstop
@@ -892,6 +953,12 @@ void Endstops::update() {
892 953
     #if HAS_Z3_MAX
893 954
       ES_GET_STATE(Z3_MAX);
894 955
     #endif
956
+    #if HAS_Z4_MIN
957
+      ES_GET_STATE(Z4_MIN);
958
+    #endif
959
+    #if HAS_Z4_MAX
960
+      ES_GET_STATE(Z4_MAX);
961
+    #endif
895 962
 
896 963
     uint16_t endstop_change = live_state_local ^ old_live_state_local;
897 964
     #define ES_REPORT_CHANGE(S) if (TEST(endstop_change, S)) SERIAL_ECHOPAIR("  " STRINGIFY(S) ":", TEST(live_state_local, S))
@@ -942,6 +1009,12 @@ void Endstops::update() {
942 1009
       #if HAS_Z3_MAX
943 1010
         ES_REPORT_CHANGE(Z3_MAX);
944 1011
       #endif
1012
+      #if HAS_Z4_MIN
1013
+        ES_REPORT_CHANGE(Z4_MIN);
1014
+      #endif
1015
+      #if HAS_Z4_MAX
1016
+        ES_REPORT_CHANGE(Z4_MAX);
1017
+      #endif
945 1018
       SERIAL_ECHOLNPGM("\n");
946 1019
       analogWrite(pin_t(LED_PIN), local_LED_status);
947 1020
       local_LED_status ^= 255;

+ 7
- 3
Marlin/src/module/endstops.h View File

@@ -34,7 +34,8 @@ enum EndstopEnum : char {
34 34
   X2_MIN, X2_MAX,
35 35
   Y2_MIN, Y2_MAX,
36 36
   Z2_MIN, Z2_MAX,
37
-  Z3_MIN, Z3_MAX
37
+  Z3_MIN, Z3_MAX,
38
+  Z4_MIN, Z4_MAX
38 39
 };
39 40
 
40 41
 class Endstops {
@@ -47,12 +48,15 @@ class Endstops {
47 48
       #if ENABLED(Y_DUAL_ENDSTOPS)
48 49
         static float y2_endstop_adj;
49 50
       #endif
50
-      #if Z_MULTI_ENDSTOPS
51
+      #if ENABLED(Z_MULTI_ENDSTOPS)
51 52
         static float z2_endstop_adj;
52 53
       #endif
53
-      #if ENABLED(Z_TRIPLE_ENDSTOPS)
54
+      #if ENABLED(Z_MULTI_ENDSTOPS) && NUM_Z_STEPPER_DRIVERS >= 3
54 55
         static float z3_endstop_adj;
55 56
       #endif
57
+      #if ENABLED(Z_MULTI_ENDSTOPS) && NUM_Z_STEPPER_DRIVERS >= 4
58
+        static float z4_endstop_adj;
59
+      #endif
56 60
     #else
57 61
       typedef uint8_t esbits_t;
58 62
     #endif

+ 103
- 55
Marlin/src/module/motion.cpp View File

@@ -1156,6 +1156,9 @@ feedRate_t get_homing_bump_feedrate(const AxisEnum axis) {
1156 1156
           #if AXIS_HAS_STALLGUARD(Z3)
1157 1157
             stealth_states.z3 = tmc_enable_stallguard(stepperZ3);
1158 1158
           #endif
1159
+          #if AXIS_HAS_STALLGUARD(Z4)
1160
+            stealth_states.z4 = tmc_enable_stallguard(stepperZ4);
1161
+          #endif
1159 1162
           #if CORE_IS_XZ && X_SENSORLESS
1160 1163
             stealth_states.x = tmc_enable_stallguard(stepperX);
1161 1164
           #elif CORE_IS_YZ && Y_SENSORLESS
@@ -1225,6 +1228,9 @@ feedRate_t get_homing_bump_feedrate(const AxisEnum axis) {
1225 1228
           #if AXIS_HAS_STALLGUARD(Z3)
1226 1229
             tmc_disable_stallguard(stepperZ3, enable_stealth.z3);
1227 1230
           #endif
1231
+          #if AXIS_HAS_STALLGUARD(Z4)
1232
+            tmc_disable_stallguard(stepperZ4, enable_stealth.z4);
1233
+          #endif
1228 1234
           #if CORE_IS_XZ && X_SENSORLESS
1229 1235
             tmc_disable_stallguard(stepperX, enable_stealth.x);
1230 1236
           #elif CORE_IS_YZ && Y_SENSORLESS
@@ -1509,7 +1515,7 @@ void homeaxis(const AxisEnum axis) {
1509 1515
       #if ENABLED(Y_DUAL_ENDSTOPS)
1510 1516
         case Y_AXIS:
1511 1517
       #endif
1512
-      #if Z_MULTI_ENDSTOPS
1518
+      #if ENABLED(Z_MULTI_ENDSTOPS)
1513 1519
         case Z_AXIS:
1514 1520
       #endif
1515 1521
       stepper.set_separate_multi_axis(true);
@@ -1593,77 +1599,119 @@ void homeaxis(const AxisEnum axis) {
1593 1599
         }
1594 1600
       }
1595 1601
     #endif
1596
-    #if ENABLED(Z_DUAL_ENDSTOPS)
1602
+
1603
+    #if ENABLED(Z_MULTI_ENDSTOPS)
1597 1604
       if (axis == Z_AXIS) {
1598
-        const float adj = ABS(endstops.z2_endstop_adj);
1599
-        if (adj) {
1600
-          if (pos_dir ? (endstops.z2_endstop_adj > 0) : (endstops.z2_endstop_adj < 0)) stepper.set_z_lock(true); else stepper.set_z2_lock(true);
1601
-          do_homing_move(axis, pos_dir ? -adj : adj);
1605
+
1606
+        #if NUM_Z_STEPPER_DRIVERS == 2
1607
+
1608
+          const float adj = ABS(endstops.z2_endstop_adj);
1609
+          if (adj) {
1610
+            if (pos_dir ? (endstops.z2_endstop_adj > 0) : (endstops.z2_endstop_adj < 0)) stepper.set_z_lock(true); else stepper.set_z2_lock(true);
1611
+            do_homing_move(axis, pos_dir ? -adj : adj);
1612
+            stepper.set_z_lock(false);
1613
+            stepper.set_z2_lock(false);
1614
+          }
1615
+
1616
+        #else
1617
+
1618
+          // Handy arrays of stepper lock function pointers
1619
+
1620
+          typedef void (*adjustFunc_t)(const bool);
1621
+
1622
+          adjustFunc_t lock[] = {
1623
+            stepper.set_z_lock, stepper.set_z2_lock, stepper.set_z3_lock
1624
+            #if NUM_Z_STEPPER_DRIVERS >= 4
1625
+              , stepper.set_z4_lock
1626
+            #endif
1627
+          };
1628
+          float adj[] = {
1629
+            0, endstops.z2_endstop_adj, endstops.z3_endstop_adj
1630
+            #if NUM_Z_STEPPER_DRIVERS >= 4
1631
+              , endstops.z4_endstop_adj
1632
+            #endif
1633
+          };
1634
+
1635
+          adjustFunc_t tempLock;
1636
+          float tempAdj;
1637
+
1638
+          // Manual bubble sort by adjust value
1639
+          if (adj[1] < adj[0]) {
1640
+            tempLock = lock[0], tempAdj = adj[0];
1641
+            lock[0] = lock[1], adj[0] = adj[1];
1642
+            lock[1] = tempLock, adj[1] = tempAdj;
1643
+          }
1644
+          if (adj[2] < adj[1]) {
1645
+            tempLock = lock[1], tempAdj = adj[1];
1646
+            lock[1] = lock[2], adj[1] = adj[2];
1647
+            lock[2] = tempLock, adj[2] = tempAdj;
1648
+          }
1649
+          #if NUM_Z_STEPPER_DRIVERS >= 4
1650
+            if (adj[3] < adj[2]) {
1651
+              tempLock = lock[2], tempAdj = adj[2];
1652
+              lock[2] = lock[3], adj[2] = adj[3];
1653
+              lock[3] = tempLock, adj[3] = tempAdj;
1654
+            }
1655
+            if (adj[2] < adj[1]) {
1656
+              tempLock = lock[1], tempAdj = adj[1];
1657
+              lock[1] = lock[2], adj[1] = adj[2];
1658
+              lock[2] = tempLock, adj[2] = tempAdj;
1659
+            }
1660
+          #endif
1661
+          if (adj[1] < adj[0]) {
1662
+            tempLock = lock[0], tempAdj = adj[0];
1663
+            lock[0] = lock[1], adj[0] = adj[1];
1664
+            lock[1] = tempLock, adj[1] = tempAdj;
1665
+          }
1666
+
1667
+          if (pos_dir) {
1668
+            // normalize adj to smallest value and do the first move
1669
+            (*lock[0])(true);
1670
+            do_homing_move(axis, adj[1] - adj[0]);
1671
+            // lock the second stepper for the final correction
1672
+            (*lock[1])(true);
1673
+            do_homing_move(axis, adj[2] - adj[1]);
1674
+            #if NUM_Z_STEPPER_DRIVERS >= 4
1675
+              // lock the third stepper for the final correction
1676
+              (*lock[2])(true);
1677
+              do_homing_move(axis, adj[3] - adj[2]);
1678
+            #endif
1679
+          }
1680
+          else {
1681
+            #if NUM_Z_STEPPER_DRIVERS >= 4
1682
+              (*lock[3])(true);
1683
+              do_homing_move(axis, adj[2] - adj[3]);
1684
+            #endif
1685
+            (*lock[2])(true);
1686
+            do_homing_move(axis, adj[1] - adj[2]);
1687
+            (*lock[1])(true);
1688
+            do_homing_move(axis, adj[0] - adj[1]);
1689
+          }
1690
+
1602 1691
           stepper.set_z_lock(false);
1603 1692
           stepper.set_z2_lock(false);
1604
-        }
1605
-      }
1606
-    #endif
1607
-    #if ENABLED(Z_TRIPLE_ENDSTOPS)
1608
-      if (axis == Z_AXIS) {
1609
-        // we push the function pointers for the stepper lock function into an array
1610
-        void (*lock[3]) (bool)= {&stepper.set_z_lock, &stepper.set_z2_lock, &stepper.set_z3_lock};
1611
-        float adj[3] = {0, endstops.z2_endstop_adj, endstops.z3_endstop_adj};
1612
-
1613
-        void (*tempLock) (bool);
1614
-        float tempAdj;
1615
-
1616
-        // manual bubble sort by adjust value
1617
-        if (adj[1] < adj[0]) {
1618
-          tempLock = lock[0], tempAdj = adj[0];
1619
-          lock[0] = lock[1], adj[0] = adj[1];
1620
-          lock[1] = tempLock, adj[1] = tempAdj;
1621
-        }
1622
-        if (adj[2] < adj[1]) {
1623
-          tempLock = lock[1], tempAdj = adj[1];
1624
-          lock[1] = lock[2], adj[1] = adj[2];
1625
-          lock[2] = tempLock, adj[2] = tempAdj;
1626
-        }
1627
-        if (adj[1] < adj[0]) {
1628
-          tempLock = lock[0], tempAdj = adj[0];
1629
-          lock[0] = lock[1], adj[0] = adj[1];
1630
-          lock[1] = tempLock, adj[1] = tempAdj;
1631
-        }
1632
-
1633
-        if (pos_dir) {
1634
-          // normalize adj to smallest value and do the first move
1635
-          (*lock[0])(true);
1636
-          do_homing_move(axis, adj[1] - adj[0]);
1637
-          // lock the second stepper for the final correction
1638
-          (*lock[1])(true);
1639
-          do_homing_move(axis, adj[2] - adj[1]);
1640
-        }
1641
-        else {
1642
-          (*lock[2])(true);
1643
-          do_homing_move(axis, adj[1] - adj[2]);
1644
-          (*lock[1])(true);
1645
-          do_homing_move(axis, adj[0] - adj[1]);
1646
-        }
1693
+          stepper.set_z3_lock(false);
1694
+          #if NUM_Z_STEPPER_DRIVERS >= 4
1695
+            stepper.set_z4_lock(false);
1696
+          #endif
1647 1697
 
1648
-        stepper.set_z_lock(false);
1649
-        stepper.set_z2_lock(false);
1650
-        stepper.set_z3_lock(false);
1698
+        #endif
1651 1699
       }
1652 1700
     #endif
1653 1701
 
1654 1702
     // Reset flags for X, Y, Z motor locking
1655 1703
     switch (axis) {
1704
+      default: break;
1656 1705
       #if ENABLED(X_DUAL_ENDSTOPS)
1657 1706
         case X_AXIS:
1658 1707
       #endif
1659 1708
       #if ENABLED(Y_DUAL_ENDSTOPS)
1660 1709
         case Y_AXIS:
1661 1710
       #endif
1662
-      #if Z_MULTI_ENDSTOPS
1711
+      #if ENABLED(Z_MULTI_ENDSTOPS)
1663 1712
         case Z_AXIS:
1664 1713
       #endif
1665
-      stepper.set_separate_multi_axis(false);
1666
-      default: break;
1714
+          stepper.set_separate_multi_axis(false);
1667 1715
     }
1668 1716
   #endif
1669 1717
 

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

@@ -156,11 +156,16 @@ bool Stepper::abort_current_block;
156 156
 #if ENABLED(Y_DUAL_ENDSTOPS)
157 157
   bool Stepper::locked_Y_motor = false, Stepper::locked_Y2_motor = false;
158 158
 #endif
159
-#if Z_MULTI_ENDSTOPS || ENABLED(Z_STEPPER_AUTO_ALIGN)
160
-  bool Stepper::locked_Z_motor = false, Stepper::locked_Z2_motor = false;
161
-#endif
162
-#if ENABLED(Z_TRIPLE_ENDSTOPS) || BOTH(Z_STEPPER_AUTO_ALIGN, Z_TRIPLE_STEPPER_DRIVERS)
163
-  bool Stepper::locked_Z3_motor = false;
159
+
160
+#if EITHER(Z_MULTI_ENDSTOPS, Z_STEPPER_AUTO_ALIGN)
161
+  bool Stepper::locked_Z_motor = false, Stepper::locked_Z2_motor = false
162
+       #if NUM_Z_STEPPER_DRIVERS >= 3
163
+         , Stepper::locked_Z3_motor = false
164
+         #if NUM_Z_STEPPER_DRIVERS >= 4
165
+           , Stepper::locked_Z4_motor = false
166
+         #endif
167
+       #endif
168
+       ;
164 169
 #endif
165 170
 
166 171
 uint32_t Stepper::acceleration_time, Stepper::deceleration_time;
@@ -281,6 +286,42 @@ xyze_int8_t Stepper::count_direction{0};
281 286
     A##3_STEP_WRITE(V);                           \
282 287
   }
283 288
 
289
+#define QUAD_ENDSTOP_APPLY_STEP(A,V)                                                                                        \
290
+  if (separate_multi_axis) {                                                                                                \
291
+    if (A##_HOME_DIR < 0) {                                                                                                 \
292
+      if (!(TEST(endstops.state(), A##_MIN) && count_direction[_AXIS(A)] < 0) && !locked_##A##_motor) A##_STEP_WRITE(V);    \
293
+      if (!(TEST(endstops.state(), A##2_MIN) && count_direction[_AXIS(A)] < 0) && !locked_##A##2_motor) A##2_STEP_WRITE(V); \
294
+      if (!(TEST(endstops.state(), A##3_MIN) && count_direction[_AXIS(A)] < 0) && !locked_##A##3_motor) A##3_STEP_WRITE(V); \
295
+      if (!(TEST(endstops.state(), A##4_MIN) && count_direction[_AXIS(A)] < 0) && !locked_##A##4_motor) A##4_STEP_WRITE(V); \
296
+    }                                                                                                                       \
297
+    else {                                                                                                                  \
298
+      if (!(TEST(endstops.state(), A##_MAX) && count_direction[_AXIS(A)] > 0) && !locked_##A##_motor) A##_STEP_WRITE(V);    \
299
+      if (!(TEST(endstops.state(), A##2_MAX) && count_direction[_AXIS(A)] > 0) && !locked_##A##2_motor) A##2_STEP_WRITE(V); \
300
+      if (!(TEST(endstops.state(), A##3_MAX) && count_direction[_AXIS(A)] > 0) && !locked_##A##3_motor) A##3_STEP_WRITE(V); \
301
+      if (!(TEST(endstops.state(), A##4_MAX) && count_direction[_AXIS(A)] > 0) && !locked_##A##4_motor) A##4_STEP_WRITE(V); \
302
+    }                                                                                                                       \
303
+  }                                                                                                                         \
304
+  else {                                                                                                                    \
305
+    A##_STEP_WRITE(V);                                                                                                      \
306
+    A##2_STEP_WRITE(V);                                                                                                     \
307
+    A##3_STEP_WRITE(V);                                                                                                     \
308
+    A##4_STEP_WRITE(V);                                                                                                     \
309
+  }
310
+
311
+#define QUAD_SEPARATE_APPLY_STEP(A,V)             \
312
+  if (separate_multi_axis) {                      \
313
+    if (!locked_##A##_motor) A##_STEP_WRITE(V);   \
314
+    if (!locked_##A##2_motor) A##2_STEP_WRITE(V); \
315
+    if (!locked_##A##3_motor) A##3_STEP_WRITE(V); \
316
+    if (!locked_##A##4_motor) A##4_STEP_WRITE(V); \
317
+  }                                               \
318
+  else {                                          \
319
+    A##_STEP_WRITE(V);                            \
320
+    A##2_STEP_WRITE(V);                           \
321
+    A##3_STEP_WRITE(V);                           \
322
+    A##4_STEP_WRITE(V);                           \
323
+  }
324
+
284 325
 #if ENABLED(X_DUAL_STEPPER_DRIVERS)
285 326
   #define X_APPLY_DIR(v,Q) do{ X_DIR_WRITE(v); X2_DIR_WRITE((v) != INVERT_X2_VS_X_DIR); }while(0)
286 327
   #if ENABLED(X_DUAL_ENDSTOPS)
@@ -314,18 +355,27 @@ xyze_int8_t Stepper::count_direction{0};
314 355
   #define Y_APPLY_STEP(v,Q) Y_STEP_WRITE(v)
315 356
 #endif
316 357
 
317
-#if ENABLED(Z_TRIPLE_STEPPER_DRIVERS)
358
+#if NUM_Z_STEPPER_DRIVERS == 4
359
+  #define Z_APPLY_DIR(v,Q) do{ Z_DIR_WRITE(v); Z2_DIR_WRITE(v); Z3_DIR_WRITE(v); Z4_DIR_WRITE(v); }while(0)
360
+  #if ENABLED(Z_MULTI_ENDSTOPS)
361
+    #define Z_APPLY_STEP(v,Q) QUAD_ENDSTOP_APPLY_STEP(Z,v)
362
+  #elif ENABLED(Z_STEPPER_AUTO_ALIGN)
363
+    #define Z_APPLY_STEP(v,Q) QUAD_SEPARATE_APPLY_STEP(Z,v)
364
+  #else
365
+    #define Z_APPLY_STEP(v,Q) do{ Z_STEP_WRITE(v); Z2_STEP_WRITE(v); Z3_STEP_WRITE(v); Z4_STEP_WRITE(v); }while(0)
366
+  #endif
367
+#elif NUM_Z_STEPPER_DRIVERS == 3
318 368
   #define Z_APPLY_DIR(v,Q) do{ Z_DIR_WRITE(v); Z2_DIR_WRITE(v); Z3_DIR_WRITE(v); }while(0)
319
-  #if ENABLED(Z_TRIPLE_ENDSTOPS)
369
+  #if ENABLED(Z_MULTI_ENDSTOPS)
320 370
     #define Z_APPLY_STEP(v,Q) TRIPLE_ENDSTOP_APPLY_STEP(Z,v)
321 371
   #elif ENABLED(Z_STEPPER_AUTO_ALIGN)
322 372
     #define Z_APPLY_STEP(v,Q) TRIPLE_SEPARATE_APPLY_STEP(Z,v)
323 373
   #else
324 374
     #define Z_APPLY_STEP(v,Q) do{ Z_STEP_WRITE(v); Z2_STEP_WRITE(v); Z3_STEP_WRITE(v); }while(0)
325 375
   #endif
326
-#elif ENABLED(Z_DUAL_STEPPER_DRIVERS)
376
+#elif NUM_Z_STEPPER_DRIVERS == 2
327 377
   #define Z_APPLY_DIR(v,Q) do{ Z_DIR_WRITE(v); Z2_DIR_WRITE(v); }while(0)
328
-  #if ENABLED(Z_DUAL_ENDSTOPS)
378
+  #if ENABLED(Z_MULTI_ENDSTOPS)
329 379
     #define Z_APPLY_STEP(v,Q) DUAL_ENDSTOP_APPLY_STEP(Z,v)
330 380
   #elif ENABLED(Z_STEPPER_AUTO_ALIGN)
331 381
     #define Z_APPLY_STEP(v,Q) DUAL_SEPARATE_APPLY_STEP(Z,v)
@@ -2062,12 +2112,15 @@ void Stepper::init() {
2062 2112
   #endif
2063 2113
   #if HAS_Z_DIR
2064 2114
     Z_DIR_INIT();
2065
-    #if Z_MULTI_STEPPER_DRIVERS && HAS_Z2_DIR
2115
+    #if NUM_Z_STEPPER_DRIVERS >= 2 && HAS_Z2_DIR
2066 2116
       Z2_DIR_INIT();
2067 2117
     #endif
2068
-    #if ENABLED(Z_TRIPLE_STEPPER_DRIVERS) && HAS_Z3_DIR
2118
+    #if NUM_Z_STEPPER_DRIVERS >= 3 && HAS_Z3_DIR
2069 2119
       Z3_DIR_INIT();
2070 2120
     #endif
2121
+    #if NUM_Z_STEPPER_DRIVERS >= 4 && HAS_Z4_DIR
2122
+      Z4_DIR_INIT();
2123
+    #endif
2071 2124
   #endif
2072 2125
   #if HAS_E0_DIR
2073 2126
     E0_DIR_INIT();
@@ -2108,14 +2161,18 @@ void Stepper::init() {
2108 2161
   #if HAS_Z_ENABLE
2109 2162
     Z_ENABLE_INIT();
2110 2163
     if (!Z_ENABLE_ON) Z_ENABLE_WRITE(HIGH);
2111
-    #if Z_MULTI_STEPPER_DRIVERS && HAS_Z2_ENABLE
2164
+    #if NUM_Z_STEPPER_DRIVERS >= 2 && HAS_Z2_ENABLE
2112 2165
       Z2_ENABLE_INIT();
2113 2166
       if (!Z_ENABLE_ON) Z2_ENABLE_WRITE(HIGH);
2114 2167
     #endif
2115
-    #if ENABLED(Z_TRIPLE_STEPPER_DRIVERS) && HAS_Z3_ENABLE
2168
+    #if NUM_Z_STEPPER_DRIVERS >= 3 && HAS_Z3_ENABLE
2116 2169
       Z3_ENABLE_INIT();
2117 2170
       if (!Z_ENABLE_ON) Z3_ENABLE_WRITE(HIGH);
2118 2171
     #endif
2172
+    #if NUM_Z_STEPPER_DRIVERS >= 4 && HAS_Z4_ENABLE
2173
+      Z4_ENABLE_INIT();
2174
+      if (!Z_ENABLE_ON) Z4_ENABLE_WRITE(HIGH);
2175
+    #endif
2119 2176
   #endif
2120 2177
   #if HAS_E0_ENABLE
2121 2178
     E0_ENABLE_INIT();
@@ -2171,14 +2228,18 @@ void Stepper::init() {
2171 2228
   #endif
2172 2229
 
2173 2230
   #if HAS_Z_STEP
2174
-    #if Z_MULTI_STEPPER_DRIVERS
2231
+    #if NUM_Z_STEPPER_DRIVERS >= 2
2175 2232
       Z2_STEP_INIT();
2176 2233
       Z2_STEP_WRITE(INVERT_Z_STEP_PIN);
2177 2234
     #endif
2178
-    #if ENABLED(Z_TRIPLE_STEPPER_DRIVERS)
2235
+    #if NUM_Z_STEPPER_DRIVERS >= 3
2179 2236
       Z3_STEP_INIT();
2180 2237
       Z3_STEP_WRITE(INVERT_Z_STEP_PIN);
2181 2238
     #endif
2239
+    #if NUM_Z_STEPPER_DRIVERS >= 4
2240
+      Z4_STEP_INIT();
2241
+      Z4_STEP_WRITE(INVERT_Z_STEP_PIN);
2242
+    #endif
2182 2243
     AXIS_INIT(Z, Z);
2183 2244
   #endif
2184 2245
 
@@ -2692,6 +2753,13 @@ void Stepper::report_positions() {
2692 2753
         SET_OUTPUT(Z3_MS3_PIN);
2693 2754
       #endif
2694 2755
     #endif
2756
+    #if HAS_Z4_MICROSTEPS
2757
+      SET_OUTPUT(Z4_MS1_PIN);
2758
+      SET_OUTPUT(Z4_MS2_PIN);
2759
+      #if PIN_EXISTS(Z4_MS3)
2760
+        SET_OUTPUT(Z4_MS3_PIN);
2761
+      #endif
2762
+    #endif
2695 2763
     #if HAS_E0_MICROSTEPS
2696 2764
       SET_OUTPUT(E0_MS1_PIN);
2697 2765
       SET_OUTPUT(E0_MS2_PIN);
@@ -2762,7 +2830,7 @@ void Stepper::report_positions() {
2762 2830
           #endif
2763 2831
           break;
2764 2832
       #endif
2765
-      #if HAS_Z_MICROSTEPS || HAS_Z2_MICROSTEPS || HAS_Z3_MICROSTEPS
2833
+      #if HAS_SOME_Z_MICROSTEPS
2766 2834
         case 2:
2767 2835
           #if HAS_Z_MICROSTEPS
2768 2836
             WRITE(Z_MS1_PIN, ms1);
@@ -2773,6 +2841,9 @@ void Stepper::report_positions() {
2773 2841
           #if HAS_Z3_MICROSTEPS
2774 2842
             WRITE(Z3_MS1_PIN, ms1);
2775 2843
           #endif
2844
+          #if HAS_Z4_MICROSTEPS
2845
+            WRITE(Z4_MS1_PIN, ms1);
2846
+          #endif
2776 2847
           break;
2777 2848
       #endif
2778 2849
       #if HAS_E0_MICROSTEPS
@@ -2815,7 +2886,7 @@ void Stepper::report_positions() {
2815 2886
           #endif
2816 2887
           break;
2817 2888
       #endif
2818
-      #if HAS_Z_MICROSTEPS || HAS_Z2_MICROSTEPS || HAS_Z3_MICROSTEPS
2889
+      #if HAS_SOME_Z_MICROSTEPS
2819 2890
         case 2:
2820 2891
           #if HAS_Z_MICROSTEPS
2821 2892
             WRITE(Z_MS2_PIN, ms2);
@@ -2826,6 +2897,9 @@ void Stepper::report_positions() {
2826 2897
           #if HAS_Z3_MICROSTEPS
2827 2898
             WRITE(Z3_MS2_PIN, ms2);
2828 2899
           #endif
2900
+          #if HAS_Z4_MICROSTEPS
2901
+            WRITE(Z4_MS2_PIN, ms2);
2902
+          #endif
2829 2903
           break;
2830 2904
       #endif
2831 2905
       #if HAS_E0_MICROSTEPS
@@ -2868,7 +2942,7 @@ void Stepper::report_positions() {
2868 2942
           #endif
2869 2943
           break;
2870 2944
       #endif
2871
-      #if HAS_Z_MICROSTEPS || HAS_Z2_MICROSTEPS || HAS_Z3_MICROSTEPS
2945
+      #if HAS_SOME_Z_MICROSTEPS
2872 2946
         case 2:
2873 2947
           #if HAS_Z_MICROSTEPS && PIN_EXISTS(Z_MS3)
2874 2948
             WRITE(Z_MS3_PIN, ms3);
@@ -2879,6 +2953,9 @@ void Stepper::report_positions() {
2879 2953
           #if HAS_Z3_MICROSTEPS && PIN_EXISTS(Z3_MS3)
2880 2954
             WRITE(Z3_MS3_PIN, ms3);
2881 2955
           #endif
2956
+          #if HAS_Z4_MICROSTEPS && PIN_EXISTS(Z4_MS3)
2957
+            WRITE(Z4_MS3_PIN, ms3);
2958
+          #endif
2882 2959
           break;
2883 2960
       #endif
2884 2961
       #if HAS_E0_MICROSTEPS && PIN_EXISTS(E0_MS3)

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

@@ -274,11 +274,15 @@ class Stepper {
274 274
     #if ENABLED(Y_DUAL_ENDSTOPS)
275 275
       static bool locked_Y_motor, locked_Y2_motor;
276 276
     #endif
277
-    #if Z_MULTI_ENDSTOPS || ENABLED(Z_STEPPER_AUTO_ALIGN)
278
-      static bool locked_Z_motor, locked_Z2_motor;
279
-    #endif
280
-    #if ENABLED(Z_TRIPLE_ENDSTOPS) || BOTH(Z_STEPPER_AUTO_ALIGN, Z_TRIPLE_STEPPER_DRIVERS)
281
-      static bool locked_Z3_motor;
277
+    #if EITHER(Z_MULTI_ENDSTOPS, Z_STEPPER_AUTO_ALIGN)
278
+      static bool locked_Z_motor, locked_Z2_motor
279
+                  #if NUM_Z_STEPPER_DRIVERS >= 3
280
+                    , locked_Z3_motor
281
+                    #if NUM_Z_STEPPER_DRIVERS >= 4
282
+                      , locked_Z4_motor
283
+                    #endif
284
+                  #endif
285
+                  ;
282 286
     #endif
283 287
 
284 288
     static uint32_t acceleration_time, deceleration_time; // time measured in Stepper Timer ticks
@@ -430,12 +434,15 @@ class Stepper {
430 434
       FORCE_INLINE static void set_y_lock(const bool state) { locked_Y_motor = state; }
431 435
       FORCE_INLINE static void set_y2_lock(const bool state) { locked_Y2_motor = state; }
432 436
     #endif
433
-    #if Z_MULTI_ENDSTOPS || (ENABLED(Z_STEPPER_AUTO_ALIGN) && Z_MULTI_STEPPER_DRIVERS)
437
+    #if EITHER(Z_MULTI_ENDSTOPS, Z_STEPPER_AUTO_ALIGN)
434 438
       FORCE_INLINE static void set_z_lock(const bool state) { locked_Z_motor = state; }
435 439
       FORCE_INLINE static void set_z2_lock(const bool state) { locked_Z2_motor = state; }
436
-    #endif
437
-    #if ENABLED(Z_TRIPLE_ENDSTOPS) || BOTH(Z_STEPPER_AUTO_ALIGN, Z_TRIPLE_STEPPER_DRIVERS)
438
-      FORCE_INLINE static void set_z3_lock(const bool state) { locked_Z3_motor = state; }
440
+      #if NUM_Z_STEPPER_DRIVERS >= 3
441
+        FORCE_INLINE static void set_z3_lock(const bool state) { locked_Z3_motor = state; }
442
+        #if NUM_Z_STEPPER_DRIVERS >= 4
443
+          FORCE_INLINE static void set_z4_lock(const bool state) { locked_Z4_motor = state; }
444
+        #endif
445
+      #endif
439 446
     #endif
440 447
 
441 448
     #if ENABLED(BABYSTEPPING)

+ 3
- 0
Marlin/src/module/stepper/L64xx.cpp View File

@@ -52,6 +52,9 @@
52 52
 #if AXIS_IS_L64XX(Z3)
53 53
   L64XX_CLASS(Z3) stepperZ3(L6470_CHAIN_SS_PIN);
54 54
 #endif
55
+#if AXIS_IS_L64XX(Z4)
56
+  L64XX_CLASS(Z4) stepperZ4(L6470_CHAIN_SS_PIN);
57
+#endif
55 58
 #if AXIS_IS_L64XX(E0)
56 59
   L64XX_CLASS(E0) stepperE0(L6470_CHAIN_SS_PIN);
57 60
 #endif

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

@@ -160,6 +160,23 @@
160 160
   #endif
161 161
 #endif
162 162
 
163
+// Z4 Stepper
164
+#if HAS_Z4_ENABLE && AXIS_IS_L64XX(Z4)
165
+  extern L64XX_CLASS(Z4)         stepperZ4;
166
+  #define Z4_ENABLE_INIT()       NOOP
167
+  #define Z4_ENABLE_WRITE(STATE) (STATE ? NOOP : stepperZ4.free())
168
+  #define Z4_ENABLE_READ()       (stepperZ4.getStatus() & STATUS_HIZ)
169
+  #if AXIS_DRIVER_TYPE_Z4(L6474)
170
+    #define Z4_DIR_INIT()        SET_OUTPUT(Z4_DIR_PIN)
171
+    #define Z4_DIR_WRITE(STATE)  L6474_DIR_WRITE(Z4, STATE)
172
+    #define Z4_DIR_READ()        READ(Z4_DIR_PIN)
173
+  #else
174
+    #define Z4_DIR_INIT()        NOOP
175
+    #define Z4_DIR_WRITE(STATE)  L64XX_DIR_WRITE(Z4, STATE)
176
+    #define Z4_DIR_READ()        (stepper##Z4.getStatus() & STATUS_DIR);
177
+  #endif
178
+#endif
179
+
163 180
 // E0 Stepper
164 181
 #if AXIS_IS_L64XX(E0)
165 182
   extern L64XX_CLASS(E0)         stepperE0;

+ 6
- 0
Marlin/src/module/stepper/TMC26X.cpp View File

@@ -57,6 +57,9 @@
57 57
 #if AXIS_DRIVER_TYPE_Z3(TMC26X)
58 58
   _TMC26X_DEFINE(Z3);
59 59
 #endif
60
+#if AXIS_DRIVER_TYPE_Z4(TMC26X)
61
+  _TMC26X_DEFINE(Z4);
62
+#endif
60 63
 #if AXIS_DRIVER_TYPE_E0(TMC26X)
61 64
   _TMC26X_DEFINE(E0);
62 65
 #endif
@@ -103,6 +106,9 @@ void tmc26x_init_to_defaults() {
103 106
   #if AXIS_DRIVER_TYPE_Z3(TMC26X)
104 107
     _TMC26X_INIT(Z3);
105 108
   #endif
109
+  #if AXIS_DRIVER_TYPE_Z4(TMC26X)
110
+    _TMC26X_INIT(Z4);
111
+  #endif
106 112
   #if AXIS_DRIVER_TYPE_E0(TMC26X)
107 113
     _TMC26X_INIT(E0);
108 114
   #endif

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

@@ -95,6 +95,14 @@ void tmc26x_init_to_defaults();
95 95
   #define Z3_ENABLE_READ() stepperZ3.isEnabled()
96 96
 #endif
97 97
 
98
+// Z4 Stepper
99
+#if HAS_Z4_ENABLE && AXIS_DRIVER_TYPE_Z4(TMC26X)
100
+  extern TMC26XStepper stepperZ4;
101
+  #define Z4_ENABLE_INIT() NOOP
102
+  #define Z4_ENABLE_WRITE(STATE) stepperZ4.setEnabled(STATE)
103
+  #define Z4_ENABLE_READ() stepperZ4.isEnabled()
104
+#endif
105
+
98 106
 // E0 Stepper
99 107
 #if AXIS_DRIVER_TYPE_E0(TMC26X)
100 108
   extern TMC26XStepper stepperE0;

+ 35
- 2
Marlin/src/module/stepper/indirection.h View File

@@ -180,6 +180,27 @@ void reset_stepper_drivers();    // Called by settings.load / settings.reset
180 180
   #define Z3_DIR_WRITE(STATE) NOOP
181 181
 #endif
182 182
 
183
+// Z4 Stepper
184
+#if HAS_Z4_ENABLE
185
+  #ifndef Z4_ENABLE_INIT
186
+    #define Z4_ENABLE_INIT() SET_OUTPUT(Z4_ENABLE_PIN)
187
+    #define Z4_ENABLE_WRITE(STATE) WRITE(Z4_ENABLE_PIN,STATE)
188
+    #define Z4_ENABLE_READ() READ(Z4_ENABLE_PIN)
189
+  #endif
190
+  #ifndef Z4_DIR_INIT
191
+    #define Z4_DIR_INIT() SET_OUTPUT(Z4_DIR_PIN)
192
+    #define Z4_DIR_WRITE(STATE) WRITE(Z4_DIR_PIN,STATE)
193
+    #define Z4_DIR_READ() READ(Z4_DIR_PIN)
194
+  #endif
195
+  #define Z4_STEP_INIT SET_OUTPUT(Z4_STEP_PIN)
196
+  #ifndef Z4_STEP_WRITE
197
+    #define Z4_STEP_WRITE(STATE) WRITE(Z4_STEP_PIN,STATE)
198
+  #endif
199
+  #define Z4_STEP_READ READ(Z4_STEP_PIN)
200
+#else
201
+  #define Z4_DIR_WRITE(STATE) NOOP
202
+#endif
203
+
183 204
 // E0 Stepper
184 205
 #ifndef E0_ENABLE_INIT
185 206
   #define E0_ENABLE_INIT() SET_OUTPUT(E0_ENABLE_PIN)
@@ -491,8 +512,20 @@ void reset_stepper_drivers();    // Called by settings.load / settings.reset
491 512
   #define Z3_disable() NOOP
492 513
 #endif
493 514
 
494
-#define  enable_Z() do{ Z_enable();  Z2_enable();  Z3_enable();  }while(0)
495
-#define disable_Z() do{ Z_disable(); Z2_disable(); Z3_disable(); CBI(axis_known_position, Z_AXIS); }while(0)
515
+#if AXIS_DRIVER_TYPE_Z4(L6470)
516
+  extern L6470 stepperZ4;
517
+  #define Z4_enable()  NOOP
518
+  #define Z4_disable() stepperZ4.free()
519
+#elif HAS_Z4_ENABLE
520
+  #define Z4_enable()  Z4_ENABLE_WRITE( Z_ENABLE_ON)
521
+  #define Z4_disable() Z4_ENABLE_WRITE(!Z_ENABLE_ON)
522
+#else
523
+  #define Z4_enable()  NOOP
524
+  #define Z4_disable() NOOP
525
+#endif
526
+
527
+#define  enable_Z() do{ Z_enable();  Z2_enable();  Z3_enable();  Z4_enable(); }while(0)
528
+#define disable_Z() do{ Z_disable(); Z2_disable(); Z3_disable(); Z4_disable(); CBI(axis_known_position, Z_AXIS); }while(0)
496 529
 
497 530
 //
498 531
 // Extruder Stepper enable / disable

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

@@ -88,6 +88,9 @@ enum StealthIndex : uint8_t { STEALTH_AXIS_XY, STEALTH_AXIS_Z, STEALTH_AXIS_E };
88 88
 #if AXIS_HAS_SPI(Z3)
89 89
   TMC_SPI_DEFINE(Z3, Z);
90 90
 #endif
91
+#if AXIS_HAS_SPI(Z4)
92
+  TMC_SPI_DEFINE(Z4, Z);
93
+#endif
91 94
 #if AXIS_HAS_SPI(E0)
92 95
   TMC_SPI_DEFINE_E(0);
93 96
 #endif
@@ -249,6 +252,13 @@ enum StealthIndex : uint8_t { STEALTH_AXIS_XY, STEALTH_AXIS_Z, STEALTH_AXIS_E };
249 252
       TMC_UART_DEFINE(SW, Z3, Z);
250 253
     #endif
251 254
   #endif
255
+  #if AXIS_HAS_UART(Z4)
256
+    #ifdef Z4_HARDWARE_SERIAL
257
+      TMC_UART_DEFINE(HW, Z4, Z);
258
+    #else
259
+      TMC_UART_DEFINE(SW, Z4, Z);
260
+    #endif
261
+  #endif
252 262
   #if AXIS_HAS_UART(E0)
253 263
     #ifdef E0_HARDWARE_SERIAL
254 264
       TMC_UART_DEFINE_E(HW, 0);
@@ -342,6 +352,13 @@ enum StealthIndex : uint8_t { STEALTH_AXIS_XY, STEALTH_AXIS_Z, STEALTH_AXIS_E };
342 352
         stepperZ3.beginSerial(TMC_BAUD_RATE);
343 353
       #endif
344 354
     #endif
355
+    #if AXIS_HAS_UART(Z4)
356
+      #ifdef Z4_HARDWARE_SERIAL
357
+        Z4_HARDWARE_SERIAL.begin(TMC_BAUD_RATE);
358
+      #else
359
+        stepperZ4.beginSerial(TMC_BAUD_RATE);
360
+      #endif
361
+    #endif
345 362
     #if AXIS_HAS_UART(E0)
346 363
       #ifdef E0_HARDWARE_SERIAL
347 364
         E0_HARDWARE_SERIAL.begin(TMC_BAUD_RATE);
@@ -616,6 +633,9 @@ void restore_trinamic_drivers() {
616 633
   #if AXIS_IS_TMC(Z3)
617 634
     stepperZ3.push();
618 635
   #endif
636
+  #if AXIS_IS_TMC(Z4)
637
+    stepperZ4.push();
638
+  #endif
619 639
   #if AXIS_IS_TMC(E0)
620 640
     stepperE0.push();
621 641
   #endif
@@ -678,6 +698,9 @@ void reset_trinamic_drivers() {
678 698
   #if AXIS_IS_TMC(Z3)
679 699
     _TMC_INIT(Z3, STEALTH_AXIS_Z);
680 700
   #endif
701
+  #if AXIS_IS_TMC(Z4)
702
+    _TMC_INIT(Z4, STEALTH_AXIS_Z);
703
+  #endif
681 704
   #if AXIS_IS_TMC(E0)
682 705
     _TMC_INIT(E0, STEALTH_AXIS_E);
683 706
   #endif
@@ -727,6 +750,9 @@ void reset_trinamic_drivers() {
727 750
       #if AXIS_HAS_STALLGUARD(Z3)
728 751
         stepperZ3.homing_threshold(Z_STALL_SENSITIVITY);
729 752
       #endif
753
+      #if AXIS_HAS_STALLGUARD(Z4)
754
+        stepperZ4.homing_threshold(Z_STALL_SENSITIVITY);
755
+      #endif
730 756
     #endif
731 757
   #endif
732 758
 

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

@@ -50,6 +50,7 @@
50 50
 #define TMC_Y2_LABEL 'Y', '2'
51 51
 #define TMC_Z2_LABEL 'Z', '2'
52 52
 #define TMC_Z3_LABEL 'Z', '3'
53
+#define TMC_Z4_LABEL 'Z', '4'
53 54
 
54 55
 #define TMC_E0_LABEL 'E', '0'
55 56
 #define TMC_E1_LABEL 'E', '1'
@@ -175,6 +176,19 @@ void reset_trinamic_drivers();
175 176
   #endif
176 177
 #endif
177 178
 
179
+// Z4 Stepper
180
+#if HAS_Z4_ENABLE && AXIS_IS_TMC(Z4)
181
+  extern TMC_CLASS(Z4, Z) stepperZ4;
182
+  #if ENABLED(SOFTWARE_DRIVER_ENABLE)
183
+    #define Z4_ENABLE_INIT() NOOP
184
+    #define Z4_ENABLE_WRITE(STATE) stepperZ4.toff((STATE)==Z_ENABLE_ON ? chopper_timing.toff : 0)
185
+    #define Z4_ENABLE_READ() stepperZ4.isEnabled()
186
+  #endif
187
+  #if AXIS_HAS_SQUARE_WAVE(Z4)
188
+    #define Z4_STEP_WRITE(STATE) do{ if(STATE) TOGGLE(Z4_STEP_PIN); }while(0)
189
+  #endif
190
+#endif
191
+
178 192
 // E0 Stepper
179 193
 #if AXIS_IS_TMC(E0)
180 194
   extern TMC_CLASS_E(0) stepperE0;

+ 49
- 2
Marlin/src/pins/pins.h View File

@@ -1153,7 +1153,7 @@
1153 1153
 #endif
1154 1154
 
1155 1155
 // The Z2 axis, if any, should be the next open extruder port
1156
-#if Z_MULTI_STEPPER_DRIVERS
1156
+#if NUM_Z_STEPPER_DRIVERS >= 2
1157 1157
   #ifndef Z2_STEP_PIN
1158 1158
     #define Z2_STEP_PIN   _EPIN(Z2_E_INDEX, STEP)
1159 1159
     #define Z2_DIR_PIN    _EPIN(Z2_E_INDEX, DIR)
@@ -1200,7 +1200,7 @@
1200 1200
   #define Z2_MS3_PIN -1
1201 1201
 #endif
1202 1202
 
1203
-#if ENABLED(Z_TRIPLE_STEPPER_DRIVERS)
1203
+#if NUM_Z_STEPPER_DRIVERS >= 3
1204 1204
   #ifndef Z3_STEP_PIN
1205 1205
     #define Z3_STEP_PIN   _EPIN(Z3_E_INDEX, STEP)
1206 1206
     #define Z3_DIR_PIN    _EPIN(Z3_E_INDEX, DIR)
@@ -1231,6 +1231,7 @@
1231 1231
       #define Z3_SERIAL_RX_PIN _EPIN(Z3_E_INDEX, SERIAL_RX)
1232 1232
     #endif
1233 1233
   #endif
1234
+  #define Z4_E_INDEX INCREMENT(Z3_E_INDEX)
1234 1235
 #endif
1235 1236
 
1236 1237
 #ifndef Z3_CS_PIN
@@ -1246,6 +1247,52 @@
1246 1247
   #define Z3_MS3_PIN -1
1247 1248
 #endif
1248 1249
 
1250
+#if NUM_Z_STEPPER_DRIVERS >= 4
1251
+  #ifndef Z4_STEP_PIN
1252
+    #define Z4_STEP_PIN   _EPIN(Z4_E_INDEX, STEP)
1253
+    #define Z4_DIR_PIN    _EPIN(Z4_E_INDEX, DIR)
1254
+    #define Z4_ENABLE_PIN _EPIN(Z4_E_INDEX, ENABLE)
1255
+    #if Z4_E_INDEX >= MAX_EXTRUDERS || !PIN_EXISTS(Z4_STEP)
1256
+      #error "No E stepper plug left for Z4!"
1257
+    #endif
1258
+  #endif
1259
+  #if AXIS_HAS_SPI(Z4)
1260
+    #ifndef Z4_CS_PIN
1261
+      #define Z4_CS_PIN     _EPIN(Z4_E_INDEX, CS)
1262
+    #endif
1263
+  #endif
1264
+  #ifndef Z4_MS1_PIN
1265
+    #define Z4_MS1_PIN    _EPIN(Z4_E_INDEX, MS1)
1266
+  #endif
1267
+  #ifndef Z4_MS2_PIN
1268
+    #define Z4_MS2_PIN    _EPIN(Z4_E_INDEX, MS2)
1269
+  #endif
1270
+  #ifndef Z4_MS3_PIN
1271
+    #define Z4_MS3_PIN    _EPIN(Z4_E_INDEX, MS3)
1272
+  #endif
1273
+  #if AXIS_HAS_UART(Z4)
1274
+    #ifndef Z4_SERIAL_TX_PIN
1275
+      #define Z4_SERIAL_TX_PIN _EPIN(Z4_E_INDEX, SERIAL_TX)
1276
+    #endif
1277
+    #ifndef Z4_SERIAL_RX_PIN
1278
+      #define Z4_SERIAL_RX_PIN _EPIN(Z4_E_INDEX, SERIAL_RX)
1279
+    #endif
1280
+  #endif
1281
+#endif
1282
+
1283
+#ifndef Z4_CS_PIN
1284
+  #define Z4_CS_PIN  -1
1285
+#endif
1286
+#ifndef Z4_MS1_PIN
1287
+  #define Z4_MS1_PIN -1
1288
+#endif
1289
+#ifndef Z4_MS2_PIN
1290
+  #define Z4_MS2_PIN -1
1291
+#endif
1292
+#ifndef Z4_MS3_PIN
1293
+  #define Z4_MS3_PIN -1
1294
+#endif
1295
+
1249 1296
 #if HAS_GRAPHICAL_LCD
1250 1297
   #if !defined(ST7920_DELAY_1) && defined(BOARD_ST7920_DELAY_1)
1251 1298
     #define ST7920_DELAY_1 BOARD_ST7920_DELAY_1

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

@@ -90,6 +90,15 @@
90 90
 #if !PIN_EXISTS(Z3_MS3)
91 91
   #undef Z3_MS3_PIN
92 92
 #endif
93
+#if !PIN_EXISTS(Z4_MS1)
94
+  #undef Z4_MS1_PIN
95
+#endif
96
+#if !PIN_EXISTS(Z4_MS2)
97
+  #undef Z4_MS2_PIN
98
+#endif
99
+#if !PIN_EXISTS(Z4_MS3)
100
+  #undef Z4_MS3_PIN
101
+#endif
93 102
 #if !PIN_EXISTS(E0_MS1)
94 103
   #undef E0_MS1_PIN
95 104
 #endif
@@ -1335,6 +1344,27 @@
1335 1344
 #if PIN_EXISTS(Z3_STEP)
1336 1345
   REPORT_NAME_DIGITAL(__LINE__, Z3_STEP_PIN)
1337 1346
 #endif
1347
+#if PIN_EXISTS(Z4_CS)
1348
+  REPORT_NAME_DIGITAL(__LINE__, Z4_CS_PIN)
1349
+#endif
1350
+#if PIN_EXISTS(Z4_DIR)
1351
+  REPORT_NAME_DIGITAL(__LINE__, Z4_DIR_PIN)
1352
+#endif
1353
+#if PIN_EXISTS(Z4_ENABLE)
1354
+  REPORT_NAME_DIGITAL(__LINE__, Z4_ENABLE_PIN)
1355
+#endif
1356
+#if PIN_EXISTS(Z4_MS1)
1357
+  REPORT_NAME_DIGITAL(__LINE__, Z4_MS1_PIN)
1358
+#endif
1359
+#if PIN_EXISTS(Z4_MS2)
1360
+  REPORT_NAME_DIGITAL(__LINE__, Z4_MS2_PIN)
1361
+#endif
1362
+#if PIN_EXISTS(Z4_MS3)
1363
+  REPORT_NAME_DIGITAL(__LINE__, Z4_MS3_PIN)
1364
+#endif
1365
+#if PIN_EXISTS(Z4_STEP)
1366
+  REPORT_NAME_DIGITAL(__LINE__, Z4_STEP_PIN)
1367
+#endif
1338 1368
 #if PIN_EXISTS(ZRIB_V20_D6)
1339 1369
   REPORT_NAME_DIGITAL(__LINE__, ZRIB_V20_D6_PIN)
1340 1370
 #endif
@@ -1383,6 +1413,12 @@
1383 1413
 #if PIN_EXISTS(Z3_SERIAL_RX)
1384 1414
   REPORT_NAME_DIGITAL(__LINE__, Z3_SERIAL_RX_PIN)
1385 1415
 #endif
1416
+#if PIN_EXISTS(Z4_SERIAL_TX)
1417
+  REPORT_NAME_DIGITAL(__LINE__, Z4_SERIAL_TX_PIN)
1418
+#endif
1419
+#if PIN_EXISTS(Z4_SERIAL_RX)
1420
+  REPORT_NAME_DIGITAL(__LINE__, Z4_SERIAL_RX_PIN)
1421
+#endif
1386 1422
 #if PIN_EXISTS(E0_SERIAL_TX)
1387 1423
   REPORT_NAME_DIGITAL(__LINE__, E0_SERIAL_TX_PIN)
1388 1424
 #endif

+ 3
- 7
Marlin/src/pins/ramps/pins_RL200.h View File

@@ -31,13 +31,9 @@
31 31
 
32 32
 #if HOTENDS > 2 || E_STEPPERS > 2
33 33
   #error "RL200v1 supports up to 2 hotends / E-steppers. Comment out this line to continue."
34
-#endif
35
-
36
-#if DISABLED(Z_DUAL_STEPPER_DRIVERS)
37
-  #error "RL200 uses dual Z stepper motors. Update Configuration_adv.h or comment out this line to continue."
38
-#endif
39
-
40
-#if !(AXIS_DRIVER_TYPE_X(DRV8825) && AXIS_DRIVER_TYPE_Y(DRV8825) && AXIS_DRIVER_TYPE_Z(DRV8825) && AXIS_DRIVER_TYPE_Z2(DRV8825) && AXIS_DRIVER_TYPE_E0(DRV8825))
34
+#elif NUM_Z_STEPPER_DRIVERS != 2
35
+  #error "RL200 uses dual Z stepper motors. Set NUM_Z_STEPPER_DRIVERS to 2 or comment out this line to continue."
36
+#elif !(AXIS_DRIVER_TYPE_X(DRV8825) && AXIS_DRIVER_TYPE_Y(DRV8825) && AXIS_DRIVER_TYPE_Z(DRV8825) && AXIS_DRIVER_TYPE_Z2(DRV8825) && AXIS_DRIVER_TYPE_E0(DRV8825))
41 37
   #error "You must set ([XYZ]|Z2|E0)_DRIVER_TYPE to DRV8825 in Configuration.h for RL200."
42 38
 #endif
43 39
 

+ 31
- 5
Marlin/src/pins/sensitive_pins.h View File

@@ -423,7 +423,7 @@
423 423
   #define _Y2_PINS
424 424
 #endif
425 425
 
426
-#if Z_MULTI_STEPPER_DRIVERS
426
+#if NUM_Z_STEPPER_DRIVERS >= 2
427 427
   #if PIN_EXISTS(Z2_CS) && AXIS_HAS_SPI(Z2)
428 428
     #define _Z2_CS Z2_CS_PIN,
429 429
   #else
@@ -449,7 +449,7 @@
449 449
   #define _Z2_PINS
450 450
 #endif
451 451
 
452
-#if ENABLED(Z_TRIPLE_STEPPER_DRIVERS)
452
+#if NUM_Z_STEPPER_DRIVERS >= 3
453 453
   #if PIN_EXISTS(Z3_CS) && AXIS_HAS_SPI(Z3)
454 454
     #define _Z3_CS Z3_CS_PIN,
455 455
   #else
@@ -475,6 +475,32 @@
475 475
   #define _Z3_PINS
476 476
 #endif
477 477
 
478
+#if NUM_Z_STEPPER_DRIVERS >= 4
479
+  #if PIN_EXISTS(Z4_CS) && AXIS_HAS_SPI(Z4)
480
+    #define _Z4_CS Z4_CS_PIN,
481
+  #else
482
+    #define _Z4_CS
483
+  #endif
484
+  #if PIN_EXISTS(Z4_MS1)
485
+    #define _Z4_MS1 Z4_MS1_PIN,
486
+  #else
487
+    #define _Z4_MS1
488
+  #endif
489
+  #if PIN_EXISTS(Z4_MS2)
490
+    #define _Z4_MS2 Z4_MS2_PIN,
491
+  #else
492
+    #define _Z4_MS2
493
+  #endif
494
+  #if PIN_EXISTS(Z4_MS3)
495
+    #define _Z4_MS3 Z4_MS3_PIN,
496
+  #else
497
+    #define _Z4_MS3
498
+  #endif
499
+  #define _Z4_PINS Z4_STEP_PIN, Z4_DIR_PIN, Z4_ENABLE_PIN, _Z4_CS _Z4_MS1 _Z4_MS2 _Z4_MS3
500
+#else
501
+  #define _Z4_PINS
502
+#endif
503
+
478 504
 //
479 505
 // Generate the final Sensitive Pins array,
480 506
 // keeping the array as small as possible.
@@ -524,9 +550,9 @@
524 550
 #endif
525 551
 
526 552
 #define SENSITIVE_PINS { \
527
-  _X_PINS _Y_PINS _Z_PINS _X2_PINS _Y2_PINS _Z2_PINS _Z3_PINS _Z_PROBE \
528
-  _E0_PINS _E1_PINS _E2_PINS _E3_PINS _E4_PINS _E5_PINS _BED_PINS \
529
-  _H0_PINS _H1_PINS _H2_PINS _H3_PINS _H4_PINS _H5_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 \
530 556
   _PS_ON _HEATER_BED _FAN0 _FAN1 _FAN2 _FANC \
531 557
   HAL_SENSITIVE_PINS \
532 558
 }

+ 5
- 5
buildroot/share/tests/DUE-tests View File

@@ -37,16 +37,16 @@ exec_test $1 $2 "RAMPS4DUE_EFB with ABL (Bilinear), EXTENSIBLE_UI, S-Curve, many
37 37
 restore_configs
38 38
 opt_set MOTHERBOARD BOARD_RADDS
39 39
 opt_enable USE_XMAX_PLUG USE_YMAX_PLUG ENDSTOPPULLUPS BLTOUCH AUTO_BED_LEVELING_BILINEAR \
40
-           Z_TRIPLE_STEPPER_DRIVERS Z_TRIPLE_ENDSTOPS Z_STEPPER_AUTO_ALIGN \
41
-           Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS
40
+           Z_MULTI_ENDSTOPS Z_STEPPER_AUTO_ALIGN Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS
42 41
            #TOUCH_UI_FTDI_EVE LCD_ALEPHOBJECTS_CLCD_UI OTHER_PIN_LAYOUT
42
+opt_set NUM_Z_STEPPER_DRIVERS 3
43 43
 opt_add Z2_MAX_ENDSTOP_INVERTING false
44 44
 opt_add Z3_MAX_ENDSTOP_INVERTING false
45
-pins_set ramps/RAMPS X_MAX_PIN -1
46
-pins_set ramps/RAMPS Y_MAX_PIN -1
47 45
 opt_add Z2_MAX_PIN 2
48 46
 opt_add Z3_MAX_PIN 3
49
-exec_test $1 $2 "RADDS with ABL (Bilinear), Z_TRIPLE_STEPPER_DRIVERS and Z_STEPPER_AUTO_ALIGN"
47
+pins_set ramps/RAMPS X_MAX_PIN -1
48
+pins_set ramps/RAMPS Y_MAX_PIN -1
49
+exec_test $1 $2 "RADDS with ABL (Bilinear), Triple Z Axis, Z_STEPPER_AUTO_ALIGN"
50 50
 
51 51
 #
52 52
 # Test SWITCHING_EXTRUDER

+ 4
- 3
buildroot/share/tests/teensy35-tests View File

@@ -100,15 +100,16 @@ opt_enable COREXZ
100 100
 exec_test $1 $2 "COREXZ"
101 101
 
102 102
 #
103
-# Enable Z_DUAL_STEPPER_DRIVERS, Z_DUAL_ENDSTOPS
103
+# Enable Dual Z with Dual Z endstops
104 104
 #
105 105
 restore_configs
106 106
 opt_set MOTHERBOARD BOARD_TEENSY35_36
107
-opt_enable Z_DUAL_STEPPER_DRIVERS Z_DUAL_ENDSTOPS
107
+opt_enable Z_MULTI_ENDSTOPS
108
+opt_set NUM_Z_STEPPER_DRIVERS 2
108 109
 pins_set ramps/RAMPS X_MAX_PIN -1
109 110
 opt_add Z2_MAX_PIN 2
110 111
 opt_enable USE_XMAX_PLUG
111
-exec_test $1 $2 "Z_DUAL_STEPPER_DRIVERS, Z_DUAL_ENDSTOPS"
112
+exec_test $1 $2 "Dual Z with Dual Z endstops"
112 113
 
113 114
 # Clean up
114 115
 restore_configs

Loading…
Cancel
Save