Ver código fonte

Add support for Triple-Z steppers/endstops

Holger Müller 6 anos atrás
pai
commit
1a6f2b29b8
37 arquivos alterados com 901 adições e 155 exclusões
  1. 1
    0
      Marlin/Configuration.h
  2. 23
    0
      Marlin/Configuration_adv.h
  3. 1
    0
      Marlin/src/HAL/HAL_AVR/SanityCheck.h
  4. 20
    0
      Marlin/src/HAL/HAL_AVR/endstop_interrupts.h
  5. 6
    0
      Marlin/src/HAL/HAL_DUE/endstop_interrupts.h
  6. 6
    0
      Marlin/src/HAL/HAL_ESP32/endstop_interrupts.h
  7. 6
    0
      Marlin/src/HAL/HAL_LPC1768/endstop_interrupts.h
  8. 6
    0
      Marlin/src/HAL/HAL_STM32F1/endstop_interrupts.h
  9. 6
    0
      Marlin/src/HAL/HAL_STM32F4/endstop_interrupts.h
  10. 6
    0
      Marlin/src/HAL/HAL_STM32F7/endstop_interrupts.h
  11. 8
    12
      Marlin/src/HAL/HAL_TEENSY35_36/endstop_interrupts.h
  12. 4
    1
      Marlin/src/Marlin.h
  13. 1
    0
      Marlin/src/config/default/Configuration.h
  14. 23
    0
      Marlin/src/config/default/Configuration_adv.h
  15. 3
    2
      Marlin/src/core/drivers.h
  16. 2
    0
      Marlin/src/core/language.h
  17. 3
    0
      Marlin/src/feature/controllerfan.cpp
  18. 72
    6
      Marlin/src/feature/tmc_util.cpp
  19. 28
    1
      Marlin/src/feature/tmc_util.h
  20. 25
    9
      Marlin/src/gcode/calibrate/M666.cpp
  21. 6
    0
      Marlin/src/gcode/feature/trinamic/M906.cpp
  22. 44
    19
      Marlin/src/gcode/feature/trinamic/M911-M915.cpp
  23. 3
    0
      Marlin/src/inc/Conditionals_LCD.h
  24. 63
    2
      Marlin/src/inc/Conditionals_post.h
  25. 66
    16
      Marlin/src/inc/SanityCheck.h
  26. 97
    29
      Marlin/src/module/configuration_store.cpp
  27. 78
    9
      Marlin/src/module/endstops.cpp
  28. 11
    6
      Marlin/src/module/endstops.h
  29. 66
    10
      Marlin/src/module/motion.cpp
  30. 62
    24
      Marlin/src/module/stepper.cpp
  31. 12
    6
      Marlin/src/module/stepper.h
  32. 41
    0
      Marlin/src/module/stepper_indirection.cpp
  33. 35
    0
      Marlin/src/module/stepper_indirection.h
  34. 27
    2
      Marlin/src/pins/pins.h
  35. 27
    0
      Marlin/src/pins/pinsDebug_list.h
  36. 12
    0
      buildroot/share/tests/DUE_tests
  37. 1
    1
      buildroot/share/tests/teensy35_tests

+ 1
- 0
Marlin/Configuration.h Ver arquivo

@@ -587,6 +587,7 @@
587 587
 //#define X2_DRIVER_TYPE A4988
588 588
 //#define Y2_DRIVER_TYPE A4988
589 589
 //#define Z2_DRIVER_TYPE A4988
590
+//#define Z3_DRIVER_TYPE A4988
590 591
 //#define E0_DRIVER_TYPE A4988
591 592
 //#define E1_DRIVER_TYPE A4988
592 593
 //#define E2_DRIVER_TYPE A4988

+ 23
- 0
Marlin/Configuration_adv.h Ver arquivo

@@ -338,6 +338,17 @@
338 338
   #endif
339 339
 #endif
340 340
 
341
+//#define Z_TRIPLE_STEPPER_DRIVERS
342
+#if ENABLED(Z_TRIPLE_STEPPER_DRIVERS)
343
+  //#define Z_TRIPLE_ENDSTOPS
344
+  #if ENABLED(Z_TRIPLE_ENDSTOPS)
345
+    #define Z2_USE_ENDSTOP _XMAX_
346
+    #define Z3_USE_ENDSTOP _YMAX_
347
+    #define Z_TRIPLE2_ENDSTOPS_ADJUSTMENT  0
348
+    #define Z_TRIPLE3_ENDSTOPS_ADJUSTMENT  0
349
+  #endif
350
+#endif
351
+
341 352
 /**
342 353
  * Dual X Carriage
343 354
  *
@@ -1087,6 +1098,10 @@
1087 1098
   #define Z2_SENSE_RESISTOR   91
1088 1099
   #define Z2_MICROSTEPS       16
1089 1100
 
1101
+  #define Z3_MAX_CURRENT    1000
1102
+  #define Z3_SENSE_RESISTOR   91
1103
+  #define Z3_MICROSTEPS       16
1104
+
1090 1105
   #define E0_MAX_CURRENT    1000
1091 1106
   #define E0_SENSE_RESISTOR   91
1092 1107
   #define E0_MICROSTEPS       16
@@ -1153,6 +1168,9 @@
1153 1168
   #define Z2_CURRENT         800
1154 1169
   #define Z2_MICROSTEPS       16
1155 1170
 
1171
+  #define Z3_CURRENT         800
1172
+  #define Z3_MICROSTEPS       16
1173
+
1156 1174
   #define E0_CURRENT         800
1157 1175
   #define E0_MICROSTEPS       16
1158 1176
 
@@ -1217,6 +1235,7 @@
1217 1235
   #define Y2_HYBRID_THRESHOLD    100
1218 1236
   #define Z_HYBRID_THRESHOLD       3
1219 1237
   #define Z2_HYBRID_THRESHOLD      3
1238
+  #define Z3_HYBRID_THRESHOLD      3
1220 1239
   #define E0_HYBRID_THRESHOLD     30
1221 1240
   #define E1_HYBRID_THRESHOLD     30
1222 1241
   #define E2_HYBRID_THRESHOLD     30
@@ -1315,6 +1334,10 @@
1315 1334
   #define Z2_OVERCURRENT    2000
1316 1335
   #define Z2_STALLCURRENT   1500
1317 1336
 
1337
+  #define Z3_MICROSTEPS       16
1338
+  #define Z3_OVERCURRENT    2000
1339
+  #define Z3_STALLCURRENT   1500
1340
+
1318 1341
   #define E0_MICROSTEPS       16
1319 1342
   #define E0_OVERCURRENT    2000
1320 1343
   #define E0_STALLCURRENT   1500

+ 1
- 0
Marlin/src/HAL/HAL_AVR/SanityCheck.h Ver arquivo

@@ -106,6 +106,7 @@
106 106
     || defined(Y2_HARDWARE_SERIAL) \
107 107
     || defined(Z_HARDWARE_SERIAL ) \
108 108
     || defined(Z2_HARDWARE_SERIAL) \
109
+    || defined(Z3_HARDWARE_SERIAL) \
109 110
     || defined(E0_HARDWARE_SERIAL) \
110 111
     || defined(E1_HARDWARE_SERIAL) \
111 112
     || defined(E2_HARDWARE_SERIAL) \

+ 20
- 0
Marlin/src/HAL/HAL_AVR/endstop_interrupts.h Ver arquivo

@@ -225,6 +225,26 @@ void setup_endstop_interrupts( void ) {
225 225
     #endif
226 226
   #endif
227 227
 
228
+  #if HAS_Z3_MAX
229
+    #if (digitalPinToInterrupt(Z3_MAX_PIN) != NOT_AN_INTERRUPT)
230
+      attachInterrupt(digitalPinToInterrupt(Z3_MAX_PIN), endstop_ISR, CHANGE);
231
+    #else
232
+      // Not all used endstop/probe -pins can raise interrupts. Please deactivate ENDSTOP_INTERRUPTS or change the pin configuration!
233
+      static_assert(digitalPinToPCICR(Z3_MAX_PIN) != NULL, "Z3_MAX_PIN is not interrupt-capable");
234
+      pciSetup(Z3_MAX_PIN);
235
+    #endif
236
+  #endif
237
+
238
+  #if HAS_Z3_MIN
239
+    #if (digitalPinToInterrupt(Z3_MIN_PIN) != NOT_AN_INTERRUPT)
240
+      attachInterrupt(digitalPinToInterrupt(Z3_MIN_PIN), endstop_ISR, CHANGE);
241
+    #else
242
+      // Not all used endstop/probe -pins can raise interrupts. Please deactivate ENDSTOP_INTERRUPTS or change the pin configuration!
243
+      static_assert(digitalPinToPCICR(Z3_MIN_PIN) != NULL, "Z3_MIN_PIN is not interrupt-capable");
244
+      pciSetup(Z3_MIN_PIN);
245
+    #endif
246
+  #endif
247
+
228 248
   #if HAS_Z_MIN_PROBE_PIN
229 249
     #if (digitalPinToInterrupt(Z_MIN_PROBE_PIN) != NOT_AN_INTERRUPT)
230 250
       attachInterrupt(digitalPinToInterrupt(Z_MIN_PROBE_PIN), endstop_ISR, CHANGE);

+ 6
- 0
Marlin/src/HAL/HAL_DUE/endstop_interrupts.h Ver arquivo

@@ -72,6 +72,12 @@ void setup_endstop_interrupts(void) {
72 72
   #if HAS_Z2_MIN
73 73
     attachInterrupt(digitalPinToInterrupt(Z2_MIN_PIN), endstop_ISR, CHANGE);
74 74
   #endif
75
+  #if HAS_Z3_MAX
76
+    attachInterrupt(digitalPinToInterrupt(Z3_MAX_PIN), endstop_ISR, CHANGE);
77
+  #endif
78
+  #if HAS_Z3_MIN
79
+    attachInterrupt(digitalPinToInterrupt(Z3_MIN_PIN), endstop_ISR, CHANGE);
80
+  #endif
75 81
   #if HAS_Z_MIN_PROBE_PIN
76 82
     attachInterrupt(digitalPinToInterrupt(Z_MIN_PROBE_PIN), endstop_ISR, CHANGE);
77 83
   #endif

+ 6
- 0
Marlin/src/HAL/HAL_ESP32/endstop_interrupts.h Ver arquivo

@@ -67,6 +67,12 @@ void setup_endstop_interrupts(void) {
67 67
   #if HAS_Z2_MIN
68 68
     attachInterrupt(digitalPinToInterrupt(Z2_MIN_PIN), endstop_ISR, CHANGE);
69 69
   #endif
70
+  #if HAS_Z3_MAX
71
+    attachInterrupt(digitalPinToInterrupt(Z3_MAX_PIN), endstop_ISR, CHANGE);
72
+  #endif
73
+  #if HAS_Z3_MIN
74
+    attachInterrupt(digitalPinToInterrupt(Z3_MIN_PIN), endstop_ISR, CHANGE);
75
+  #endif
70 76
   #if HAS_Z_MIN_PROBE_PIN
71 77
     attachInterrupt(digitalPinToInterrupt(Z_MIN_PROBE_PIN), endstop_ISR, CHANGE);
72 78
   #endif

+ 6
- 0
Marlin/src/HAL/HAL_LPC1768/endstop_interrupts.h Ver arquivo

@@ -91,6 +91,12 @@ void setup_endstop_interrupts(void) {
91 91
     #endif
92 92
     attachInterrupt(digitalPinToInterrupt(Z2_MIN_PIN), endstop_ISR, CHANGE);
93 93
   #endif
94
+  #if HAS_Z3_MAX
95
+    attachInterrupt(digitalPinToInterrupt(Z3_MAX_PIN), endstop_ISR, CHANGE);
96
+  #endif
97
+  #if HAS_Z3_MIN
98
+    attachInterrupt(digitalPinToInterrupt(Z3_MIN_PIN), endstop_ISR, CHANGE);
99
+  #endif
94 100
   #if HAS_Z_MIN_PROBE_PIN
95 101
     #if !LPC1768_PIN_INTERRUPT_M(Z_MIN_PROBE_PIN)
96 102
       #error "Z_MIN_PROBE_PIN is not an INTERRUPT capable pin."

+ 6
- 0
Marlin/src/HAL/HAL_STM32F1/endstop_interrupts.h Ver arquivo

@@ -79,6 +79,12 @@ void setup_endstop_interrupts(void) {
79 79
   #if HAS_Z2_MIN
80 80
     attachInterrupt(Z2_MIN_PIN, endstop_ISR, CHANGE);
81 81
   #endif
82
+  #if HAS_Z3_MAX
83
+    attachInterrupt(Z3_MAX_PIN, endstop_ISR, CHANGE);
84
+  #endif
85
+  #if HAS_Z3_MIN
86
+    attachInterrupt(Z3_MIN_PIN, endstop_ISR, CHANGE);
87
+  #endif
82 88
   #if HAS_Z_MIN_PROBE_PIN
83 89
     attachInterrupt(Z_MIN_PROBE_PIN, endstop_ISR, CHANGE);
84 90
   #endif

+ 6
- 0
Marlin/src/HAL/HAL_STM32F4/endstop_interrupts.h Ver arquivo

@@ -54,6 +54,12 @@ void setup_endstop_interrupts(void) {
54 54
   #if HAS_Z2_MIN
55 55
     attachInterrupt(Z2_MIN_PIN, endstop_ISR, CHANGE);
56 56
   #endif
57
+  #if HAS_Z3_MAX
58
+    attachInterrupt(Z3_MAX_PIN, endstop_ISR, CHANGE);
59
+  #endif
60
+  #if HAS_Z3_MIN
61
+    attachInterrupt(Z3_MIN_PIN, endstop_ISR, CHANGE);
62
+  #endif
57 63
   #if HAS_Z_MIN_PROBE_PIN
58 64
     attachInterrupt(Z_MIN_PROBE_PIN, endstop_ISR, CHANGE);
59 65
   #endif

+ 6
- 0
Marlin/src/HAL/HAL_STM32F7/endstop_interrupts.h Ver arquivo

@@ -56,6 +56,12 @@ void setup_endstop_interrupts(void) {
56 56
   #if HAS_Z2_MIN
57 57
     attachInterrupt(Z2_MIN_PIN, endstop_ISR, CHANGE);
58 58
   #endif
59
+  #if HAS_Z3_MAX
60
+    attachInterrupt(Z3_MAX_PIN, endstop_ISR, CHANGE);
61
+  #endif
62
+  #if HAS_Z3_MIN
63
+    attachInterrupt(Z3_MIN_PIN, endstop_ISR, CHANGE);
64
+  #endif
59 65
   #if HAS_Z_MIN_PROBE_PIN
60 66
     attachInterrupt(Z_MIN_PROBE_PIN, endstop_ISR, CHANGE);
61 67
   #endif

+ 8
- 12
Marlin/src/HAL/HAL_TEENSY35_36/endstop_interrupts.h Ver arquivo

@@ -43,44 +43,40 @@
43 43
 void endstop_ISR(void) { endstops.update(); }
44 44
 
45 45
 /**
46
- *  Endstop interrupts for Due based targets.
47
- *  On Due, all pins support external interrupt capability.
46
+ * Endstop interrupts for Due based targets.
47
+ * On Due, all pins support external interrupt capability.
48 48
  */
49
-
50 49
 void setup_endstop_interrupts( void ) {
51
-
52 50
   #if HAS_X_MAX
53 51
     attachInterrupt(digitalPinToInterrupt(X_MAX_PIN), endstop_ISR, CHANGE); // assign it
54 52
   #endif
55
-
56 53
   #if HAS_X_MIN
57 54
     attachInterrupt(digitalPinToInterrupt(X_MIN_PIN), endstop_ISR, CHANGE);
58 55
   #endif
59
-
60 56
   #if HAS_Y_MAX
61 57
     attachInterrupt(digitalPinToInterrupt(Y_MAX_PIN), endstop_ISR, CHANGE);
62 58
   #endif
63
-
64 59
   #if HAS_Y_MIN
65 60
     attachInterrupt(digitalPinToInterrupt(Y_MIN_PIN), endstop_ISR, CHANGE);
66 61
   #endif
67
-
68 62
   #if HAS_Z_MAX
69 63
     attachInterrupt(digitalPinToInterrupt(Z_MAX_PIN), endstop_ISR, CHANGE);
70 64
   #endif
71
-
72 65
   #if HAS_Z_MIN
73 66
      attachInterrupt(digitalPinToInterrupt(Z_MIN_PIN), endstop_ISR, CHANGE);
74 67
   #endif
75
-
76 68
   #if HAS_Z2_MAX
77 69
     attachInterrupt(digitalPinToInterrupt(Z2_MAX_PIN), endstop_ISR, CHANGE);
78 70
   #endif
79
-
80 71
   #if HAS_Z2_MIN
81 72
     attachInterrupt(digitalPinToInterrupt(Z2_MIN_PIN), endstop_ISR, CHANGE);
82 73
   #endif
83
-
74
+  #if HAS_Z3_MAX
75
+    attachInterrupt(digitalPinToInterrupt(Z3_MAX_PIN), endstop_ISR, CHANGE);
76
+  #endif
77
+  #if HAS_Z3_MIN
78
+    attachInterrupt(digitalPinToInterrupt(Z3_MIN_PIN), endstop_ISR, CHANGE);
79
+  #endif
84 80
   #if HAS_Z_MIN_PROBE_PIN
85 81
     attachInterrupt(digitalPinToInterrupt(Z_MIN_PROBE_PIN), endstop_ISR, CHANGE);
86 82
   #endif

+ 4
- 1
Marlin/src/Marlin.h Ver arquivo

@@ -64,7 +64,10 @@ void manage_inactivity(const bool ignore_stepper_queue=false);
64 64
   #define disable_Y() NOOP
65 65
 #endif
66 66
 
67
-#if HAS_Z2_ENABLE
67
+#if HAS_Z3_ENABLE
68
+  #define  enable_Z() do{ Z_ENABLE_WRITE( Z_ENABLE_ON); Z2_ENABLE_WRITE(Z_ENABLE_ON); Z3_ENABLE_WRITE(Z_ENABLE_ON); }while(0)
69
+  #define disable_Z() do{ Z_ENABLE_WRITE(!Z_ENABLE_ON); Z2_ENABLE_WRITE(!Z_ENABLE_ON); Z3_ENABLE_WRITE(!Z_ENABLE_ON); CBI(axis_known_position, Z_AXIS); }while(0)
70
+#elif HAS_Z2_ENABLE
68 71
   #define  enable_Z() do{ Z_ENABLE_WRITE( Z_ENABLE_ON); Z2_ENABLE_WRITE(Z_ENABLE_ON); }while(0)
69 72
   #define disable_Z() do{ Z_ENABLE_WRITE(!Z_ENABLE_ON); Z2_ENABLE_WRITE(!Z_ENABLE_ON); CBI(axis_known_position, Z_AXIS); }while(0)
70 73
 #elif HAS_Z_ENABLE

+ 1
- 0
Marlin/src/config/default/Configuration.h Ver arquivo

@@ -587,6 +587,7 @@
587 587
 //#define X2_DRIVER_TYPE A4988
588 588
 //#define Y2_DRIVER_TYPE A4988
589 589
 //#define Z2_DRIVER_TYPE A4988
590
+//#define Z3_DRIVER_TYPE A4988
590 591
 //#define E0_DRIVER_TYPE A4988
591 592
 //#define E1_DRIVER_TYPE A4988
592 593
 //#define E2_DRIVER_TYPE A4988

+ 23
- 0
Marlin/src/config/default/Configuration_adv.h Ver arquivo

@@ -338,6 +338,17 @@
338 338
   #endif
339 339
 #endif
340 340
 
341
+//#define Z_TRIPLE_STEPPER_DRIVERS
342
+#if ENABLED(Z_TRIPLE_STEPPER_DRIVERS)
343
+  //#define Z_TRIPLE_ENDSTOPS
344
+  #if ENABLED(Z_TRIPLE_ENDSTOPS)
345
+    #define Z2_USE_ENDSTOP _XMAX_
346
+    #define Z3_USE_ENDSTOP _YMAX_
347
+    #define Z_TRIPLE_ENDSTOPS_ADJUSTMENT2  0
348
+    #define Z_TRIPLE_ENDSTOPS_ADJUSTMENT3  0
349
+  #endif
350
+#endif
351
+
341 352
 /**
342 353
  * Dual X Carriage
343 354
  *
@@ -1087,6 +1098,10 @@
1087 1098
   #define Z2_SENSE_RESISTOR   91
1088 1099
   #define Z2_MICROSTEPS       16
1089 1100
 
1101
+  #define Z3_MAX_CURRENT    1000
1102
+  #define Z3_SENSE_RESISTOR   91
1103
+  #define Z3_MICROSTEPS       16
1104
+
1090 1105
   #define E0_MAX_CURRENT    1000
1091 1106
   #define E0_SENSE_RESISTOR   91
1092 1107
   #define E0_MICROSTEPS       16
@@ -1153,6 +1168,9 @@
1153 1168
   #define Z2_CURRENT         800
1154 1169
   #define Z2_MICROSTEPS       16
1155 1170
 
1171
+  #define Z3_CURRENT         800
1172
+  #define Z3_MICROSTEPS       16
1173
+
1156 1174
   #define E0_CURRENT         800
1157 1175
   #define E0_MICROSTEPS       16
1158 1176
 
@@ -1217,6 +1235,7 @@
1217 1235
   #define Y2_HYBRID_THRESHOLD    100
1218 1236
   #define Z_HYBRID_THRESHOLD       3
1219 1237
   #define Z2_HYBRID_THRESHOLD      3
1238
+  #define Z3_HYBRID_THRESHOLD      3
1220 1239
   #define E0_HYBRID_THRESHOLD     30
1221 1240
   #define E1_HYBRID_THRESHOLD     30
1222 1241
   #define E2_HYBRID_THRESHOLD     30
@@ -1315,6 +1334,10 @@
1315 1334
   #define Z2_OVERCURRENT    2000
1316 1335
   #define Z2_STALLCURRENT   1500
1317 1336
 
1337
+  #define Z3_MICROSTEPS       16
1338
+  #define Z3_OVERCURRENT    2000
1339
+  #define Z3_STALLCURRENT   1500
1340
+
1318 1341
   #define E0_MICROSTEPS       16
1319 1342
   #define E0_OVERCURRENT    2000
1320 1343
   #define E0_STALLCURRENT   1500

+ 3
- 2
Marlin/src/core/drivers.h Ver arquivo

@@ -47,7 +47,8 @@
47 47
 #define AXIS_DRIVER_TYPE_Z(T) _AXIS_DRIVER_TYPE(Z,T)
48 48
 #define AXIS_DRIVER_TYPE_X2(T) (ENABLED(X_DUAL_STEPPER_DRIVERS) || ENABLED(DUAL_X_CARRIAGE)) && _AXIS_DRIVER_TYPE(X2,T)
49 49
 #define AXIS_DRIVER_TYPE_Y2(T) (ENABLED(Y_DUAL_STEPPER_DRIVERS) && _AXIS_DRIVER_TYPE(Y2,T))
50
-#define AXIS_DRIVER_TYPE_Z2(T) (ENABLED(Z_DUAL_STEPPER_DRIVERS) && _AXIS_DRIVER_TYPE(Z2,T))
50
+#define AXIS_DRIVER_TYPE_Z2(T) (Z_MULTI_STEPPER_DRIVERS && _AXIS_DRIVER_TYPE(Z2,T))
51
+#define AXIS_DRIVER_TYPE_Z3(T) (ENABLED(Z_TRIPLE_STEPPER_DRIVERS) && _AXIS_DRIVER_TYPE(Z3,T))
51 52
 #define AXIS_DRIVER_TYPE_E0(T) (E_STEPPERS > 0 && _AXIS_DRIVER_TYPE(E0,T))
52 53
 #define AXIS_DRIVER_TYPE_E1(T) (E_STEPPERS > 1 && _AXIS_DRIVER_TYPE(E1,T))
53 54
 #define AXIS_DRIVER_TYPE_E2(T) (E_STEPPERS > 2 && _AXIS_DRIVER_TYPE(E2,T))
@@ -58,7 +59,7 @@
58 59
 
59 60
 #define HAS_DRIVER(T)  (AXIS_DRIVER_TYPE_X(T)  || AXIS_DRIVER_TYPE_X2(T) || \
60 61
                         AXIS_DRIVER_TYPE_Y(T)  || AXIS_DRIVER_TYPE_Y2(T) || \
61
-                        AXIS_DRIVER_TYPE_Z(T)  || AXIS_DRIVER_TYPE_Z2(T) || \
62
+                        AXIS_DRIVER_TYPE_Z(T)  || AXIS_DRIVER_TYPE_Z2(T) || AXIS_DRIVER_TYPE_Z3(T) || \
62 63
                         AXIS_DRIVER_TYPE_E0(T) || AXIS_DRIVER_TYPE_E1(T) || \
63 64
                         AXIS_DRIVER_TYPE_E2(T) || AXIS_DRIVER_TYPE_E3(T) || \
64 65
                         AXIS_DRIVER_TYPE_E4(T) )

+ 2
- 0
Marlin/src/core/language.h Ver arquivo

@@ -151,6 +151,8 @@
151 151
 #define MSG_Z_MAX                           "z_max: "
152 152
 #define MSG_Z2_MIN                          "z2_min: "
153 153
 #define MSG_Z2_MAX                          "z2_max: "
154
+#define MSG_Z3_MIN                          "z3_min: "
155
+#define MSG_Z3_MAX                          "z3_max: "
154 156
 #define MSG_Z_PROBE                         "z_probe: "
155 157
 #define MSG_PROBE_Z_OFFSET                  "Probe Z Offset"
156 158
 #define MSG_SKEW_MIN                        "min_skew_factor: "

+ 3
- 0
Marlin/src/feature/controllerfan.cpp Ver arquivo

@@ -50,6 +50,9 @@ void controllerfan_update() {
50 50
         #if HAS_Z2_ENABLE
51 51
           || Z2_ENABLE_READ == Z_ENABLE_ON
52 52
         #endif
53
+        #if HAS_Z3_ENABLE
54
+          || Z3_ENABLE_READ == Z_ENABLE_ON
55
+        #endif
53 56
         || E0_ENABLE_READ == E_ENABLE_ON
54 57
         #if E_STEPPERS > 1
55 58
           || E1_ENABLE_READ == E_ENABLE_ON

+ 72
- 6
Marlin/src/feature/tmc_util.cpp Ver arquivo

@@ -189,6 +189,10 @@ bool report_tmc_status = false;
189 189
         static uint8_t z2_otpw_cnt = 0;
190 190
         monitor_tmc_driver(stepperZ2, TMC_Z, z2_otpw_cnt);
191 191
       #endif
192
+      #if HAS_HW_COMMS(Z3)
193
+        static uint8_t z3_otpw_cnt = 0;
194
+        monitor_tmc_driver(stepperZ3, TMC_Z, z3_otpw_cnt);
195
+      #endif
192 196
       #if HAS_HW_COMMS(E0)
193 197
         static uint8_t e0_otpw_cnt = 0;
194 198
         monitor_tmc_driver(stepperE0, TMC_E0, e0_otpw_cnt);
@@ -217,12 +221,65 @@ bool report_tmc_status = false;
217 221
 #endif // MONITOR_DRIVER_STATUS
218 222
 
219 223
 void _tmc_say_axis(const TMC_AxisEnum axis) {
220
-  static const char ext_X[]  PROGMEM = "X",  ext_Y[]  PROGMEM = "Y",  ext_Z[]  PROGMEM = "Z",
221
-                    ext_X2[] PROGMEM = "X2", ext_Y2[] PROGMEM = "Y2", ext_Z2[] PROGMEM = "Z2",
222
-                    ext_E0[] PROGMEM = "E0", ext_E1[] PROGMEM = "E1",
223
-                    ext_E2[] PROGMEM = "E2", ext_E3[] PROGMEM = "E3",
224
-                    ext_E4[] PROGMEM = "E4";
225
-  static const char* const tmc_axes[] PROGMEM = { ext_X, ext_Y, ext_Z, ext_X2, ext_Y2, ext_Z2, ext_E0, ext_E1, ext_E2, ext_E3, ext_E4 };
224
+  static const char ext_X[] PROGMEM = "X", ext_Y[] PROGMEM = "Y", ext_Z[] PROGMEM = "Z",
225
+    #if ENABLED(DUAL_X_CARRIAGE) || ENABLED(X_DUAL_STEPPER_DRIVERS)
226
+      , ext_X2[] PROGMEM = "X2"
227
+    #endif
228
+    #if ENABLED(Y_DUAL_STEPPER_DRIVERS)
229
+      , ext_Y2[] PROGMEM = "Y2"
230
+    #endif
231
+    #if Z_MULTI_STEPPER_DRIVERS
232
+      , ext_Z2[] PROGMEM = "Z2"
233
+      #if ENABLED(Z_TRIPLE_STEPPER_DRIVERS)
234
+        , ext_Z3[] PROGMEM = "Z3"
235
+      #endif
236
+    #endif
237
+    #if E_STEPPERS
238
+      , ext_E0[] PROGMEM = "E0"
239
+      #if E_STEPPERS > 1
240
+        , ext_E1[] PROGMEM = "E1"
241
+        #if E_STEPPERS > 2
242
+          , ext_E2[] PROGMEM = "E2"
243
+          #if E_STEPPERS > 3
244
+            , ext_E3[] PROGMEM = "E3"
245
+            #if E_STEPPERS > 4
246
+              , ext_E4[] PROGMEM = "E4"
247
+            #endif
248
+          #endif
249
+        #endif
250
+      #endif
251
+    #endif
252
+
253
+  static const char* const tmc_axes[] PROGMEM = {
254
+    ext_X, ext_Y, ext_Z
255
+    #if ENABLED(DUAL_X_CARRIAGE) || ENABLED(X_DUAL_STEPPER_DRIVERS)
256
+      , ext_X2
257
+    #endif
258
+    #if ENABLED(Y_DUAL_STEPPER_DRIVERS)
259
+      , ext_Y2
260
+    #endif
261
+    #if Z_MULTI_STEPPER_DRIVERS
262
+      , ext_Z2
263
+      #if ENABLED(Z_TRIPLE_STEPPER_DRIVERS)
264
+        , ext_Z3
265
+      #endif
266
+    #endif
267
+    #if E_STEPPERS
268
+      , ext_E0
269
+      #if E_STEPPERS > 1
270
+        , ext_E1
271
+        #if E_STEPPERS > 2
272
+          , ext_E2
273
+          #if E_STEPPERS > 3
274
+            , ext_E3
275
+            #if E_STEPPERS > 4
276
+              , ext_E4
277
+            #endif
278
+          #endif
279
+        #endif
280
+      #endif
281
+    #endif
282
+  };
226 283
   serialprintPGM((char*)pgm_read_ptr(&tmc_axes[axis]));
227 284
 }
228 285
 
@@ -440,6 +497,9 @@ void _tmc_say_sgt(const TMC_AxisEnum axis, const int8_t sgt) {
440 497
     #if AXIS_IS_TMC(Z2)
441 498
       tmc_status(stepperZ2, TMC_Z2, i, planner.axis_steps_per_mm[Z_AXIS]);
442 499
     #endif
500
+    #if AXIS_IS_TMC(Z3)
501
+      tmc_status(stepperZ3, TMC_Z3, i, planner.axis_steps_per_mm[Z_AXIS]);
502
+    #endif
443 503
 
444 504
     #if AXIS_IS_TMC(E0)
445 505
       tmc_status(stepperE0, TMC_E0, i, planner.axis_steps_per_mm[E_AXIS]);
@@ -497,6 +557,9 @@ void _tmc_say_sgt(const TMC_AxisEnum axis, const int8_t sgt) {
497 557
     #if AXIS_IS_TMC(Z2)
498 558
       tmc_parse_drv_status(stepperZ2, TMC_Z2, i);
499 559
     #endif
560
+    #if AXIS_IS_TMC(Z3)
561
+      tmc_parse_drv_status(stepperZ3, TMC_Z3, i);
562
+    #endif
500 563
 
501 564
     #if AXIS_IS_TMC(E0)
502 565
       tmc_parse_drv_status(stepperE0, TMC_E0, i);
@@ -612,6 +675,9 @@ void _tmc_say_sgt(const TMC_AxisEnum axis, const int8_t sgt) {
612 675
     #if AXIS_DRIVER_TYPE(Z2, TMC2130)
613 676
       SET_CS_PIN(Z2);
614 677
     #endif
678
+    #if AXIS_DRIVER_TYPE(Z3, TMC2130)
679
+      SET_CS_PIN(Z3);
680
+    #endif
615 681
     #if AXIS_DRIVER_TYPE(E0, TMC2130)
616 682
       SET_CS_PIN(E0);
617 683
     #endif

+ 28
- 1
Marlin/src/feature/tmc_util.h Ver arquivo

@@ -35,7 +35,34 @@
35 35
 
36 36
 extern bool report_tmc_status;
37 37
 
38
-enum TMC_AxisEnum : char { TMC_X, TMC_Y, TMC_Z, TMC_X2, TMC_Y2, TMC_Z2, TMC_E0, TMC_E1, TMC_E2, TMC_E3, TMC_E4 };
38
+enum TMC_AxisEnum : char {
39
+  TMC_X, TMC_Y, TMC_Z
40
+  #if ENABLED(DUAL_X_CARRIAGE) || ENABLED(X_DUAL_STEPPER_DRIVERS)
41
+    , TMC_X2
42
+  #endif
43
+  #if ENABLED(Y_DUAL_STEPPER_DRIVERS)
44
+    , TMC_Y2
45
+  #endif
46
+  #if ENABLED(Z_DUAL_STEPPER_DRIVERS)
47
+    , TMC_Z2
48
+  #endif
49
+  #if ENABLED(Z_TRIPLE_STEPPER_DRIVERS)
50
+    , TMC_Z3
51
+  #endif
52
+  , TMC_E0
53
+  #if E_STEPPERS > 1
54
+    , TMC_E1
55
+    #if E_STEPPERS > 2
56
+      , TMC_E2
57
+      #if E_STEPPERS > 3
58
+        , TMC_E3
59
+        #if E_STEPPERS > 4
60
+          , TMC_E4
61
+        #endif
62
+      #endif
63
+    #endif
64
+  #endif
65
+};
39 66
 
40 67
 constexpr uint32_t _tmc_thrs(const uint16_t msteps, const int32_t thrs, const uint32_t spmm) {
41 68
   return 12650000UL * msteps / (256 * thrs * spmm);

+ 25
- 9
Marlin/src/gcode/calibrate/M666.cpp Ver arquivo

@@ -59,44 +59,60 @@
59 59
     #endif
60 60
   }
61 61
 
62
-#elif ENABLED(X_DUAL_ENDSTOPS) || ENABLED(Y_DUAL_ENDSTOPS) || ENABLED(Z_DUAL_ENDSTOPS)
62
+#elif ENABLED(X_DUAL_ENDSTOPS) || ENABLED(Y_DUAL_ENDSTOPS) || Z_MULTI_ENDSTOPS
63 63
 
64 64
   #include "../../module/endstops.h"
65 65
 
66 66
   /**
67 67
    * M666: Set Dual Endstops offsets for X, Y, and/or Z.
68 68
    *       With no parameters report current offsets.
69
+   *
70
+   * For Triple Z Endstops:
71
+   *   Set Z2 Only: M666 S2 Z<offset>
72
+   *   Set Z3 Only: M666 S3 Z<offset>
73
+   *      Set Both: M666 Z<offset>
69 74
    */
70 75
   void GcodeSuite::M666() {
71 76
     bool report = true;
72 77
     #if ENABLED(X_DUAL_ENDSTOPS)
73 78
       if (parser.seen('X')) {
74
-        endstops.x_endstop_adj = parser.value_linear_units();
79
+        endstops.x2_endstop_adj = parser.value_linear_units();
75 80
         report = false;
76 81
       }
77 82
     #endif
78 83
     #if ENABLED(Y_DUAL_ENDSTOPS)
79 84
       if (parser.seen('Y')) {
80
-        endstops.y_endstop_adj = parser.value_linear_units();
85
+        endstops.y2_endstop_adj = parser.value_linear_units();
81 86
         report = false;
82 87
       }
83 88
     #endif
84
-    #if ENABLED(Z_DUAL_ENDSTOPS)
89
+    #if ENABLED(Z_TRIPLE_ENDSTOPS)
85 90
       if (parser.seen('Z')) {
86
-        endstops.z_endstop_adj = parser.value_linear_units();
91
+        const int ind = parser.intval('S');
92
+        const float z_adj = parser.value_linear_units();
93
+        if (!ind || ind == 2) endstops.z2_endstop_adj = z_adj;
94
+        if (!ind || ind == 3) endstops.z3_endstop_adj = z_adj;
95
+        report = false;
96
+      }
97
+    #elif Z_MULTI_ENDSTOPS
98
+      if (parser.seen('Z')) {
99
+        endstops.z2_endstop_adj = parser.value_linear_units();
87 100
         report = false;
88 101
       }
89 102
     #endif
90 103
     if (report) {
91 104
       SERIAL_ECHOPGM("Dual Endstop Adjustment (mm): ");
92 105
       #if ENABLED(X_DUAL_ENDSTOPS)
93
-        SERIAL_ECHOPAIR(" X", endstops.x_endstop_adj);
106
+        SERIAL_ECHOPAIR(" X2:", endstops.x2_endstop_adj);
94 107
       #endif
95 108
       #if ENABLED(Y_DUAL_ENDSTOPS)
96
-        SERIAL_ECHOPAIR(" Y", endstops.y_endstop_adj);
109
+        SERIAL_ECHOPAIR(" Y2:", endstops.y2_endstop_adj);
110
+      #endif
111
+      #if Z_MULTI_ENDSTOPS
112
+        SERIAL_ECHOPAIR(" Z2:", endstops.z2_endstop_adj);
97 113
       #endif
98
-      #if ENABLED(Z_DUAL_ENDSTOPS)
99
-        SERIAL_ECHOPAIR(" Z", endstops.z_endstop_adj);
114
+      #if ENABLED(Z_TRIPLE_ENDSTOPS)
115
+        SERIAL_ECHOPAIR(" Z3:", endstops.z3_endstop_adj);
100 116
       #endif
101 117
       SERIAL_EOL();
102 118
     }

+ 6
- 0
Marlin/src/gcode/feature/trinamic/M906.cpp Ver arquivo

@@ -64,6 +64,9 @@ void GcodeSuite::M906() {
64 64
         #if AXIS_IS_TMC(Z2)
65 65
           if (index == 1) TMC_SET_CURRENT(Z2);
66 66
         #endif
67
+        #if AXIS_IS_TMC(Z3)
68
+          if (index == 2) TMC_SET_CURRENT(Z3);
69
+        #endif
67 70
         break;
68 71
       case E_AXIS: {
69 72
         if (get_target_extruder_from_command()) return;
@@ -107,6 +110,9 @@ void GcodeSuite::M906() {
107 110
     #if AXIS_IS_TMC(Z2)
108 111
       TMC_SAY_CURRENT(Z2);
109 112
     #endif
113
+    #if AXIS_IS_TMC(Z3)
114
+      TMC_SAY_CURRENT(Z3);
115
+    #endif
110 116
     #if AXIS_IS_TMC(E0)
111 117
       TMC_SAY_CURRENT(E0);
112 118
     #endif

+ 44
- 19
Marlin/src/gcode/feature/trinamic/M911-M915.cpp Ver arquivo

@@ -56,6 +56,9 @@ void GcodeSuite::M911() {
56 56
   #if M91x_USE(Z2)
57 57
     tmc_report_otpw(stepperZ2, TMC_Z2);
58 58
   #endif
59
+  #if M91x_USE(Z3)
60
+    tmc_report_otpw(stepperZ3, TMC_Z3);
61
+  #endif
59 62
   #if M91x_USE_E(0)
60 63
     tmc_report_otpw(stepperE0, TMC_E0);
61 64
   #endif
@@ -75,7 +78,7 @@ void GcodeSuite::M911() {
75 78
 
76 79
 /**
77 80
  * M912: Clear TMC stepper driver overtemperature pre-warn flag held by the library
78
- *       Specify one or more axes with X, Y, Z, X1, Y1, Z1, X2, Y2, Z2, and E[index].
81
+ *       Specify one or more axes with X, Y, Z, X1, Y1, Z1, X2, Y2, Z2, Z3 and E[index].
79 82
  *       If no axes are given, clear all.
80 83
  *
81 84
  * Examples:
@@ -93,51 +96,54 @@ void GcodeSuite::M912() {
93 96
                hasNone = !hasX && !hasY && !hasZ && !hasE;
94 97
 
95 98
     #if M91x_USE(X) || M91x_USE(X2)
96
-      const uint8_t xval = parser.byteval(axis_codes[X_AXIS], 10);
99
+      const int8_t xval = int8_t(parser.byteval(axis_codes[X_AXIS], 0xFF));
97 100
       #if M91x_USE(X)
98
-        if (hasNone || xval == 1 || (hasX && xval == 10)) tmc_clear_otpw(stepperX, TMC_X);
101
+        if (hasNone || xval == 1 || (hasX && xval < 0)) tmc_clear_otpw(stepperX, TMC_X);
99 102
       #endif
100 103
       #if M91x_USE(X2)
101
-        if (hasNone || xval == 2 || (hasX && xval == 10)) tmc_clear_otpw(stepperX2, TMC_X2);
104
+        if (hasNone || xval == 2 || (hasX && xval < 0)) tmc_clear_otpw(stepperX2, TMC_X2);
102 105
       #endif
103 106
     #endif
104 107
 
105 108
     #if M91x_USE(Y) || M91x_USE(Y2)
106
-      const uint8_t yval = parser.byteval(axis_codes[Y_AXIS], 10);
109
+      const int8_t yval = int8_t(parser.byteval(axis_codes[Y_AXIS], 0xFF));
107 110
       #if M91x_USE(Y)
108
-        if (hasNone || yval == 1 || (hasY && yval == 10)) tmc_clear_otpw(stepperY, TMC_Y);
111
+        if (hasNone || yval == 1 || (hasY && yval < 0)) tmc_clear_otpw(stepperY, TMC_Y);
109 112
       #endif
110 113
       #if M91x_USE(Y2)
111
-        if (hasNone || yval == 2 || (hasY && yval == 10)) tmc_clear_otpw(stepperY2, TMC_Y2);
114
+        if (hasNone || yval == 2 || (hasY && yval < 0)) tmc_clear_otpw(stepperY2, TMC_Y2);
112 115
       #endif
113 116
     #endif
114 117
 
115
-    #if M91x_USE(Z) || M91x_USE(Z2)
116
-      const uint8_t zval = parser.byteval(axis_codes[Z_AXIS], 10);
118
+    #if M91x_USE(Z) || M91x_USE(Z2) || M91x_USE(Z3)
119
+      const int8_t zval = int8_t(parser.byteval(axis_codes[Z_AXIS], 0xFF));
117 120
       #if M91x_USE(Z)
118
-        if (hasNone || zval == 1 || (hasZ && zval == 10)) tmc_clear_otpw(stepperZ, TMC_Z);
121
+        if (hasNone || zval == 1 || (hasZ && zval < 0)) tmc_clear_otpw(stepperZ, TMC_Z);
119 122
       #endif
120 123
       #if M91x_USE(Z2)
121
-        if (hasNone || zval == 2 || (hasZ && zval == 10)) tmc_clear_otpw(stepperZ2, TMC_Z2);
124
+        if (hasNone || zval == 2 || (hasZ && zval < 0)) tmc_clear_otpw(stepperZ2, TMC_Z2);
125
+      #endif
126
+      #if M91x_USE(Z3)
127
+        if (hasNone || zval == 3 || (hasZ && zval < 0)) tmc_clear_otpw(stepperZ3, TMC_Z3);
122 128
       #endif
123 129
     #endif
124 130
 
125 131
     #if M91x_USE_E(0) || M91x_USE_E(1) || M91x_USE_E(2) || M91x_USE_E(3) || M91x_USE_E(4)
126
-      const uint8_t eval = parser.byteval(axis_codes[E_AXIS], 10);
132
+      const int8_t eval = int8_t(parser.byteval(axis_codes[E_AXIS], 0xFF));
127 133
       #if M91x_USE_E(0)
128
-        if (hasNone || eval == 0 || (hasE && eval == 10)) tmc_clear_otpw(stepperE0, TMC_E0);
134
+        if (hasNone || eval == 0 || (hasE && eval < 0)) tmc_clear_otpw(stepperE0, TMC_E0);
129 135
       #endif
130 136
       #if M91x_USE_E(1)
131
-        if (hasNone || eval == 1 || (hasE && eval == 10)) tmc_clear_otpw(stepperE1, TMC_E1);
137
+        if (hasNone || eval == 1 || (hasE && eval < 0)) tmc_clear_otpw(stepperE1, TMC_E1);
132 138
       #endif
133 139
       #if M91x_USE_E(2)
134
-        if (hasNone || eval == 2 || (hasE && eval == 10)) tmc_clear_otpw(stepperE2, TMC_E2);
140
+        if (hasNone || eval == 2 || (hasE && eval < 0)) tmc_clear_otpw(stepperE2, TMC_E2);
135 141
       #endif
136 142
       #if M91x_USE_E(3)
137
-        if (hasNone || eval == 3 || (hasE && eval == 10)) tmc_clear_otpw(stepperE3, TMC_E3);
143
+        if (hasNone || eval == 3 || (hasE && eval < 0)) tmc_clear_otpw(stepperE3, TMC_E3);
138 144
       #endif
139 145
       #if M91x_USE_E(4)
140
-        if (hasNone || eval == 4 || (hasE && eval == 10)) tmc_clear_otpw(stepperE4, TMC_E4);
146
+        if (hasNone || eval == 4 || (hasE && eval < 0)) tmc_clear_otpw(stepperE4, TMC_E4);
141 147
       #endif
142 148
     #endif
143 149
 }
@@ -178,7 +184,10 @@ void GcodeSuite::M912() {
178 184
             if (index < 2) TMC_SET_PWMTHRS(Z,Z);
179 185
           #endif
180 186
           #if AXIS_HAS_STEALTHCHOP(Z2)
181
-            if (!(index & 1)) TMC_SET_PWMTHRS(Z,Z2);
187
+            if (index == 0 || index == 2) TMC_SET_PWMTHRS(Z,Z2);
188
+          #endif
189
+          #if AXIS_HAS_STEALTHCHOP(Z3)
190
+            if (index == 0 || index == 3) TMC_SET_PWMTHRS(Z,Z3);
182 191
           #endif
183 192
           break;
184 193
         case E_AXIS: {
@@ -223,6 +232,9 @@ void GcodeSuite::M912() {
223 232
       #if AXIS_HAS_STEALTHCHOP(Z2)
224 233
         TMC_SAY_PWMTHRS(Z,Z2);
225 234
       #endif
235
+      #if AXIS_HAS_STEALTHCHOP(Z3)
236
+        TMC_SAY_PWMTHRS(Z,Z3);
237
+      #endif
226 238
       #if AXIS_HAS_STEALTHCHOP(E0)
227 239
         TMC_SAY_PWMTHRS_E(0);
228 240
       #endif
@@ -282,7 +294,10 @@ void GcodeSuite::M912() {
282 294
               if (index < 2) TMC_SET_SGT(Z);
283 295
             #endif
284 296
             #if AXIS_HAS_STALLGUARD(Z2)
285
-              if (!(index & 1)) TMC_SET_SGT(Z2);
297
+              if (index == 0 || index == 2) TMC_SET_SGT(Z2);
298
+            #endif
299
+            #if AXIS_HAS_STALLGUARD(Z3)
300
+              if (index == 0 || index == 3) TMC_SET_SGT(Z3);
286 301
             #endif
287 302
             break;
288 303
         #endif
@@ -313,6 +328,9 @@ void GcodeSuite::M912() {
313 328
         #if AXIS_HAS_STALLGUARD(Z2)
314 329
           TMC_SAY_SGT(Z2);
315 330
         #endif
331
+        #if AXIS_HAS_STALLGUARD(Z3)
332
+          TMC_SAY_SGT(Z3);
333
+        #endif
316 334
       #endif
317 335
     }
318 336
   }
@@ -339,6 +357,10 @@ void GcodeSuite::M912() {
339 357
       const uint16_t Z2_current_1 = stepperZ2.getCurrent();
340 358
       stepperZ2.setCurrent(_rms, R_SENSE, HOLD_MULTIPLIER);
341 359
     #endif
360
+    #if Z3_IS_TRINAMIC
361
+      const uint16_t Z3_current_1 = stepperZ3.getCurrent();
362
+      stepperZ3.setCurrent(_rms, R_SENSE, HOLD_MULTIPLIER);
363
+    #endif
342 364
 
343 365
     SERIAL_ECHOPAIR("\nCalibration current: Z", _rms);
344 366
 
@@ -352,6 +374,9 @@ void GcodeSuite::M912() {
352 374
     #if AXIS_IS_TMC(Z2)
353 375
       stepperZ2.setCurrent(Z2_current_1, R_SENSE, HOLD_MULTIPLIER);
354 376
     #endif
377
+    #if AXIS_IS_TMC(Z3)
378
+      stepperZ3.setCurrent(Z3_current_1, R_SENSE, HOLD_MULTIPLIER);
379
+    #endif
355 380
 
356 381
     do_blocking_move_to_z(Z_MAX_POS);
357 382
     soft_endstops_enabled = true;

+ 3
- 0
Marlin/src/inc/Conditionals_LCD.h Ver arquivo

@@ -546,4 +546,7 @@
546 546
 #define HAS_RESUME_CONTINUE (ENABLED(NEWPANEL) || ENABLED(EMERGENCY_PARSER))
547 547
 #define HAS_COLOR_LEDS (ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_LED))
548 548
 
549
+#define Z_MULTI_STEPPER_DRIVERS (ENABLED(Z_DUAL_STEPPER_DRIVERS) || ENABLED(Z_TRIPLE_STEPPER_DRIVERS))
550
+#define Z_MULTI_ENDSTOPS (ENABLED(Z_DUAL_ENDSTOPS) || ENABLED(Z_TRIPLE_ENDSTOPS))
551
+
549 552
 #endif // CONDITIONALS_LCD_H

+ 63
- 2
Marlin/src/inc/Conditionals_post.h Ver arquivo

@@ -611,7 +611,7 @@
611 611
 /**
612 612
  * Z_DUAL_ENDSTOPS endstop reassignment
613 613
  */
614
-#if ENABLED(Z_DUAL_ENDSTOPS)
614
+#if Z_MULTI_ENDSTOPS
615 615
   #if Z_HOME_DIR > 0
616 616
     #if Z2_USE_ENDSTOP == _XMIN_
617 617
       #define Z2_MAX_ENDSTOP_INVERTING X_MIN_ENDSTOP_INVERTING
@@ -661,9 +661,64 @@
661 661
   #endif
662 662
 #endif
663 663
 
664
+#if ENABLED(Z_TRIPLE_ENDSTOPS)
665
+  #if Z_HOME_DIR > 0
666
+    #if Z3_USE_ENDSTOP == _XMIN_
667
+      #define Z3_MAX_ENDSTOP_INVERTING X_MIN_ENDSTOP_INVERTING
668
+      #define Z3_MAX_PIN X_MIN_PIN
669
+    #elif Z3_USE_ENDSTOP == _XMAX_
670
+      #define Z3_MAX_ENDSTOP_INVERTING X_MAX_ENDSTOP_INVERTING
671
+      #define Z3_MAX_PIN X_MAX_PIN
672
+    #elif Z3_USE_ENDSTOP == _YMIN_
673
+      #define Z3_MAX_ENDSTOP_INVERTING Y_MIN_ENDSTOP_INVERTING
674
+      #define Z3_MAX_PIN Y_MIN_PIN
675
+    #elif Z3_USE_ENDSTOP == _YMAX_
676
+      #define Z3_MAX_ENDSTOP_INVERTING Y_MAX_ENDSTOP_INVERTING
677
+      #define Z3_MAX_PIN Y_MAX_PIN
678
+    #elif Z3_USE_ENDSTOP == _ZMIN_
679
+      #define Z3_MAX_ENDSTOP_INVERTING Z_MIN_ENDSTOP_INVERTING
680
+      #define Z3_MAX_PIN Z_MIN_PIN
681
+    #elif Z3_USE_ENDSTOP == _ZMAX_
682
+      #define Z3_MAX_ENDSTOP_INVERTING Z_MAX_ENDSTOP_INVERTING
683
+      #define Z3_MAX_PIN Z_MAX_PIN
684
+    #else
685
+      #define Z3_MAX_ENDSTOP_INVERTING false
686
+    #endif
687
+    #define Z3_MIN_ENDSTOP_INVERTING false
688
+  #else
689
+    #if Z3_USE_ENDSTOP == _XMIN_
690
+      #define Z3_MIN_ENDSTOP_INVERTING X_MIN_ENDSTOP_INVERTING
691
+      #define Z3_MIN_PIN X_MIN_PIN
692
+    #elif Z3_USE_ENDSTOP == _XMAX_
693
+      #define Z3_MIN_ENDSTOP_INVERTING X_MAX_ENDSTOP_INVERTING
694
+      #define Z3_MIN_PIN X_MAX_PIN
695
+    #elif Z3_USE_ENDSTOP == _YMIN_
696
+      #define Z3_MIN_ENDSTOP_INVERTING Y_MIN_ENDSTOP_INVERTING
697
+      #define Z3_MIN_PIN Y_MIN_PIN
698
+    #elif Z3_USE_ENDSTOP == _YMAX_
699
+      #define Z3_MIN_ENDSTOP_INVERTING Y_MAX_ENDSTOP_INVERTING
700
+      #define Z3_MIN_PIN Y_MAX_PIN
701
+    #elif Z3_USE_ENDSTOP == _ZMIN_
702
+      #define Z3_MIN_ENDSTOP_INVERTING Z_MIN_ENDSTOP_INVERTING
703
+      #define Z3_MIN_PIN Z_MIN_PIN
704
+    #elif Z3_USE_ENDSTOP == _ZMAX_
705
+      #define Z3_MIN_ENDSTOP_INVERTING Z_MAX_ENDSTOP_INVERTING
706
+      #define Z3_MIN_PIN Z_MAX_PIN
707
+    #else
708
+      #define Z3_MIN_ENDSTOP_INVERTING false
709
+    #endif
710
+    #define Z3_MAX_ENDSTOP_INVERTING false
711
+  #endif
712
+#endif
713
+
664 714
 // Is an endstop plug used for the Z2 endstop or the bed probe?
665 715
 #define IS_Z2_OR_PROBE(A,M) ( \
666
-     (ENABLED(Z_DUAL_ENDSTOPS) && Z2_USE_ENDSTOP == _##A##M##_) \
716
+     (Z_MULTI_ENDSTOPS && Z2_USE_ENDSTOP == _##A##M##_) \
717
+  || (ENABLED(Z_MIN_PROBE_ENDSTOP) && Z_MIN_PROBE_PIN == A##_##M##_PIN ) )
718
+
719
+// Is an endstop plug used for the Z3 endstop or the bed probe?
720
+#define IS_Z3_OR_PROBE(A,M) ( \
721
+     (ENABLED(Z_TRIPLE_ENDSTOPS) && Z3_USE_ENDSTOP == _##A##M##_) \
667 722
   || (ENABLED(Z_MIN_PROBE_ENDSTOP) && Z_MIN_PROBE_PIN == A##_##M##_PIN ) )
668 723
 
669 724
 /**
@@ -749,6 +804,10 @@
749 804
 #define HAS_Z2_STEP       (PIN_EXISTS(Z2_STEP))
750 805
 #define HAS_Z2_MICROSTEPS (PIN_EXISTS(Z2_MS1))
751 806
 
807
+#define HAS_Z3_ENABLE     (PIN_EXISTS(Z3_ENABLE))
808
+#define HAS_Z3_DIR        (PIN_EXISTS(Z3_DIR))
809
+#define HAS_Z3_STEP       (PIN_EXISTS(Z3_STEP))
810
+
752 811
 // Extruder steppers and solenoids
753 812
 #define HAS_E0_ENABLE     (PIN_EXISTS(E0_ENABLE))
754 813
 #define HAS_E0_DIR        (PIN_EXISTS(E0_DIR))
@@ -810,6 +869,8 @@
810 869
 #define HAS_Y2_MAX (PIN_EXISTS(Y2_MAX))
811 870
 #define HAS_Z2_MIN (PIN_EXISTS(Z2_MIN))
812 871
 #define HAS_Z2_MAX (PIN_EXISTS(Z2_MAX))
872
+#define HAS_Z3_MIN (PIN_EXISTS(Z3_MIN))
873
+#define HAS_Z3_MAX (PIN_EXISTS(Z3_MAX))
813 874
 #define HAS_Z_MIN_PROBE_PIN (PIN_EXISTS(Z_MIN_PROBE))
814 875
 
815 876
 // ADC Temp Sensors (Thermistor or Thermocouple with amplifier ADC interface)

+ 66
- 16
Marlin/src/inc/SanityCheck.h Ver arquivo

@@ -272,19 +272,19 @@
272 272
   #error "HAVE_TMC2130 is now [AXIS]_DRIVER_TYPE TMC2130. Please update your Configuration.h."
273 273
 #elif defined(HAVE_L6470DRIVER)
274 274
   #error "HAVE_L6470DRIVER is now [AXIS]_DRIVER_TYPE L6470. Please update your Configuration.h."
275
-#elif defined(X_IS_TMC) || defined(X2_IS_TMC) || defined(Y_IS_TMC) || defined(Y2_IS_TMC) || defined(Z_IS_TMC) || defined(Z2_IS_TMC) \
275
+#elif defined(X_IS_TMC) || defined(X2_IS_TMC) || defined(Y_IS_TMC) || defined(Y2_IS_TMC) || defined(Z_IS_TMC) || defined(Z2_IS_TMC) || defined(Z3_IS_TMC) \
276 276
    || defined(E0_IS_TMC) || defined(E1_IS_TMC) || defined(E2_IS_TMC) || defined(E3_IS_TMC) || defined(E4_IS_TMC)
277 277
   #error "[AXIS]_IS_TMC is now [AXIS]_DRIVER_TYPE TMC26X. Please update your Configuration.h."
278
-#elif defined(X_IS_TMC26X) || defined(X2_IS_TMC26X) || defined(Y_IS_TMC26X) || defined(Y2_IS_TMC26X) || defined(Z_IS_TMC26X) || defined(Z2_IS_TMC26X) \
278
+#elif defined(X_IS_TMC26X) || defined(X2_IS_TMC26X) || defined(Y_IS_TMC26X) || defined(Y2_IS_TMC26X) || defined(Z_IS_TMC26X) || defined(Z2_IS_TMC26X) || defined(Z3_IS_TMC26X) \
279 279
    || defined(E0_IS_TMC26X) || defined(E1_IS_TMC26X) || defined(E2_IS_TMC26X) || defined(E3_IS_TMC26X) || defined(E4_IS_TMC26X)
280 280
   #error "[AXIS]_IS_TMC26X is now [AXIS]_DRIVER_TYPE TMC26X. Please update your Configuration.h."
281
-#elif defined(X_IS_TMC2130) || defined(X2_IS_TMC2130) || defined(Y_IS_TMC2130) || defined(Y2_IS_TMC2130) || defined(Z_IS_TMC2130) || defined(Z2_IS_TMC2130) \
281
+#elif defined(X_IS_TMC2130) || defined(X2_IS_TMC2130) || defined(Y_IS_TMC2130) || defined(Y2_IS_TMC2130) || defined(Z_IS_TMC2130) || defined(Z2_IS_TMC2130) || defined(Z3_IS_TMC2130) \
282 282
    || defined(E0_IS_TMC2130) || defined(E1_IS_TMC2130) || defined(E2_IS_TMC2130) || defined(E3_IS_TMC2130) || defined(E4_IS_TMC2130)
283 283
   #error "[AXIS]_IS_TMC2130 is now [AXIS]_DRIVER_TYPE TMC2130. Please update your Configuration.h."
284
-#elif defined(X_IS_TMC2208) || defined(X2_IS_TMC2208) || defined(Y_IS_TMC2208) || defined(Y2_IS_TMC2208) || defined(Z_IS_TMC2208) || defined(Z2_IS_TMC2208) \
284
+#elif defined(X_IS_TMC2208) || defined(X2_IS_TMC2208) || defined(Y_IS_TMC2208) || defined(Y2_IS_TMC2208) || defined(Z_IS_TMC2208) || defined(Z2_IS_TMC2208) || defined(Z3_IS_TMC2208) \
285 285
    || defined(E0_IS_TMC2208) || defined(E1_IS_TMC2208) || defined(E2_IS_TMC2208) || defined(E3_IS_TMC2208) || defined(E4_IS_TMC2208)
286 286
   #error "[AXIS]_IS_TMC2208 is now [AXIS]_DRIVER_TYPE TMC2208. Please update your Configuration.h."
287
-#elif defined(X_IS_L6470) || defined(X2_IS_L6470) || defined(Y_IS_L6470) || defined(Y2_IS_L6470) || defined(Z_IS_L6470) || defined(Z2_IS_L6470) \
287
+#elif defined(X_IS_L6470) || defined(X2_IS_L6470) || defined(Y_IS_L6470) || defined(Y2_IS_L6470) || defined(Z_IS_L6470) || defined(Z2_IS_L6470) || defined(Z3_IS_L6470) \
288 288
    || defined(E0_IS_L6470) || defined(E1_IS_L6470) || defined(E2_IS_L6470) || defined(E3_IS_L6470) || defined(E4_IS_L6470)
289 289
   #error "[AXIS]_IS_L6470 is now [AXIS]_DRIVER_TYPE L6470. Please update your Configuration.h."
290 290
 #elif defined(AUTOMATIC_CURRENT_CONTROL)
@@ -365,16 +365,22 @@
365 365
 #endif
366 366
 
367 367
 /**
368
- * Dual Stepper Drivers
368
+ * Dual / Triple Stepper Drivers
369 369
  */
370 370
 #if ENABLED(X_DUAL_STEPPER_DRIVERS) && ENABLED(DUAL_X_CARRIAGE)
371 371
   #error "DUAL_X_CARRIAGE is not compatible with X_DUAL_STEPPER_DRIVERS."
372
-#elif ENABLED(X_DUAL_STEPPER_DRIVERS) && (!HAS_X2_ENABLE || !HAS_X2_STEP || !HAS_X2_DIR)
372
+#elif ENABLED(X_DUAL_STEPPER_DRIVERS) && !(HAS_X2_ENABLE && HAS_X2_STEP && HAS_X2_DIR)
373 373
   #error "X_DUAL_STEPPER_DRIVERS requires X2 pins (and an extra E plug)."
374
-#elif ENABLED(Y_DUAL_STEPPER_DRIVERS) && (!HAS_Y2_ENABLE || !HAS_Y2_STEP || !HAS_Y2_DIR)
374
+#elif ENABLED(Y_DUAL_STEPPER_DRIVERS) && !(HAS_Y2_ENABLE && HAS_Y2_STEP && HAS_Y2_DIR)
375 375
   #error "Y_DUAL_STEPPER_DRIVERS requires Y2 pins (and an extra E plug)."
376
-#elif ENABLED(Z_DUAL_STEPPER_DRIVERS) && (!HAS_Z2_ENABLE || !HAS_Z2_STEP || !HAS_Z2_DIR)
377
-  #error "Z_DUAL_STEPPER_DRIVERS requires Z2 pins (and an extra E plug)."
376
+#elif ENABLED(Z_DUAL_STEPPER_DRIVERS)
377
+  #if ENABLED(Z_TRIPLE_STEPPER_DRIVERS)
378
+    #error "Please select either Z_TRIPLE_STEPPER_DRIVERS or Z_DUAL_STEPPER_DRIVERS, not both."
379
+  #elif !(HAS_Z2_ENABLE && HAS_Z2_STEP && HAS_Z2_DIR)
380
+    #error "Z_DUAL_STEPPER_DRIVERS requires Z2 pins (and an extra E plug)."
381
+  #endif
382
+#elif ENABLED(Z_TRIPLE_STEPPER_DRIVERS) && !(HAS_Z2_ENABLE && HAS_Z2_STEP && HAS_Z2_DIR && HAS_Z3_ENABLE && HAS_Z3_STEP && HAS_Z3_DIR)
383
+  #error "Z_TRIPLE_STEPPER_DRIVERS requires Z3 pins (and two extra E plugs)."
378 384
 #endif
379 385
 
380 386
 /**
@@ -1138,7 +1144,7 @@ static_assert(X_MAX_LENGTH >= X_BED_SIZE && Y_MAX_LENGTH >= Y_BED_SIZE,
1138 1144
     #error "DUAL_X_CARRIAGE requires 2 (or more) extruders."
1139 1145
   #elif CORE_IS_XY || CORE_IS_XZ
1140 1146
     #error "DUAL_X_CARRIAGE cannot be used with COREXY, COREYX, COREXZ, or COREZX."
1141
-  #elif !HAS_X2_ENABLE || !HAS_X2_STEP || !HAS_X2_DIR
1147
+  #elif !(HAS_X2_ENABLE && HAS_X2_STEP && HAS_X2_DIR)
1142 1148
     #error "DUAL_X_CARRIAGE requires X2 stepper pins to be defined."
1143 1149
   #elif !HAS_X_MAX
1144 1150
     #error "DUAL_X_CARRIAGE requires USE_XMAX_PLUG and an X Max Endstop."
@@ -1301,23 +1307,24 @@ static_assert(X_MAX_LENGTH >= X_BED_SIZE && Y_MAX_LENGTH >= Y_BED_SIZE,
1301 1307
  */
1302 1308
 #if DISABLED(MK2_MULTIPLEXER) // MK2_MULTIPLEXER uses E0 stepper only
1303 1309
   #if E_STEPPERS > 4
1304
-    #if !PIN_EXISTS(E4_STEP) || !PIN_EXISTS(E4_DIR) || !PIN_EXISTS(E4_ENABLE)
1310
+    #if !(PIN_EXISTS(E4_STEP) && PIN_EXISTS(E4_DIR) && PIN_EXISTS(E4_ENABLE))
1305 1311
       #error "E4_STEP_PIN, E4_DIR_PIN, or E4_ENABLE_PIN not defined for this board."
1306 1312
     #endif
1307 1313
   #elif E_STEPPERS > 3
1308
-    #if !PIN_EXISTS(E3_STEP) || !PIN_EXISTS(E3_DIR) || !PIN_EXISTS(E3_ENABLE)
1314
+    #if !(PIN_EXISTS(E3_STEP) && PIN_EXISTS(E3_DIR) && PIN_EXISTS(E3_ENABLE))
1309 1315
       #error "E3_STEP_PIN, E3_DIR_PIN, or E3_ENABLE_PIN not defined for this board."
1310 1316
     #endif
1311 1317
   #elif E_STEPPERS > 2
1312
-    #if !PIN_EXISTS(E2_STEP) || !PIN_EXISTS(E2_DIR) || !PIN_EXISTS(E2_ENABLE)
1318
+    #if !(PIN_EXISTS(E2_STEP) && PIN_EXISTS(E2_DIR) && PIN_EXISTS(E2_ENABLE))
1313 1319
       #error "E2_STEP_PIN, E2_DIR_PIN, or E2_ENABLE_PIN not defined for this board."
1314 1320
     #endif
1315 1321
   #elif E_STEPPERS > 1
1316
-    #if !PIN_EXISTS(E1_STEP) || !PIN_EXISTS(E1_DIR) || !PIN_EXISTS(E1_ENABLE)
1322
+    #if !(PIN_EXISTS(E1_STEP) && PIN_EXISTS(E1_DIR) && PIN_EXISTS(E1_ENABLE))
1317 1323
       #error "E1_STEP_PIN, E1_DIR_PIN, or E1_ENABLE_PIN not defined for this board."
1318 1324
     #endif
1319 1325
   #endif
1320 1326
 #endif
1327
+
1321 1328
 /**
1322 1329
  * Endstop Tests
1323 1330
  */
@@ -1418,6 +1425,46 @@ static_assert(X_MAX_LENGTH >= X_BED_SIZE && Y_MAX_LENGTH >= Y_BED_SIZE,
1418 1425
     #error "Z_DUAL_ENDSTOPS is not compatible with DELTA."
1419 1426
   #endif
1420 1427
 #endif
1428
+#if ENABLED(Z_TRIPLE_ENDSTOPS)
1429
+  #if !Z2_USE_ENDSTOP
1430
+    #error "You must set Z2_USE_ENDSTOP with Z_TRIPLE_ENDSTOPS."
1431
+  #elif Z2_USE_ENDSTOP == _XMIN_ && DISABLED(USE_XMIN_PLUG)
1432
+    #error "USE_XMIN_PLUG is required when Z2_USE_ENDSTOP is _XMIN_."
1433
+  #elif Z2_USE_ENDSTOP == _XMAX_ && DISABLED(USE_XMAX_PLUG)
1434
+    #error "USE_XMAX_PLUG is required when Z2_USE_ENDSTOP is _XMAX_."
1435
+  #elif Z2_USE_ENDSTOP == _YMIN_ && DISABLED(USE_YMIN_PLUG)
1436
+    #error "USE_YMIN_PLUG is required when Z2_USE_ENDSTOP is _YMIN_."
1437
+  #elif Z2_USE_ENDSTOP == _YMAX_ && DISABLED(USE_YMAX_PLUG)
1438
+    #error "USE_YMAX_PLUG is required when Z2_USE_ENDSTOP is _YMAX_."
1439
+  #elif Z2_USE_ENDSTOP == _ZMIN_ && DISABLED(USE_ZMIN_PLUG)
1440
+    #error "USE_ZMIN_PLUG is required when Z2_USE_ENDSTOP is _ZMIN_."
1441
+  #elif Z2_USE_ENDSTOP == _ZMAX_ && DISABLED(USE_ZMAX_PLUG)
1442
+    #error "USE_ZMAX_PLUG is required when Z2_USE_ENDSTOP is _ZMAX_."
1443
+  #elif !HAS_Z2_MIN && !HAS_Z2_MAX
1444
+    #error "Z2_USE_ENDSTOP has been assigned to a nonexistent endstop!"
1445
+  #elif ENABLED(DELTA)
1446
+    #error "Z_TRIPLE_ENDSTOPS is not compatible with DELTA."
1447
+  #endif
1448
+  #if !Z3_USE_ENDSTOP
1449
+    #error "You must set Z3_USE_ENDSTOP with Z_TRIPLE_ENDSTOPS."
1450
+  #elif Z3_USE_ENDSTOP == _XMIN_ && DISABLED(USE_XMIN_PLUG)
1451
+    #error "USE_XMIN_PLUG is required when Z3_USE_ENDSTOP is _XMIN_."
1452
+  #elif Z3_USE_ENDSTOP == _XMAX_ && DISABLED(USE_XMAX_PLUG)
1453
+    #error "USE_XMAX_PLUG is required when Z3_USE_ENDSTOP is _XMAX_."
1454
+  #elif Z3_USE_ENDSTOP == _YMIN_ && DISABLED(USE_YMIN_PLUG)
1455
+    #error "USE_YMIN_PLUG is required when Z3_USE_ENDSTOP is _YMIN_."
1456
+  #elif Z3_USE_ENDSTOP == _YMAX_ && DISABLED(USE_YMAX_PLUG)
1457
+    #error "USE_YMAX_PLUG is required when Z3_USE_ENDSTOP is _YMAX_."
1458
+  #elif Z3_USE_ENDSTOP == _ZMIN_ && DISABLED(USE_ZMIN_PLUG)
1459
+    #error "USE_ZMIN_PLUG is required when Z3_USE_ENDSTOP is _ZMIN_."
1460
+  #elif Z3_USE_ENDSTOP == _ZMAX_ && DISABLED(USE_ZMAX_PLUG)
1461
+    #error "USE_ZMAX_PLUG is required when Z3_USE_ENDSTOP is _ZMAX_."
1462
+  #elif !HAS_Z3_MIN && !HAS_Z3_MAX
1463
+    #error "Z3_USE_ENDSTOP has been assigned to a nonexistent endstop!"
1464
+  #elif ENABLED(DELTA)
1465
+    #error "Z_TRIPLE_ENDSTOPS is not compatible with DELTA."
1466
+  #endif
1467
+#endif
1421 1468
 
1422 1469
 /**
1423 1470
  * emergency-command parser
@@ -1566,6 +1613,8 @@ static_assert(X_MAX_LENGTH >= X_BED_SIZE && Y_MAX_LENGTH >= Y_BED_SIZE,
1566 1613
   #error "Z_CS_PIN is required for TMC2130. Define Z_CS_PIN in Configuration_adv.h."
1567 1614
 #elif AXIS_DRIVER_TYPE(Z2, TMC2130) && !PIN_EXISTS(Z2_CS)
1568 1615
   #error "Z2_CS_PIN is required for TMC2130. Define Z2_CS_PIN in Configuration_adv.h."
1616
+#elif AXIS_DRIVER_TYPE(Z3, TMC2130) && !PIN_EXISTS(Z3_CS)
1617
+  #error "Z3_CS_PIN is required for TMC2130. Define Z3_CS_PIN in Configuration_adv.h."
1569 1618
 #elif AXIS_DRIVER_TYPE(E0, TMC2130) && !PIN_EXISTS(E0_CS)
1570 1619
   #error "E0_CS_PIN is required for TMC2130. Define E0_CS_PIN in Configuration_adv.h."
1571 1620
 #elif AXIS_DRIVER_TYPE(E1, TMC2130) && !PIN_EXISTS(E1_CS)
@@ -1588,6 +1637,7 @@ static_assert(X_MAX_LENGTH >= X_BED_SIZE && Y_MAX_LENGTH >= Y_BED_SIZE,
1588 1637
     || defined(Y2_HARDWARE_SERIAL) \
1589 1638
     || defined(Z_HARDWARE_SERIAL ) \
1590 1639
     || defined(Z2_HARDWARE_SERIAL) \
1640
+    || defined(Z3_HARDWARE_SERIAL) \
1591 1641
     || defined(E0_HARDWARE_SERIAL) \
1592 1642
     || defined(E1_HARDWARE_SERIAL) \
1593 1643
     || defined(E2_HARDWARE_SERIAL) \
@@ -1650,7 +1700,7 @@ static_assert(X_MAX_LENGTH >= X_BED_SIZE && Y_MAX_LENGTH >= Y_BED_SIZE,
1650 1700
 #if ENABLED(HYBRID_THRESHOLD) && DISABLED(STEALTHCHOP)
1651 1701
   #error "Enable STEALTHCHOP to use HYBRID_THRESHOLD."
1652 1702
 #endif
1653
-#if ENABLED(TMC_Z_CALIBRATION) && !AXIS_IS_TMC(Z) && !AXIS_IS_TMC(Z2)
1703
+#if ENABLED(TMC_Z_CALIBRATION) && !AXIS_IS_TMC(Z) && !AXIS_IS_TMC(Z2) && !AXIS_IS_TMC(Z3)
1654 1704
   #error "TMC_Z_CALIBRATION requires at least one TMC driver on Z axis"
1655 1705
 #endif
1656 1706
 

+ 97
- 29
Marlin/src/module/configuration_store.cpp Ver arquivo

@@ -194,10 +194,13 @@ typedef struct SettingsDataStruct {
194 194
           delta_segments_per_second,                    // M665 S
195 195
           delta_calibration_radius,                     // M665 B
196 196
           delta_tower_angle_trim[ABC];                  // M665 XYZ
197
-  #elif ENABLED(X_DUAL_ENDSTOPS) || ENABLED(Y_DUAL_ENDSTOPS) || ENABLED(Z_DUAL_ENDSTOPS)
198
-    float x_endstop_adj,                                // M666 X
199
-          y_endstop_adj,                                // M666 Y
200
-          z_endstop_adj;                                // M666 Z
197
+  #elif ENABLED(X_DUAL_ENDSTOPS) || ENABLED(Y_DUAL_ENDSTOPS) || Z_MULTI_ENDSTOPS
198
+    float x2_endstop_adj,                                // M666 X
199
+          y2_endstop_adj,                                // M666 Y
200
+          z2_endstop_adj;                                // M666 Z
201
+    #if ENABLED(Z_TRIPLE_ENDSTOPS)
202
+      float z3_endstop_adj;                             // M666 Z
203
+    #endif
201 204
   #endif
202 205
 
203 206
   //
@@ -246,9 +249,9 @@ typedef struct SettingsDataStruct {
246 249
   //
247 250
   // HAS_TRINAMIC
248 251
   //
249
-  #define TMC_AXES (MAX_EXTRUDERS + 6)
250
-  uint16_t tmc_stepper_current[TMC_AXES];               // M906 X Y Z X2 Y2 Z2 E0 E1 E2 E3 E4
251
-  uint32_t tmc_hybrid_threshold[TMC_AXES];              // M913 X Y Z X2 Y2 Z2 E0 E1 E2 E3 E4
252
+  #define TMC_AXES (MAX_EXTRUDERS + 7)
253
+  uint16_t tmc_stepper_current[TMC_AXES];               // M906 X Y Z X2 Y2 Z2 Z3 E0 E1 E2 E3 E4
254
+  uint32_t tmc_hybrid_threshold[TMC_AXES];              // M913 X Y Z X2 Y2 Z2 Z3 E0 E1 E2 E3 E4
252 255
   int16_t tmc_sgt[XYZ];                                 // M914 X Y Z
253 256
 
254 257
   //
@@ -574,26 +577,32 @@ void MarlinSettings::postprocess() {
574 577
       EEPROM_WRITE(delta_calibration_radius);  // 1 float
575 578
       EEPROM_WRITE(delta_tower_angle_trim);    // 3 floats
576 579
 
577
-    #elif ENABLED(X_DUAL_ENDSTOPS) || ENABLED(Y_DUAL_ENDSTOPS) || ENABLED(Z_DUAL_ENDSTOPS)
580
+    #elif ENABLED(X_DUAL_ENDSTOPS) || ENABLED(Y_DUAL_ENDSTOPS) || Z_MULTI_ENDSTOPS
578 581
 
579
-      _FIELD_TEST(x_endstop_adj);
582
+      _FIELD_TEST(x2_endstop_adj);
580 583
 
581 584
       // Write dual endstops in X, Y, Z order. Unused = 0.0
582 585
       dummy = 0;
583 586
       #if ENABLED(X_DUAL_ENDSTOPS)
584
-        EEPROM_WRITE(endstops.x_endstop_adj);   // 1 float
587
+        EEPROM_WRITE(endstops.x2_endstop_adj);   // 1 float
585 588
       #else
586 589
         EEPROM_WRITE(dummy);
587 590
       #endif
588 591
 
589 592
       #if ENABLED(Y_DUAL_ENDSTOPS)
590
-        EEPROM_WRITE(endstops.y_endstop_adj);   // 1 float
593
+        EEPROM_WRITE(endstops.y2_endstop_adj);   // 1 float
591 594
       #else
592 595
         EEPROM_WRITE(dummy);
593 596
       #endif
594 597
 
595
-      #if ENABLED(Z_DUAL_ENDSTOPS)
596
-        EEPROM_WRITE(endstops.z_endstop_adj);   // 1 float
598
+      #if Z_MULTI_ENDSTOPS
599
+        EEPROM_WRITE(endstops.z2_endstop_adj);   // 1 float
600
+      #else
601
+        EEPROM_WRITE(dummy);
602
+      #endif
603
+
604
+      #if ENABLED(Z_TRIPLE_ENDSTOPS)
605
+        EEPROM_WRITE(endstops.z3_endstop_adj);   // 1 float
597 606
       #else
598 607
         EEPROM_WRITE(dummy);
599 608
       #endif
@@ -740,6 +749,11 @@ void MarlinSettings::postprocess() {
740 749
         #else
741 750
           0,
742 751
         #endif
752
+        #if AXIS_IS_TMC(Z3)
753
+          stepperZ3.getCurrent(),
754
+        #else
755
+          0,
756
+        #endif
743 757
         #if AXIS_IS_TMC(E0)
744 758
           stepperE0.getCurrent(),
745 759
         #else
@@ -809,6 +823,11 @@ void MarlinSettings::postprocess() {
809 823
         #else
810 824
           Z2_HYBRID_THRESHOLD,
811 825
         #endif
826
+        #if AXIS_HAS_STEALTHCHOP(Z3)
827
+          TMC_GET_PWMTHRS(Z, Z3),
828
+        #else
829
+          Z3_HYBRID_THRESHOLD,
830
+        #endif
812 831
         #if AXIS_HAS_STEALTHCHOP(E0)
813 832
           TMC_GET_PWMTHRS(E, E0),
814 833
         #else
@@ -836,7 +855,7 @@ void MarlinSettings::postprocess() {
836 855
         #endif
837 856
       #else
838 857
         100, 100, 3,          // X, Y, Z
839
-        100, 100, 3,          // X2, Y2, Z2
858
+        100, 100, 3, 3,       // X2, Y2, Z2, Z3
840 859
         30, 30, 30, 30, 30    // E0, E1, E2, E3, E4
841 860
       #endif
842 861
     };
@@ -1187,22 +1206,27 @@ void MarlinSettings::postprocess() {
1187 1206
         EEPROM_READ(delta_calibration_radius);  // 1 float
1188 1207
         EEPROM_READ(delta_tower_angle_trim);    // 3 floats
1189 1208
 
1190
-      #elif ENABLED(X_DUAL_ENDSTOPS) || ENABLED(Y_DUAL_ENDSTOPS) || ENABLED(Z_DUAL_ENDSTOPS)
1209
+      #elif ENABLED(X_DUAL_ENDSTOPS) || ENABLED(Y_DUAL_ENDSTOPS) || Z_MULTI_ENDSTOPS
1191 1210
 
1192
-        _FIELD_TEST(x_endstop_adj);
1211
+        _FIELD_TEST(x2_endstop_adj);
1193 1212
 
1194 1213
         #if ENABLED(X_DUAL_ENDSTOPS)
1195
-          EEPROM_READ(endstops.x_endstop_adj);  // 1 float
1214
+          EEPROM_READ(endstops.x2_endstop_adj);  // 1 float
1196 1215
         #else
1197 1216
           EEPROM_READ(dummy);
1198 1217
         #endif
1199 1218
         #if ENABLED(Y_DUAL_ENDSTOPS)
1200
-          EEPROM_READ(endstops.y_endstop_adj);  // 1 float
1219
+          EEPROM_READ(endstops.y2_endstop_adj);  // 1 float
1220
+        #else
1221
+          EEPROM_READ(dummy);
1222
+        #endif
1223
+        #if Z_MULTI_ENDSTOPS
1224
+          EEPROM_READ(endstops.z2_endstop_adj); // 1 float
1201 1225
         #else
1202 1226
           EEPROM_READ(dummy);
1203 1227
         #endif
1204
-        #if ENABLED(Z_DUAL_ENDSTOPS)
1205
-          EEPROM_READ(endstops.z_endstop_adj); // 1 float
1228
+        #if ENABLED(Z_TRIPLE_ENDSTOPS)
1229
+          EEPROM_READ(endstops.z3_endstop_adj); // 1 float
1206 1230
         #else
1207 1231
           EEPROM_READ(dummy);
1208 1232
         #endif
@@ -1365,6 +1389,9 @@ void MarlinSettings::postprocess() {
1365 1389
           #if AXIS_IS_TMC(Z2)
1366 1390
             SET_CURR(Z2);
1367 1391
           #endif
1392
+          #if AXIS_IS_TMC(Z3)
1393
+            SET_CURR(Z3);
1394
+          #endif
1368 1395
           #if AXIS_IS_TMC(E0)
1369 1396
             SET_CURR(E0);
1370 1397
           #endif
@@ -1409,6 +1436,9 @@ void MarlinSettings::postprocess() {
1409 1436
           #if AXIS_HAS_STEALTHCHOP(Z2)
1410 1437
             TMC_SET_PWMTHRS(Z, Z2);
1411 1438
           #endif
1439
+          #if AXIS_HAS_STEALTHCHOP(Z3)
1440
+            TMC_SET_PWMTHRS(Z, Z3);
1441
+          #endif
1412 1442
           #if AXIS_HAS_STEALTHCHOP(E0)
1413 1443
             TMC_SET_PWMTHRS(E, E0);
1414 1444
           #endif
@@ -1434,7 +1464,7 @@ void MarlinSettings::postprocess() {
1434 1464
        * TMC2130 Sensorless homing threshold.
1435 1465
        * X and X2 use the same value
1436 1466
        * Y and Y2 use the same value
1437
-       * Z and Z2 use the same value
1467
+       * Z, Z2 and Z3 use the same value
1438 1468
        */
1439 1469
       int16_t tmc_sgt[XYZ];
1440 1470
       EEPROM_READ(tmc_sgt);
@@ -1463,6 +1493,9 @@ void MarlinSettings::postprocess() {
1463 1493
             #if AXIS_HAS_STALLGUARD(Z2)
1464 1494
               stepperZ2.sgt(tmc_sgt[2]);
1465 1495
             #endif
1496
+            #if AXIS_HAS_STALLGUARD(Z3)
1497
+              stepperZ3.sgt(tmc_sgt[2]);
1498
+            #endif
1466 1499
           #endif
1467 1500
         }
1468 1501
       #endif
@@ -1860,10 +1893,10 @@ void MarlinSettings::reset(PORTARG_SOLO) {
1860 1893
     delta_calibration_radius = DELTA_CALIBRATION_RADIUS;
1861 1894
     COPY(delta_tower_angle_trim, dta);
1862 1895
 
1863
-  #elif ENABLED(X_DUAL_ENDSTOPS) || ENABLED(Y_DUAL_ENDSTOPS) || ENABLED(Z_DUAL_ENDSTOPS)
1896
+  #elif ENABLED(X_DUAL_ENDSTOPS) || ENABLED(Y_DUAL_ENDSTOPS) || Z_MULTI_ENDSTOPS
1864 1897
 
1865 1898
     #if ENABLED(X_DUAL_ENDSTOPS)
1866
-      endstops.x_endstop_adj = (
1899
+      endstops.x2_endstop_adj = (
1867 1900
         #ifdef X_DUAL_ENDSTOPS_ADJUSTMENT
1868 1901
           X_DUAL_ENDSTOPS_ADJUSTMENT
1869 1902
         #else
@@ -1872,7 +1905,7 @@ void MarlinSettings::reset(PORTARG_SOLO) {
1872 1905
       );
1873 1906
     #endif
1874 1907
     #if ENABLED(Y_DUAL_ENDSTOPS)
1875
-      endstops.y_endstop_adj = (
1908
+      endstops.y2_endstop_adj = (
1876 1909
         #ifdef Y_DUAL_ENDSTOPS_ADJUSTMENT
1877 1910
           Y_DUAL_ENDSTOPS_ADJUSTMENT
1878 1911
         #else
@@ -1881,13 +1914,28 @@ void MarlinSettings::reset(PORTARG_SOLO) {
1881 1914
       );
1882 1915
     #endif
1883 1916
     #if ENABLED(Z_DUAL_ENDSTOPS)
1884
-      endstops.z_endstop_adj = (
1917
+      endstops.z2_endstop_adj = (
1885 1918
         #ifdef Z_DUAL_ENDSTOPS_ADJUSTMENT
1886 1919
           Z_DUAL_ENDSTOPS_ADJUSTMENT
1887 1920
         #else
1888 1921
           0
1889 1922
         #endif
1890 1923
       );
1924
+    #elif ENABLED(Z_TRIPLE_ENDSTOPS)
1925
+      endstops.z2_endstop_adj = (
1926
+        #ifdef Z_TRIPLE_ENDSTOPS_ADJUSTMENT2
1927
+          Z_TRIPLE_ENDSTOPS_ADJUSTMENT2
1928
+        #else
1929
+          0
1930
+        #endif
1931
+      );
1932
+      endstops.z3_endstop_adj = (
1933
+        #ifdef Z_TRIPLE_ENDSTOPS_ADJUSTMENT3
1934
+          Z_TRIPLE_ENDSTOPS_ADJUSTMENT3
1935
+        #else
1936
+          0
1937
+        #endif
1938
+      );
1891 1939
     #endif
1892 1940
 
1893 1941
   #endif
@@ -2391,13 +2439,17 @@ void MarlinSettings::reset(PORTARG_SOLO) {
2391 2439
       CONFIG_ECHO_START;
2392 2440
       SERIAL_ECHOPGM_P(port, "  M666");
2393 2441
       #if ENABLED(X_DUAL_ENDSTOPS)
2394
-        SERIAL_ECHOPAIR_P(port, " X", LINEAR_UNIT(endstops.x_endstop_adj));
2442
+        SERIAL_ECHOPAIR_P(port, " X", LINEAR_UNIT(endstops.x2_endstop_adj));
2395 2443
       #endif
2396 2444
       #if ENABLED(Y_DUAL_ENDSTOPS)
2397
-        SERIAL_ECHOPAIR_P(port, " Y", LINEAR_UNIT(endstops.y_endstop_adj));
2445
+        SERIAL_ECHOPAIR_P(port, " Y", LINEAR_UNIT(endstops.y2_endstop_adj));
2398 2446
       #endif
2399
-      #if ENABLED(Z_DUAL_ENDSTOPS)
2400
-        SERIAL_ECHOPAIR_P(port, " Z", LINEAR_UNIT(endstops.z_endstop_adj));
2447
+      #if ENABLED(Z_TRIPLE_ENDSTOPS)
2448
+        SERIAL_ECHOLNPAIR_P(port, "S1 Z", LINEAR_UNIT(endstops.z2_endstop_adj));
2449
+        CONFIG_ECHO_START;
2450
+        SERIAL_ECHOPAIR_P(port, "  M666 S2 Z", LINEAR_UNIT(endstops.z3_endstop_adj));
2451
+      #elif ENABLED(Z_DUAL_ENDSTOPS)
2452
+        SERIAL_ECHOPAIR_P(port, " Z", LINEAR_UNIT(endstops.z2_endstop_adj));
2401 2453
       #endif
2402 2454
       SERIAL_EOL_P(port);
2403 2455
 
@@ -2582,6 +2634,10 @@ void MarlinSettings::reset(PORTARG_SOLO) {
2582 2634
       #if AXIS_IS_TMC(X2) || AXIS_IS_TMC(Y2) || AXIS_IS_TMC(Z2)
2583 2635
         SERIAL_EOL_P(port);
2584 2636
       #endif
2637
+      #if AXIS_IS_TMC(Z3)
2638
+        say_M906(PORTVAR_SOLO);
2639
+        SERIAL_ECHOLNPAIR_P(port, " I2 Z", stepperZ3.getCurrent());
2640
+      #endif
2585 2641
       #if AXIS_IS_TMC(E0)
2586 2642
         say_M906(PORTVAR_SOLO);
2587 2643
         SERIAL_ECHOLNPAIR_P(port, " T0 E", stepperE0.getCurrent());
@@ -2644,6 +2700,11 @@ void MarlinSettings::reset(PORTARG_SOLO) {
2644 2700
         #if AXIS_IS_TMC(X2) || AXIS_IS_TMC(Y2) || AXIS_IS_TMC(Z2)
2645 2701
           SERIAL_EOL_P(port);
2646 2702
         #endif
2703
+        #if AXIS_IS_TMC(Z3)
2704
+          say_M913(PORTVAR_SOLO);
2705
+          SERIAL_ECHOPGM_P(port, " I2");
2706
+          SERIAL_ECHOLNPAIR_P(port, " Z", TMC_GET_PWMTHRS(Z, Z3));
2707
+        #endif
2647 2708
         #if AXIS_IS_TMC(E0)
2648 2709
           say_M913(PORTVAR_SOLO);
2649 2710
           SERIAL_ECHOLNPAIR_P(port, " T0 E", TMC_GET_PWMTHRS(E, E0));
@@ -2693,6 +2754,7 @@ void MarlinSettings::reset(PORTARG_SOLO) {
2693 2754
         #define HAS_X2_SENSORLESS (defined(X_HOMING_SENSITIVITY) && AXIS_HAS_STALLGUARD(X2))
2694 2755
         #define HAS_Y2_SENSORLESS (defined(Y_HOMING_SENSITIVITY) && AXIS_HAS_STALLGUARD(Y2))
2695 2756
         #define HAS_Z2_SENSORLESS (defined(Z_HOMING_SENSITIVITY) && AXIS_HAS_STALLGUARD(Z2))
2757
+        #define HAS_Z3_SENSORLESS (defined(Z_HOMING_SENSITIVITY) && AXIS_HAS_STALLGUARD(Z3))
2696 2758
         #if HAS_X2_SENSORLESS || HAS_Y2_SENSORLESS || HAS_Z2_SENSORLESS
2697 2759
           say_M914(PORTVAR_SOLO);
2698 2760
           SERIAL_ECHOPGM_P(port, " I1");
@@ -2708,6 +2770,12 @@ void MarlinSettings::reset(PORTARG_SOLO) {
2708 2770
           SERIAL_EOL_P(port);
2709 2771
         #endif
2710 2772
 
2773
+        #if HAS_Z3_SENSORLESS
2774
+          say_M914(PORTVAR_SOLO);
2775
+          SERIAL_ECHOPGM_P(port, " I2");
2776
+          SERIAL_ECHOLNPAIR_P(port, " Z", stepperZ3.sgt());
2777
+        #endif
2778
+
2711 2779
       #endif // SENSORLESS_HOMING
2712 2780
 
2713 2781
     #endif // HAS_TRINAMIC

+ 78
- 9
Marlin/src/module/endstops.cpp Ver arquivo

@@ -56,13 +56,16 @@ Endstops::esbits_t Endstops::live_state = 0;
56 56
 
57 57
 // Initialized by settings.load()
58 58
 #if ENABLED(X_DUAL_ENDSTOPS)
59
-  float Endstops::x_endstop_adj;
59
+  float Endstops::x2_endstop_adj;
60 60
 #endif
61 61
 #if ENABLED(Y_DUAL_ENDSTOPS)
62
-  float Endstops::y_endstop_adj;
62
+  float Endstops::y2_endstop_adj;
63 63
 #endif
64
-#if ENABLED(Z_DUAL_ENDSTOPS)
65
-  float Endstops::z_endstop_adj;
64
+#if Z_MULTI_ENDSTOPS
65
+  float Endstops::z2_endstop_adj;
66
+#endif
67
+#if ENABLED(Z_TRIPLE_ENDSTOPS)
68
+  float Endstops::z3_endstop_adj;
66 69
 #endif
67 70
 
68 71
 /**
@@ -131,6 +134,16 @@ void Endstops::init() {
131 134
     #endif
132 135
   #endif
133 136
 
137
+  #if HAS_Z3_MIN
138
+    #if ENABLED(ENDSTOPPULLUP_ZMIN)
139
+      SET_INPUT_PULLUP(Z3_MIN_PIN);
140
+    #elif ENABLED(ENDSTOPPULLDOWN_ZMIN)
141
+      SET_INPUT_PULLDOWN(Z3_MIN_PIN);
142
+    #else
143
+      SET_INPUT(Z3_MIN_PIN);
144
+    #endif
145
+  #endif
146
+
134 147
   #if HAS_X_MAX
135 148
     #if ENABLED(ENDSTOPPULLUP_XMAX)
136 149
       SET_INPUT_PULLUP(X_MAX_PIN);
@@ -191,6 +204,16 @@ void Endstops::init() {
191 204
     #endif
192 205
   #endif
193 206
 
207
+  #if HAS_Z3_MAX
208
+    #if ENABLED(ENDSTOPPULLUP_ZMAX)
209
+      SET_INPUT_PULLUP(Z3_MAX_PIN);
210
+    #elif ENABLED(ENDSTOPPULLDOWN_ZMAX)
211
+      SET_INPUT_PULLDOWN(Z3_MAX_PIN);
212
+    #else
213
+      SET_INPUT(Z3_MAX_PIN);
214
+    #endif
215
+  #endif
216
+
194 217
   #if ENABLED(Z_MIN_PROBE_ENDSTOP)
195 218
     #if ENABLED(ENDSTOPPULLUP_ZMIN_PROBE)
196 219
       SET_INPUT_PULLUP(Z_MIN_PROBE_PIN);
@@ -371,12 +394,18 @@ void Endstops::M119() {
371 394
   #if HAS_Z2_MIN
372 395
     ES_REPORT(Z2_MIN);
373 396
   #endif
397
+  #if HAS_Z3_MIN
398
+    ES_REPORT(Z3_MIN);
399
+  #endif
374 400
   #if HAS_Z_MAX
375 401
     ES_REPORT(Z_MAX);
376 402
   #endif
377 403
   #if HAS_Z2_MAX
378 404
     ES_REPORT(Z2_MAX);
379 405
   #endif
406
+  #if HAS_Z3_MAX
407
+    ES_REPORT(Z3_MAX);
408
+  #endif
380 409
   #if ENABLED(Z_MIN_PROBE_ENDSTOP)
381 410
     SERIAL_PROTOCOLPGM(MSG_Z_PROBE);
382 411
     SERIAL_PROTOCOLLN(((READ(Z_MIN_PROBE_PIN)^Z_MIN_PROBE_ENDSTOP_INVERTING) ? MSG_ENDSTOP_HIT : MSG_ENDSTOP_OPEN));
@@ -492,13 +521,20 @@ void Endstops::update() {
492 521
   #endif
493 522
 
494 523
   #if HAS_Z_MIN
495
-    #if ENABLED(Z_DUAL_ENDSTOPS)
524
+    #if Z_MULTI_ENDSTOPS
496 525
       UPDATE_ENDSTOP_BIT(Z, MIN);
497 526
       #if HAS_Z2_MIN
498 527
         UPDATE_ENDSTOP_BIT(Z2, MIN);
499 528
       #else
500 529
         COPY_LIVE_STATE(Z_MIN, Z2_MIN);
501 530
       #endif
531
+      #if ENABLED(Z_TRIPLE_ENDSTOPS)
532
+        #if HAS_Z3_MIN
533
+          UPDATE_ENDSTOP_BIT(Z3, MIN);
534
+        #else
535
+          COPY_LIVE_STATE(Z_MIN, Z3_MIN);
536
+        #endif
537
+      #endif
502 538
     #elif ENABLED(Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN)
503 539
       UPDATE_ENDSTOP_BIT(Z, MIN);
504 540
     #elif Z_HOME_DIR < 0
@@ -513,13 +549,20 @@ void Endstops::update() {
513 549
 
514 550
   #if HAS_Z_MAX
515 551
     // Check both Z dual endstops
516
-    #if ENABLED(Z_DUAL_ENDSTOPS)
552
+    #if Z_MULTI_ENDSTOPS
517 553
       UPDATE_ENDSTOP_BIT(Z, MAX);
518 554
       #if HAS_Z2_MAX
519 555
         UPDATE_ENDSTOP_BIT(Z2, MAX);
520 556
       #else
521 557
         COPY_LIVE_STATE(Z_MAX, Z2_MAX);
522 558
       #endif
559
+      #if ENABLED(Z_TRIPLE_ENDSTOPS)
560
+        #if HAS_Z3_MAX
561
+          UPDATE_ENDSTOP_BIT(Z3, MAX);
562
+        #else
563
+          COPY_LIVE_STATE(Z_MAX, Z3_MAX);
564
+        #endif
565
+      #endif
523 566
     #elif DISABLED(Z_MIN_PROBE_ENDSTOP) || Z_MAX_PIN != Z_MIN_PROBE_PIN
524 567
       // If this pin isn't the bed probe it's the Z endstop
525 568
       UPDATE_ENDSTOP_BIT(Z, MAX);
@@ -569,7 +612,17 @@ void Endstops::update() {
569 612
     if (dual_hit) { \
570 613
       _ENDSTOP_HIT(AXIS1, MINMAX); \
571 614
       /* if not performing home or if both endstops were trigged during homing... */ \
572
-      if (!stepper.homing_dual_axis || dual_hit == 0b11) \
615
+      if (!stepper.separate_multi_axis || dual_hit == 0b11) \
616
+        planner.endstop_triggered(_AXIS(AXIS1)); \
617
+    } \
618
+  }while(0)
619
+
620
+  #define PROCESS_TRIPLE_ENDSTOP(AXIS1, AXIS2, AXIS3, MINMAX) do { \
621
+    const byte triple_hit = TEST_ENDSTOP(_ENDSTOP(AXIS1, MINMAX)) | (TEST_ENDSTOP(_ENDSTOP(AXIS2, MINMAX)) << 1) | (TEST_ENDSTOP(_ENDSTOP(AXIS3, MINMAX)) << 2); \
622
+    if (triple_hit) { \
623
+      _ENDSTOP_HIT(AXIS1, MINMAX); \
624
+      /* if not performing home or if both endstops were trigged during homing... */ \
625
+      if (!stepper.separate_multi_axis || triple_hit == 0x7) \
573 626
         planner.endstop_triggered(_AXIS(AXIS1)); \
574 627
     } \
575 628
   }while(0)
@@ -632,7 +685,9 @@ void Endstops::update() {
632 685
   if (stepper.axis_is_moving(Z_AXIS)) {
633 686
     if (stepper.motor_direction(Z_AXIS_HEAD)) { // Z -direction. Gantry down, bed up.
634 687
       #if HAS_Z_MIN
635
-        #if ENABLED(Z_DUAL_ENDSTOPS)
688
+        #if ENABLED(Z_TRIPLE_ENDSTOPS)
689
+          PROCESS_TRIPLE_ENDSTOP(Z, Z2, Z3, MIN);
690
+        #elif ENABLED(Z_DUAL_ENDSTOPS)
636 691
           PROCESS_DUAL_ENDSTOP(Z, Z2, MIN);
637 692
         #else
638 693
           #if ENABLED(Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN)
@@ -652,7 +707,9 @@ void Endstops::update() {
652 707
     }
653 708
     else { // Z +direction. Gantry up, bed down.
654 709
       #if HAS_Z_MAX
655
-        #if ENABLED(Z_DUAL_ENDSTOPS)
710
+        #if ENABLED(Z_TRIPLE_ENDSTOPS)
711
+          PROCESS_TRIPLE_ENDSTOP(Z, Z2, Z3, MAX);
712
+        #elif ENABLED(Z_DUAL_ENDSTOPS)
656 713
           PROCESS_DUAL_ENDSTOP(Z, Z2, MAX);
657 714
         #elif DISABLED(Z_MIN_PROBE_ENDSTOP) || Z_MAX_PIN != Z_MIN_PROBE_PIN
658 715
           // If this pin is not hijacked for the bed probe
@@ -723,6 +780,12 @@ void Endstops::update() {
723 780
     #if HAS_Z2_MAX
724 781
       if (READ(Z2_MAX_PIN)) SBI(live_state_local, Z2_MAX);
725 782
     #endif
783
+    #if HAS_Z3_MIN
784
+      if (READ(Z3_MIN_PIN)) SBI(live_state_local, Z3_MIN);
785
+    #endif
786
+    #if HAS_Z3_MAX
787
+      if (READ(Z3_MAX_PIN)) SBI(live_state_local, Z3_MAX);
788
+    #endif
726 789
 
727 790
     uint16_t endstop_change = live_state_local ^ old_live_state_local;
728 791
 
@@ -766,6 +829,12 @@ void Endstops::update() {
766 829
       #if HAS_Z2_MAX
767 830
         if (TEST(endstop_change, Z2_MAX)) SERIAL_PROTOCOLPAIR("  Z2_MAX:", TEST(live_state_local, Z2_MAX));
768 831
       #endif
832
+      #if HAS_Z3_MIN
833
+        if (TEST(endstop_change, Z3_MIN)) SERIAL_PROTOCOLPAIR("  Z3_MIN:", TEST(live_state_local, Z3_MIN));
834
+      #endif
835
+      #if HAS_Z3_MAX
836
+        if (TEST(endstop_change, Z3_MAX)) SERIAL_PROTOCOLPAIR("  Z3_MAX:", TEST(live_state_local, Z3_MAX));
837
+      #endif
769 838
       SERIAL_PROTOCOLPGM("\n\n");
770 839
       analogWrite(LED_PIN, local_LED_status);
771 840
       local_LED_status ^= 255;

+ 11
- 6
Marlin/src/module/endstops.h Ver arquivo

@@ -45,7 +45,9 @@ enum EndstopEnum : char {
45 45
   Y2_MIN,
46 46
   Y2_MAX,
47 47
   Z2_MIN,
48
-  Z2_MAX
48
+  Z2_MAX,
49
+  Z3_MIN,
50
+  Z3_MAX
49 51
 };
50 52
 
51 53
 class Endstops {
@@ -54,16 +56,19 @@ class Endstops {
54 56
 
55 57
     static bool enabled, enabled_globally;
56 58
 
57
-    #if ENABLED(X_DUAL_ENDSTOPS) || ENABLED(Y_DUAL_ENDSTOPS) || ENABLED(Z_DUAL_ENDSTOPS)
59
+    #if ENABLED(X_DUAL_ENDSTOPS) || ENABLED(Y_DUAL_ENDSTOPS) || Z_MULTI_ENDSTOPS
58 60
       typedef uint16_t esbits_t;
59 61
       #if ENABLED(X_DUAL_ENDSTOPS)
60
-        static float x_endstop_adj;
62
+        static float x2_endstop_adj;
61 63
       #endif
62 64
       #if ENABLED(Y_DUAL_ENDSTOPS)
63
-        static float y_endstop_adj;
65
+        static float y2_endstop_adj;
64 66
       #endif
65
-      #if ENABLED(Z_DUAL_ENDSTOPS)
66
-        static float z_endstop_adj;
67
+      #if Z_MULTI_ENDSTOPS
68
+        static float z2_endstop_adj;
69
+      #endif
70
+      #if ENABLED(Z_TRIPLE_ENDSTOPS)
71
+        static float z3_endstop_adj;
67 72
       #endif
68 73
     #else
69 74
       typedef uint8_t esbits_t;

+ 66
- 10
Marlin/src/module/motion.cpp Ver arquivo

@@ -1313,7 +1313,7 @@ void homeaxis(const AxisEnum axis) {
1313 1313
   #endif
1314 1314
 
1315 1315
   // Set flags for X, Y, Z motor locking
1316
-  #if ENABLED(X_DUAL_ENDSTOPS) || ENABLED(Y_DUAL_ENDSTOPS) || ENABLED(Z_DUAL_ENDSTOPS)
1316
+  #if ENABLED(X_DUAL_ENDSTOPS) || ENABLED(Y_DUAL_ENDSTOPS) || Z_MULTI_ENDSTOPS
1317 1317
     switch (axis) {
1318 1318
       #if ENABLED(X_DUAL_ENDSTOPS)
1319 1319
         case X_AXIS:
@@ -1324,7 +1324,17 @@ void homeaxis(const AxisEnum axis) {
1324 1324
       #if ENABLED(Z_DUAL_ENDSTOPS)
1325 1325
         case Z_AXIS:
1326 1326
       #endif
1327
-      stepper.set_homing_dual_axis(true);
1327
+      stepper.set_separate_multi_axis(true);
1328
+      default: break;
1329
+    }
1330
+  #endif
1331
+
1332
+  #if ENABLED(Z_TRIPLE_ENDSTOPS)
1333
+    switch (axis) {
1334
+      #if ENABLED(Z_TRIPLE_ENDSTOPS)
1335
+        case Z_AXIS:
1336
+      #endif
1337
+      stepper.set_separate_multi_axis(true);
1328 1338
       default: break;
1329 1339
     }
1330 1340
   #endif
@@ -1384,13 +1394,13 @@ void homeaxis(const AxisEnum axis) {
1384 1394
     #endif
1385 1395
   }
1386 1396
 
1387
-  #if ENABLED(X_DUAL_ENDSTOPS) || ENABLED(Y_DUAL_ENDSTOPS) || ENABLED(Z_DUAL_ENDSTOPS)
1397
+  #if ENABLED(X_DUAL_ENDSTOPS) || ENABLED(Y_DUAL_ENDSTOPS) || Z_MULTI_ENDSTOPS
1388 1398
     const bool pos_dir = axis_home_dir > 0;
1389 1399
     #if ENABLED(X_DUAL_ENDSTOPS)
1390 1400
       if (axis == X_AXIS) {
1391
-        const float adj = ABS(endstops.x_endstop_adj);
1401
+        const float adj = ABS(endstops.x2_endstop_adj);
1392 1402
         if (adj) {
1393
-          if (pos_dir ? (endstops.x_endstop_adj > 0) : (endstops.x_endstop_adj < 0)) stepper.set_x_lock(true); else stepper.set_x2_lock(true);
1403
+          if (pos_dir ? (endstops.x2_endstop_adj > 0) : (endstops.x2_endstop_adj < 0)) stepper.set_x_lock(true); else stepper.set_x2_lock(true);
1394 1404
           do_homing_move(axis, pos_dir ? -adj : adj);
1395 1405
           stepper.set_x_lock(false);
1396 1406
           stepper.set_x2_lock(false);
@@ -1399,9 +1409,9 @@ void homeaxis(const AxisEnum axis) {
1399 1409
     #endif
1400 1410
     #if ENABLED(Y_DUAL_ENDSTOPS)
1401 1411
       if (axis == Y_AXIS) {
1402
-        const float adj = ABS(endstops.y_endstop_adj);
1412
+        const float adj = ABS(endstops.y2_endstop_adj);
1403 1413
         if (adj) {
1404
-          if (pos_dir ? (endstops.y_endstop_adj > 0) : (endstops.y_endstop_adj < 0)) stepper.set_y_lock(true); else stepper.set_y2_lock(true);
1414
+          if (pos_dir ? (endstops.y2_endstop_adj > 0) : (endstops.y2_endstop_adj < 0)) stepper.set_y_lock(true); else stepper.set_y2_lock(true);
1405 1415
           do_homing_move(axis, pos_dir ? -adj : adj);
1406 1416
           stepper.set_y_lock(false);
1407 1417
           stepper.set_y2_lock(false);
@@ -1410,16 +1420,62 @@ void homeaxis(const AxisEnum axis) {
1410 1420
     #endif
1411 1421
     #if ENABLED(Z_DUAL_ENDSTOPS)
1412 1422
       if (axis == Z_AXIS) {
1413
-        const float adj = ABS(endstops.z_endstop_adj);
1423
+        const float adj = ABS(endstops.z2_endstop_adj);
1414 1424
         if (adj) {
1415
-          if (pos_dir ? (endstops.z_endstop_adj > 0) : (endstops.z_endstop_adj < 0)) stepper.set_z_lock(true); else stepper.set_z2_lock(true);
1425
+          if (pos_dir ? (endstops.z2_endstop_adj > 0) : (endstops.z2_endstop_adj < 0)) stepper.set_z_lock(true); else stepper.set_z2_lock(true);
1416 1426
           do_homing_move(axis, pos_dir ? -adj : adj);
1417 1427
           stepper.set_z_lock(false);
1418 1428
           stepper.set_z2_lock(false);
1419 1429
         }
1420 1430
       }
1421 1431
     #endif
1422
-    stepper.set_homing_dual_axis(false);
1432
+    #if ENABLED(Z_TRIPLE_ENDSTOPS)
1433
+      if (axis == Z_AXIS) {
1434
+        // we push the function pointers for the stepper lock function into an array
1435
+        void (*lock[3]) (bool)= {&stepper.set_z_lock, &stepper.set_z2_lock, &stepper.set_z3_lock};
1436
+        float adj[3] = {0, endstops.z2_endstop_adj, endstops.z3_endstop_adj};
1437
+
1438
+        void (*tempLock) (bool);
1439
+        float tempAdj;
1440
+
1441
+        // manual bubble sort by adjust value
1442
+        if (adj[1] < adj[0]) {
1443
+          tempLock = lock[0], tempAdj = adj[0];
1444
+          lock[0] = lock[1], adj[0] = adj[1];
1445
+          lock[1] = tempLock, adj[1] = tempAdj;
1446
+        }
1447
+        if (adj[2] < adj[1]) {
1448
+          tempLock = lock[1], tempAdj = adj[1];
1449
+          lock[1] = lock[2], adj[1] = adj[2];
1450
+          lock[2] = tempLock, adj[2] = tempAdj;
1451
+        }
1452
+        if (adj[1] < adj[0]) {
1453
+          tempLock = lock[0], tempAdj = adj[0];
1454
+          lock[0] = lock[1], adj[0] = adj[1];
1455
+          lock[1] = tempLock, adj[1] = tempAdj;
1456
+        }
1457
+
1458
+        if (pos_dir) {
1459
+          // normalize adj to smallest value and do the first move
1460
+          (*lock[0])(true);
1461
+          do_homing_move(axis, adj[1] - adj[0]);
1462
+          // lock the second stepper for the final correction
1463
+          (*lock[1])(true);
1464
+          do_homing_move(axis, adj[2] - adj[1]);
1465
+        }
1466
+        else {
1467
+          (*lock[2])(true);
1468
+          do_homing_move(axis, adj[1] - adj[2]);
1469
+          (*lock[1])(true);
1470
+          do_homing_move(axis, adj[0] - adj[1]);
1471
+        }
1472
+
1473
+        stepper.set_z_lock(false);
1474
+        stepper.set_z2_lock(false);
1475
+        stepper.set_z3_lock(false);
1476
+      }
1477
+    #endif
1478
+
1423 1479
   #endif
1424 1480
 
1425 1481
   #if IS_SCARA

+ 62
- 24
Marlin/src/module/stepper.cpp Ver arquivo

@@ -107,8 +107,8 @@ Stepper stepper; // Singleton
107 107
 
108 108
 // public:
109 109
 
110
-#if ENABLED(X_DUAL_ENDSTOPS) || ENABLED(Y_DUAL_ENDSTOPS) || ENABLED(Z_DUAL_ENDSTOPS)
111
-  bool Stepper::homing_dual_axis = false;
110
+#if ENABLED(X_DUAL_ENDSTOPS) || ENABLED(Y_DUAL_ENDSTOPS) || Z_MULTI_ENDSTOPS
111
+  bool Stepper::separate_multi_axis = false;
112 112
 #endif
113 113
 
114 114
 #if HAS_MOTOR_CURRENT_PWM
@@ -134,9 +134,12 @@ bool Stepper::abort_current_block;
134 134
 #if ENABLED(Y_DUAL_ENDSTOPS)
135 135
   bool Stepper::locked_Y_motor = false, Stepper::locked_Y2_motor = false;
136 136
 #endif
137
-#if ENABLED(Z_DUAL_ENDSTOPS)
137
+#if Z_MULTI_ENDSTOPS
138 138
   bool Stepper::locked_Z_motor = false, Stepper::locked_Z2_motor = false;
139 139
 #endif
140
+#if ENABLED(Z_TRIPLE_ENDSTOPS)
141
+  bool Stepper::locked_Z3_motor = false;
142
+#endif
140 143
 
141 144
 uint32_t Stepper::acceleration_time, Stepper::deceleration_time;
142 145
 uint8_t Stepper::steps_per_isr;
@@ -202,23 +205,40 @@ volatile int32_t Stepper::endstops_trigsteps[XYZ];
202 205
 volatile int32_t Stepper::count_position[NUM_AXIS] = { 0 };
203 206
 int8_t Stepper::count_direction[NUM_AXIS] = { 0, 0, 0, 0 };
204 207
 
205
-#if ENABLED(X_DUAL_ENDSTOPS) || ENABLED(Y_DUAL_ENDSTOPS) || ENABLED(Z_DUAL_ENDSTOPS)
206
-  #define DUAL_ENDSTOP_APPLY_STEP(A,V)                                                                                        \
207
-    if (homing_dual_axis) {                                                                                                   \
208
-      if (A##_HOME_DIR < 0) {                                                                                                 \
209
-        if (!(TEST(endstops.state(), A##_MIN) && count_direction[_AXIS(A)] < 0) && !locked_##A##_motor) A##_STEP_WRITE(V);    \
210
-        if (!(TEST(endstops.state(), A##2_MIN) && count_direction[_AXIS(A)] < 0) && !locked_##A##2_motor) A##2_STEP_WRITE(V); \
211
-      }                                                                                                                       \
212
-      else {                                                                                                                  \
213
-        if (!(TEST(endstops.state(), A##_MAX) && count_direction[_AXIS(A)] > 0) && !locked_##A##_motor) A##_STEP_WRITE(V);    \
214
-        if (!(TEST(endstops.state(), A##2_MAX) && count_direction[_AXIS(A)] > 0) && !locked_##A##2_motor) A##2_STEP_WRITE(V); \
215
-      }                                                                                                                       \
216
-    }                                                                                                                         \
217
-    else {                                                                                                                    \
218
-      A##_STEP_WRITE(V);                                                                                                      \
219
-      A##2_STEP_WRITE(V);                                                                                                     \
220
-    }
221
-#endif
208
+#define DUAL_ENDSTOP_APPLY_STEP(A,V)                                                                                       \
209
+  if (separate_multi_axis) {                                                                                                \
210
+    if (A##_HOME_DIR < 0) {                                                                                                 \
211
+      if (!(TEST(endstops.state(), A##_MIN) && count_direction[_AXIS(A)] < 0) && !locked_##A##_motor) A##_STEP_WRITE(V);    \
212
+      if (!(TEST(endstops.state(), A##2_MIN) && count_direction[_AXIS(A)] < 0) && !locked_##A##2_motor) A##2_STEP_WRITE(V); \
213
+    }                                                                                                                       \
214
+    else {                                                                                                                  \
215
+      if (!(TEST(endstops.state(), A##_MAX) && count_direction[_AXIS(A)] > 0) && !locked_##A##_motor) A##_STEP_WRITE(V);    \
216
+      if (!(TEST(endstops.state(), A##2_MAX) && count_direction[_AXIS(A)] > 0) && !locked_##A##2_motor) A##2_STEP_WRITE(V); \
217
+    }                                                                                                                       \
218
+  }                                                                                                                         \
219
+  else {                                                                                                                    \
220
+    A##_STEP_WRITE(V);                                                                                                      \
221
+    A##2_STEP_WRITE(V);                                                                                                     \
222
+  }
223
+
224
+#define TRIPLE_ENDSTOP_APPLY_STEP(A,V)                                                                                       \
225
+  if (separate_multi_axis) {                                                                                                \
226
+    if (A##_HOME_DIR < 0) {                                                                                                 \
227
+      if (!(TEST(endstops.state(), A##_MIN) && count_direction[_AXIS(A)] < 0) && !locked_##A##_motor) A##_STEP_WRITE(V);    \
228
+      if (!(TEST(endstops.state(), A##2_MIN) && count_direction[_AXIS(A)] < 0) && !locked_##A##2_motor) A##2_STEP_WRITE(V); \
229
+      if (!(TEST(endstops.state(), A##3_MIN) && count_direction[_AXIS(A)] < 0) && !locked_##A##3_motor) A##3_STEP_WRITE(V); \
230
+    }                                                                                                                       \
231
+    else {                                                                                                                  \
232
+      if (!(TEST(endstops.state(), A##_MAX) && count_direction[_AXIS(A)] > 0) && !locked_##A##_motor) A##_STEP_WRITE(V);    \
233
+      if (!(TEST(endstops.state(), A##2_MAX) && count_direction[_AXIS(A)] > 0) && !locked_##A##2_motor) A##2_STEP_WRITE(V); \
234
+      if (!(TEST(endstops.state(), A##3_MAX) && count_direction[_AXIS(A)] > 0) && !locked_##A##3_motor) A##3_STEP_WRITE(V); \
235
+    }                                                                                                                       \
236
+  }                                                                                                                         \
237
+  else {                                                                                                                    \
238
+    A##_STEP_WRITE(V);                                                                                                      \
239
+    A##2_STEP_WRITE(V);                                                                                                     \
240
+    A##3_STEP_WRITE(V);                                                                                                     \
241
+  }
222 242
 
223 243
 #if ENABLED(X_DUAL_STEPPER_DRIVERS)
224 244
   #define X_APPLY_DIR(v,Q) do{ X_DIR_WRITE(v); X2_DIR_WRITE((v) != INVERT_X2_VS_X_DIR); }while(0)
@@ -261,7 +281,14 @@ int8_t Stepper::count_direction[NUM_AXIS] = { 0, 0, 0, 0 };
261 281
   #define Y_APPLY_STEP(v,Q) Y_STEP_WRITE(v)
262 282
 #endif
263 283
 
264
-#if ENABLED(Z_DUAL_STEPPER_DRIVERS)
284
+#if ENABLED(Z_TRIPLE_STEPPER_DRIVERS)
285
+  #define Z_APPLY_DIR(v,Q) do{ Z_DIR_WRITE(v); Z2_DIR_WRITE(v); Z3_DIR_WRITE(v); }while(0)
286
+  #if ENABLED(Z_TRIPLE_ENDSTOPS)
287
+    #define Z_APPLY_STEP(v,Q) TRIPLE_ENDSTOP_APPLY_STEP(Z,v)
288
+  #else
289
+    #define Z_APPLY_STEP(v,Q) do{ Z_STEP_WRITE(v); Z2_STEP_WRITE(v); Z3_STEP_WRITE(v); }while(0)
290
+  #endif
291
+#elif ENABLED(Z_DUAL_STEPPER_DRIVERS)
265 292
   #define Z_APPLY_DIR(v,Q) do{ Z_DIR_WRITE(v); Z2_DIR_WRITE(v); }while(0)
266 293
   #if ENABLED(Z_DUAL_ENDSTOPS)
267 294
     #define Z_APPLY_STEP(v,Q) DUAL_ENDSTOP_APPLY_STEP(Z,v)
@@ -1933,9 +1960,12 @@ void Stepper::init() {
1933 1960
   #endif
1934 1961
   #if HAS_Z_DIR
1935 1962
     Z_DIR_INIT;
1936
-    #if ENABLED(Z_DUAL_STEPPER_DRIVERS) && HAS_Z2_DIR
1963
+    #if Z_MULTI_STEPPER_DRIVERS && HAS_Z2_DIR
1937 1964
       Z2_DIR_INIT;
1938 1965
     #endif
1966
+    #if ENABLED(Z_TRIPLE_STEPPER_DRIVERS) && HAS_Z3_DIR
1967
+      Z3_DIR_INIT;
1968
+    #endif
1939 1969
   #endif
1940 1970
   #if HAS_E0_DIR
1941 1971
     E0_DIR_INIT;
@@ -1973,10 +2003,14 @@ void Stepper::init() {
1973 2003
   #if HAS_Z_ENABLE
1974 2004
     Z_ENABLE_INIT;
1975 2005
     if (!Z_ENABLE_ON) Z_ENABLE_WRITE(HIGH);
1976
-    #if ENABLED(Z_DUAL_STEPPER_DRIVERS) && HAS_Z2_ENABLE
2006
+    #if Z_MULTI_STEPPER_DRIVERS && HAS_Z2_ENABLE
1977 2007
       Z2_ENABLE_INIT;
1978 2008
       if (!Z_ENABLE_ON) Z2_ENABLE_WRITE(HIGH);
1979 2009
     #endif
2010
+    #if ENABLED(Z_TRIPLE_STEPPER_DRIVERS) && HAS_Z3_ENABLE
2011
+      Z3_ENABLE_INIT;
2012
+      if (!Z_ENABLE_ON) Z3_ENABLE_WRITE(HIGH);
2013
+    #endif
1980 2014
   #endif
1981 2015
   #if HAS_E0_ENABLE
1982 2016
     E0_ENABLE_INIT;
@@ -2028,10 +2062,14 @@ void Stepper::init() {
2028 2062
   #endif
2029 2063
 
2030 2064
   #if HAS_Z_STEP
2031
-    #if ENABLED(Z_DUAL_STEPPER_DRIVERS)
2065
+    #if Z_MULTI_STEPPER_DRIVERS
2032 2066
       Z2_STEP_INIT;
2033 2067
       Z2_STEP_WRITE(INVERT_Z_STEP_PIN);
2034 2068
     #endif
2069
+    #if ENABLED(Z_TRIPLE_STEPPER_DRIVERS)
2070
+      Z3_STEP_INIT;
2071
+      Z3_STEP_WRITE(INVERT_Z_STEP_PIN);
2072
+    #endif
2035 2073
     AXIS_INIT(Z, Z);
2036 2074
   #endif
2037 2075
 

+ 12
- 6
Marlin/src/module/stepper.h Ver arquivo

@@ -234,8 +234,8 @@ class Stepper {
234 234
 
235 235
   public:
236 236
 
237
-    #if ENABLED(X_DUAL_ENDSTOPS) || ENABLED(Y_DUAL_ENDSTOPS) || ENABLED(Z_DUAL_ENDSTOPS)
238
-      static bool homing_dual_axis;
237
+    #if ENABLED(X_DUAL_ENDSTOPS) || ENABLED(Y_DUAL_ENDSTOPS) || Z_MULTI_ENDSTOPS
238
+      static bool separate_multi_axis;
239 239
     #endif
240 240
 
241 241
     #if HAS_MOTOR_CURRENT_PWM
@@ -267,9 +267,12 @@ class Stepper {
267 267
     #if ENABLED(Y_DUAL_ENDSTOPS)
268 268
       static bool locked_Y_motor, locked_Y2_motor;
269 269
     #endif
270
-    #if ENABLED(Z_DUAL_ENDSTOPS)
270
+    #if Z_MULTI_ENDSTOPS
271 271
       static bool locked_Z_motor, locked_Z2_motor;
272 272
     #endif
273
+    #if ENABLED(Z_TRIPLE_ENDSTOPS)
274
+      static bool locked_Z3_motor;
275
+    #endif
273 276
 
274 277
     static uint32_t acceleration_time, deceleration_time; // time measured in Stepper Timer ticks
275 278
     static uint8_t steps_per_isr;         // Count of steps to perform per Stepper ISR call
@@ -415,8 +418,8 @@ class Stepper {
415 418
       static void microstep_readings();
416 419
     #endif
417 420
 
418
-    #if ENABLED(X_DUAL_ENDSTOPS) || ENABLED(Y_DUAL_ENDSTOPS) || ENABLED(Z_DUAL_ENDSTOPS)
419
-      FORCE_INLINE static void set_homing_dual_axis(const bool state) { homing_dual_axis = state; }
421
+    #if ENABLED(X_DUAL_ENDSTOPS) || ENABLED(Y_DUAL_ENDSTOPS) || Z_MULTI_ENDSTOPS
422
+      FORCE_INLINE static void set_separate_multi_axis(const bool state) { separate_multi_axis = state; }
420 423
     #endif
421 424
     #if ENABLED(X_DUAL_ENDSTOPS)
422 425
       FORCE_INLINE static void set_x_lock(const bool state) { locked_X_motor = state; }
@@ -426,10 +429,13 @@ class Stepper {
426 429
       FORCE_INLINE static void set_y_lock(const bool state) { locked_Y_motor = state; }
427 430
       FORCE_INLINE static void set_y2_lock(const bool state) { locked_Y2_motor = state; }
428 431
     #endif
429
-    #if ENABLED(Z_DUAL_ENDSTOPS)
432
+    #if Z_MULTI_ENDSTOPS
430 433
       FORCE_INLINE static void set_z_lock(const bool state) { locked_Z_motor = state; }
431 434
       FORCE_INLINE static void set_z2_lock(const bool state) { locked_Z2_motor = state; }
432 435
     #endif
436
+    #if ENABLED(Z_TRIPLE_ENDSTOPS)
437
+      FORCE_INLINE static void set_z3_lock(const bool state) { locked_Z3_motor = state; }
438
+    #endif
433 439
 
434 440
     #if ENABLED(BABYSTEPPING)
435 441
       static void babystep(const AxisEnum axis, const bool direction); // perform a short step with a single stepper motor, outside of any convention

+ 41
- 0
Marlin/src/module/stepper_indirection.cpp Ver arquivo

@@ -69,6 +69,9 @@
69 69
   #if AXIS_DRIVER_TYPE(Z2, TMC26X)
70 70
     _TMC26X_DEFINE(Z2);
71 71
   #endif
72
+  #if AXIS_DRIVER_TYPE(Z3, TMC26X)
73
+    _TMC26X_DEFINE(Z3);
74
+  #endif
72 75
   #if AXIS_DRIVER_TYPE(E0, TMC26X)
73 76
     _TMC26X_DEFINE(E0);
74 77
   #endif
@@ -109,6 +112,9 @@
109 112
     #if AXIS_DRIVER_TYPE(Z2, TMC26X)
110 113
       _TMC26X_INIT(Z2);
111 114
     #endif
115
+    #if AXIS_DRIVER_TYPE(Z3, TMC26X)
116
+      _TMC26X_INIT(Z3);
117
+    #endif
112 118
     #if AXIS_DRIVER_TYPE(E0, TMC26X)
113 119
       _TMC26X_INIT(E0);
114 120
     #endif
@@ -166,6 +172,9 @@
166 172
   #if AXIS_DRIVER_TYPE(Z2, TMC2130)
167 173
     _TMC2130_DEFINE(Z2);
168 174
   #endif
175
+  #if AXIS_DRIVER_TYPE(Z3, TMC2130)
176
+    _TMC2130_DEFINE(Z3);
177
+  #endif
169 178
   #if AXIS_DRIVER_TYPE(E0, TMC2130)
170 179
     _TMC2130_DEFINE(E0);
171 180
   #endif
@@ -233,6 +242,9 @@
233 242
     #if AXIS_DRIVER_TYPE(Z2, TMC2130)
234 243
       _TMC2130_INIT(Z2, planner.axis_steps_per_mm[Z_AXIS]);
235 244
     #endif
245
+    #if AXIS_DRIVER_TYPE(Z3, TMC2130)
246
+      _TMC2130_INIT(Z3, planner.axis_steps_per_mm[Z_AXIS]);
247
+    #endif
236 248
     #if AXIS_DRIVER_TYPE(E0, TMC2130)
237 249
       _TMC2130_INIT(E0, planner.axis_steps_per_mm[E_AXIS]);
238 250
     #endif
@@ -274,6 +286,9 @@
274 286
         #if AXIS_DRIVER_TYPE(Z2, TMC2130)
275 287
           stepperZ2.sgt(Z_HOMING_SENSITIVITY);
276 288
         #endif
289
+        #if ENABLED(Z3_IS_TMC2130)
290
+          stepperZ3.sgt(Z_HOMING_SENSITIVITY);
291
+        #endif
277 292
       #endif
278 293
     #endif
279 294
   }
@@ -337,6 +352,13 @@
337 352
       _TMC2208_DEFINE_SOFTWARE(Z2);
338 353
     #endif
339 354
   #endif
355
+  #if AXIS_DRIVER_TYPE(Z3, TMC2208)
356
+    #ifdef Z3_HARDWARE_SERIAL
357
+      _TMC2208_DEFINE_HARDWARE(Z3);
358
+    #else
359
+      _TMC2208_DEFINE_SOFTWARE(Z3);
360
+    #endif
361
+  #endif
340 362
   #if AXIS_DRIVER_TYPE(E0, TMC2208)
341 363
     #ifdef E0_HARDWARE_SERIAL
342 364
       _TMC2208_DEFINE_HARDWARE(E0);
@@ -416,6 +438,13 @@
416 438
         stepperZ2.beginSerial(115200);
417 439
       #endif
418 440
     #endif
441
+    #if AXIS_DRIVER_TYPE(Z3, TMC2208)
442
+      #ifdef Z3_HARDWARE_SERIAL
443
+        Z3_HARDWARE_SERIAL.begin(115200);
444
+      #else
445
+        stepperZ3.beginSerial(115200);
446
+      #endif
447
+    #endif
419 448
     #if AXIS_DRIVER_TYPE(E0, TMC2208)
420 449
       #ifdef E0_HARDWARE_SERIAL
421 450
         E0_HARDWARE_SERIAL.begin(115200);
@@ -510,6 +539,9 @@
510 539
     #if AXIS_DRIVER_TYPE(Z2, TMC2208)
511 540
       _TMC2208_INIT(Z2, planner.axis_steps_per_mm[Z_AXIS]);
512 541
     #endif
542
+    #if AXIS_DRIVER_TYPE(Z3, TMC2208)
543
+      _TMC2208_INIT(Z3, planner.axis_steps_per_mm[Z_AXIS]);
544
+    #endif
513 545
     #if AXIS_DRIVER_TYPE(E0, TMC2208)
514 546
       _TMC2208_INIT(E0, planner.axis_steps_per_mm[E_AXIS]);
515 547
     #endif
@@ -547,6 +579,9 @@ void restore_stepper_drivers() {
547 579
   #if AXIS_IS_TMC(Z2)
548 580
     stepperZ2.push();
549 581
   #endif
582
+  #if AXIS_IS_TMC(Z3)
583
+    stepperZ3.push();
584
+  #endif
550 585
   #if AXIS_IS_TMC(E0)
551 586
     stepperE0.push();
552 587
   #endif
@@ -614,6 +649,9 @@ void reset_stepper_drivers() {
614 649
   #if AXIS_DRIVER_TYPE(Z2, L6470)
615 650
     _L6470_DEFINE(Z2);
616 651
   #endif
652
+  #if AXIS_DRIVER_TYPE(Z3, L6470)
653
+    _L6470_DEFINE(Z3);
654
+  #endif
617 655
   #if AXIS_DRIVER_TYPE(E0, L6470)
618 656
     _L6470_DEFINE(E0);
619 657
   #endif
@@ -657,6 +695,9 @@ void reset_stepper_drivers() {
657 695
     #if AXIS_DRIVER_TYPE(Z2, L6470)
658 696
       _L6470_INIT(Z2);
659 697
     #endif
698
+    #if AXIS_DRIVER_TYPE(Z3, L6470)
699
+      _L6470_INIT(Z3);
700
+    #endif
660 701
     #if AXIS_DRIVER_TYPE(E0, L6470)
661 702
       _L6470_INIT(E0);
662 703
     #endif

+ 35
- 0
Marlin/src/module/stepper_indirection.h Ver arquivo

@@ -282,6 +282,41 @@ void reset_stepper_drivers();    // Called by settings.load / settings.reset
282 282
   #define Z2_STEP_READ READ(Z2_STEP_PIN)
283 283
 #endif
284 284
 
285
+// Z3 Stepper
286
+#if HAS_Z3_ENABLE
287
+  #if ENABLED(Z3_IS_L6470)
288
+    extern L6470 stepperZ3;
289
+    #define Z3_ENABLE_INIT NOOP
290
+    #define Z3_ENABLE_WRITE(STATE) do{ if (STATE) stepperZ3.Step_Clock(stepperZ3.getStatus() & STATUS_HIZ); else stepperZ3.softFree(); }while(0)
291
+    #define Z3_ENABLE_READ (stepperZ3.getStatus() & STATUS_HIZ)
292
+    #define Z3_DIR_INIT NOOP
293
+    #define Z3_DIR_WRITE(STATE) stepperZ3.Step_Clock(STATE)
294
+    #define Z3_DIR_READ (stepperZ3.getStatus() & STATUS_DIR)
295
+  #else
296
+    #if ENABLED(Z3_IS_TMC26X)
297
+      extern TMC26XStepper stepperZ3;
298
+      #define Z3_ENABLE_INIT NOOP
299
+      #define Z3_ENABLE_WRITE(STATE) stepperZ3.setEnabled(STATE)
300
+      #define Z3_ENABLE_READ stepperZ3.isEnabled()
301
+    #else
302
+      #if ENABLED(Z3_IS_TMC2130)
303
+        extern TMC2130Stepper stepperZ3;
304
+      #elif ENABLED(Z3_IS_TMC2208)
305
+        extern TMC2208Stepper stepperZ3;
306
+      #endif
307
+      #define Z3_ENABLE_INIT SET_OUTPUT(Z3_ENABLE_PIN)
308
+      #define Z3_ENABLE_WRITE(STATE) WRITE(Z3_ENABLE_PIN,STATE)
309
+      #define Z3_ENABLE_READ READ(Z3_ENABLE_PIN)
310
+    #endif
311
+    #define Z3_DIR_INIT SET_OUTPUT(Z3_DIR_PIN)
312
+    #define Z3_DIR_WRITE(STATE) WRITE(Z3_DIR_PIN,STATE)
313
+    #define Z3_DIR_READ READ(Z3_DIR_PIN)
314
+  #endif
315
+  #define Z3_STEP_INIT SET_OUTPUT(Z3_STEP_PIN)
316
+  #define Z3_STEP_WRITE(STATE) WRITE(Z3_STEP_PIN,STATE)
317
+  #define Z3_STEP_READ READ(Z3_STEP_PIN)
318
+#endif
319
+
285 320
 // E0 Stepper
286 321
 #if AXIS_DRIVER_TYPE(E0, L6470)
287 322
   extern L6470 stepperE0;

+ 27
- 2
Marlin/src/pins/pins.h Ver arquivo

@@ -842,6 +842,7 @@
842 842
 #define _X2_PINS
843 843
 #define _Y2_PINS
844 844
 #define _Z2_PINS
845
+#define _Z3_PINS
845 846
 
846 847
 #define __EPIN(p,q) E##p##_##q##_PIN
847 848
 #define _EPIN(p,q) __EPIN(p,q)
@@ -897,7 +898,7 @@
897 898
 #endif
898 899
 
899 900
 // The Z2 axis, if any, should be the next open extruder port
900
-#if ENABLED(Z_DUAL_STEPPER_DRIVERS)
901
+#if Z_MULTI_STEPPER_DRIVERS
901 902
   #ifndef Z2_STEP_PIN
902 903
     #define Z2_STEP_PIN   _EPIN(Z2_E_INDEX, STEP)
903 904
     #define Z2_DIR_PIN    _EPIN(Z2_E_INDEX, DIR)
@@ -916,6 +917,30 @@
916 917
   #else
917 918
     #define _Z2_PINS __Z2_PINS
918 919
   #endif
920
+  #define Z3_E_INDEX INCREMENT(Z2_E_INDEX)
921
+#else
922
+  #define Z3_E_INDEX Z2_E_INDEX
923
+#endif
924
+
925
+#if ENABLED(Z_TRIPLE_STEPPER_DRIVERS)
926
+  #ifndef Z3_STEP_PIN
927
+    #define Z3_STEP_PIN   _EPIN(Z3_E_INDEX, STEP)
928
+    #define Z3_DIR_PIN    _EPIN(Z3_E_INDEX, DIR)
929
+    #define Z3_ENABLE_PIN _EPIN(Z3_E_INDEX, ENABLE)
930
+    #ifndef Z3_CS_PIN
931
+      #define Z3_CS_PIN   _EPIN(Z3_E_INDEX, CS)
932
+    #endif
933
+    #if Z3_E_INDEX > 4 || !PIN_EXISTS(Z3_ENABLE)
934
+      #error "No E stepper plug left for Z3!"
935
+    #endif
936
+  #endif
937
+  #undef _Z3_PINS
938
+  #define __Z3_PINS Z3_STEP_PIN, Z3_DIR_PIN, Z3_ENABLE_PIN,
939
+  #ifdef Z3_CS_PIN
940
+    #define _Z3_PINS __Z3_PINS Z3_CS_PIN,
941
+  #else
942
+    #define _Z3_PINS __Z3_PINS
943
+  #endif
919 944
 #endif
920 945
 
921 946
 #ifndef HAL_SENSITIVE_PINS
@@ -929,7 +954,7 @@
929 954
     PS_ON_PIN, HEATER_BED_PIN, FAN_PIN, FAN1_PIN, FAN2_PIN, CONTROLLER_FAN_PIN, \
930 955
     _E0_PINS _E1_PINS _E2_PINS _E3_PINS _E4_PINS BED_PINS \
931 956
     _H0_PINS _H1_PINS _H2_PINS _H3_PINS _H4_PINS \
932
-    _X2_PINS _Y2_PINS _Z2_PINS \
957
+    _X2_PINS _Y2_PINS _Z2_PINS _Z3_PINS \
933 958
     HAL_SENSITIVE_PINS \
934 959
   }
935 960
 

+ 27
- 0
Marlin/src/pins/pinsDebug_list.h Ver arquivo

@@ -944,6 +944,27 @@
944 944
 #if PIN_EXISTS(Z2_STEP)
945 945
   REPORT_NAME_DIGITAL(__LINE__, Z2_STEP_PIN)
946 946
 #endif
947
+#if PIN_EXISTS(Z3_CS)
948
+  REPORT_NAME_DIGITAL(__LINE__, Z3_CS_PIN)
949
+#endif
950
+#if PIN_EXISTS(Z3_DIR)
951
+  REPORT_NAME_DIGITAL(__LINE__, Z3_DIR_PIN)
952
+#endif
953
+#if PIN_EXISTS(Z3_ENABLE)
954
+  REPORT_NAME_DIGITAL(__LINE__, Z3_ENABLE_PIN)
955
+#endif
956
+#if PIN_EXISTS(Z3_MS1)
957
+  REPORT_NAME_DIGITAL(__LINE__, Z3_MS1_PIN)
958
+#endif
959
+#if PIN_EXISTS(Z3_MS2)
960
+  REPORT_NAME_DIGITAL(__LINE__, Z3_MS2_PIN)
961
+#endif
962
+#if PIN_EXISTS(Z3_MS3)
963
+  REPORT_NAME_DIGITAL(__LINE__, Z3_MS3_PIN)
964
+#endif
965
+#if PIN_EXISTS(Z3_STEP)
966
+  REPORT_NAME_DIGITAL(__LINE__, Z3_STEP_PIN)
967
+#endif
947 968
 #if PIN_EXISTS(ZRIB_V20_D6)
948 969
   REPORT_NAME_DIGITAL(__LINE__, ZRIB_V20_D6_PIN)
949 970
 #endif
@@ -986,6 +1007,12 @@
986 1007
 #if PIN_EXISTS(Z2_SERIAL_RX)
987 1008
   REPORT_NAME_DIGITAL(__LINE__, Z2_SERIAL_RX_PIN)
988 1009
 #endif
1010
+#if PIN_EXISTS(Z3_SERIAL_TX)
1011
+  REPORT_NAME_DIGITAL(__LINE__, Z3_SERIAL_TX_PIN)
1012
+#endif
1013
+#if PIN_EXISTS(Z3_SERIAL_RX)
1014
+  REPORT_NAME_DIGITAL(__LINE__, Z3_SERIAL_RX_PIN)
1015
+#endif
989 1016
 #if PIN_EXISTS(E0_SERIAL_TX)
990 1017
   REPORT_NAME_DIGITAL(__LINE__, E0_SERIAL_TX_PIN)
991 1018
 #endif

+ 12
- 0
buildroot/share/tests/DUE_tests Ver arquivo

@@ -9,3 +9,15 @@ opt_enable S_CURVE_ACCELERATION EEPROM_SETTINGS
9 9
 opt_set E0_AUTO_FAN_PIN 8
10 10
 opt_set EXTRUDER_AUTO_FAN_SPEED 100
11 11
 exec_test $1 $2 "RAMPS4DUE_EFB S_CURVE_ACCELERATION EEPROM_SETTINGS"
12
+
13
+restore_configs
14
+opt_set MOTHERBOARD BOARD_RADDS
15
+opt_enable USE_XMAX_PLUG USE_YMAX_PLUG
16
+opt_enable_adv Z_TRIPLE_STEPPER_DRIVERS Z_TRIPLE_ENDSTOPS
17
+opt_add_adv Z2_MAX_ENDSTOP_INVERTING false
18
+opt_add_adv Z3_MAX_ENDSTOP_INVERTING false
19
+pins_set RAMPS X_MAX_PIN -1
20
+pins_set RAMPS Y_MAX_PIN -1
21
+opt_add_adv Z2_MAX_PIN 2
22
+opt_add_adv Z3_MAX_PIN 3
23
+exec_test $1 $2 "RADDS Z_TRIPLE"

+ 1
- 1
buildroot/share/tests/teensy35_tests Ver arquivo

@@ -92,5 +92,5 @@ opt_add_adv Z2_MAX_PIN 2
92 92
 opt_enable USE_XMAX_PLUG
93 93
 exec_test $1 $2 "Z_DUAL_STEPPER_DRIVERS, Z_DUAL_ENDSTOPS"
94 94
 
95
-#cleanup
95
+# Clean up
96 96
 restore_configs

Carregando…
Cancelar
Salvar