Browse Source

🏗️ Support for up to 6 linear axes (#19112)

Co-authored-by: Scott Lahteine <github@thinkyhead.com>
DerAndere 3 years ago
parent
commit
7726af9c53
No account linked to committer's email address
98 changed files with 5030 additions and 2246 deletions
  1. 108
    4
      Marlin/Configuration.h
  2. 110
    2
      Marlin/Configuration_adv.h
  3. 45
    1
      Marlin/src/HAL/AVR/endstop_interrupts.h
  4. 6
    0
      Marlin/src/HAL/DUE/endstop_interrupts.h
  5. 6
    0
      Marlin/src/HAL/ESP32/endstop_interrupts.h
  6. 33
    0
      Marlin/src/HAL/LPC1768/endstop_interrupts.h
  7. 64
    74
      Marlin/src/HAL/SAMD51/endstop_interrupts.h
  8. 6
    0
      Marlin/src/HAL/STM32/endstop_interrupts.h
  9. 9
    0
      Marlin/src/HAL/STM32F1/MarlinSerial.cpp
  10. 6
    0
      Marlin/src/HAL/STM32F1/endstop_interrupts.h
  11. 6
    0
      Marlin/src/HAL/TEENSY31_32/endstop_interrupts.h
  12. 6
    0
      Marlin/src/HAL/TEENSY35_36/endstop_interrupts.h
  13. 6
    0
      Marlin/src/HAL/TEENSY40_41/endstop_interrupts.h
  14. 18
    0
      Marlin/src/MarlinCore.cpp
  15. 9
    3
      Marlin/src/core/drivers.h
  16. 128
    12
      Marlin/src/core/language.h
  17. 9
    0
      Marlin/src/core/macros.h
  18. 8
    5
      Marlin/src/core/serial.cpp
  19. 10
    9
      Marlin/src/core/serial.h
  20. 285
    192
      Marlin/src/core/types.h
  21. 1
    1
      Marlin/src/core/utility.cpp
  22. 1
    1
      Marlin/src/core/utility.h
  23. 69
    57
      Marlin/src/feature/bedlevel/ubl/ubl_motion.cpp
  24. 159
    118
      Marlin/src/feature/tmc_util.cpp
  25. 4
    10
      Marlin/src/feature/tmc_util.h
  26. 2
    2
      Marlin/src/gcode/bedlevel/abl/G29.cpp
  27. 48
    25
      Marlin/src/gcode/calibrate/G28.cpp
  28. 175
    46
      Marlin/src/gcode/calibrate/G425.cpp
  29. 4
    1
      Marlin/src/gcode/calibrate/M425.cpp
  30. 7
    1
      Marlin/src/gcode/config/M200-M205.cpp
  31. 6
    3
      Marlin/src/gcode/config/M92.cpp
  32. 10
    4
      Marlin/src/gcode/control/M17_M18_M84.cpp
  33. 21
    16
      Marlin/src/gcode/control/M605.cpp
  34. 1
    1
      Marlin/src/gcode/feature/L6470/M906.cpp
  35. 6
    5
      Marlin/src/gcode/feature/pause/G60.cpp
  36. 2
    2
      Marlin/src/gcode/feature/pause/G61.cpp
  37. 6
    14
      Marlin/src/gcode/feature/trinamic/M122.cpp
  38. 49
    104
      Marlin/src/gcode/feature/trinamic/M569.cpp
  39. 21
    2
      Marlin/src/gcode/feature/trinamic/M906.cpp
  40. 99
    103
      Marlin/src/gcode/feature/trinamic/M911-M914.cpp
  41. 4
    1
      Marlin/src/gcode/gcode.cpp
  42. 6
    2
      Marlin/src/gcode/gcode.h
  43. 11
    2
      Marlin/src/gcode/geometry/M206_M428.cpp
  44. 16
    1
      Marlin/src/gcode/host/M114.cpp
  45. 7
    2
      Marlin/src/gcode/motion/G0_G1.cpp
  46. 22
    22
      Marlin/src/gcode/motion/G2_G3.cpp
  47. 1
    1
      Marlin/src/gcode/motion/M290.cpp
  48. 1
    1
      Marlin/src/gcode/parser.cpp
  49. 1
    1
      Marlin/src/gcode/parser.h
  50. 2
    0
      Marlin/src/gcode/temp/M106_M107.cpp
  51. 33
    7
      Marlin/src/inc/Conditionals_LCD.h
  52. 18
    0
      Marlin/src/inc/Conditionals_adv.h
  53. 367
    87
      Marlin/src/inc/Conditionals_post.h
  54. 275
    38
      Marlin/src/inc/SanityCheck.h
  55. 1
    1
      Marlin/src/inc/Version.h
  56. 1
    1
      Marlin/src/lcd/dwin/e3v2/dwin.cpp
  57. 3
    3
      Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.cpp
  58. 5
    5
      Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.h
  59. 12
    24
      Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.cpp
  60. 6
    6
      Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/endstop_state_screen.cpp
  61. 15
    35
      Marlin/src/lcd/extui/mks_ui/draw_tmc_step_mode_settings.cpp
  62. 30
    0
      Marlin/src/lcd/language/language_en.h
  63. 10
    4
      Marlin/src/lcd/menu/menu_advanced.cpp
  64. 15
    2
      Marlin/src/lcd/menu/menu_backlash.cpp
  65. 45
    6
      Marlin/src/lcd/menu/menu_motion.cpp
  66. 46
    129
      Marlin/src/lcd/menu/menu_tmc.cpp
  67. 6
    4
      Marlin/src/lcd/tft/ui_1024x600.cpp
  68. 6
    4
      Marlin/src/lcd/tft/ui_320x240.cpp
  69. 6
    4
      Marlin/src/lcd/tft/ui_480x320.cpp
  70. 144
    56
      Marlin/src/libs/L64XX/L64XX_Marlin.cpp
  71. 3
    1
      Marlin/src/libs/L64XX/L64XX_Marlin.h
  72. 12
    13
      Marlin/src/libs/vector_3.cpp
  73. 22
    13
      Marlin/src/libs/vector_3.h
  74. 6
    0
      Marlin/src/module/delta.cpp
  75. 341
    67
      Marlin/src/module/endstops.cpp
  76. 6
    0
      Marlin/src/module/endstops.h
  77. 266
    155
      Marlin/src/module/motion.cpp
  78. 98
    38
      Marlin/src/module/motion.h
  79. 154
    104
      Marlin/src/module/planner.cpp
  80. 11
    42
      Marlin/src/module/planner.h
  81. 7
    3
      Marlin/src/module/planner_bezier.cpp
  82. 10
    10
      Marlin/src/module/probe.h
  83. 265
    310
      Marlin/src/module/settings.cpp
  84. 246
    57
      Marlin/src/module/stepper.cpp
  85. 24
    32
      Marlin/src/module/stepper.h
  86. 18
    0
      Marlin/src/module/stepper/L64xx.cpp
  87. 60
    0
      Marlin/src/module/stepper/L64xx.h
  88. 18
    0
      Marlin/src/module/stepper/TMC26X.cpp
  89. 24
    0
      Marlin/src/module/stepper/TMC26X.h
  90. 1
    3
      Marlin/src/module/stepper/indirection.cpp
  91. 173
    33
      Marlin/src/module/stepper/indirection.h
  92. 102
    3
      Marlin/src/module/stepper/trinamic.cpp
  93. 58
    3
      Marlin/src/module/stepper/trinamic.h
  94. 19
    5
      Marlin/src/module/tool_change.cpp
  95. 99
    0
      Marlin/src/pins/pinsDebug_list.h
  96. 98
    23
      Marlin/src/pins/pins_postprocess.h
  97. 204
    64
      Marlin/src/pins/sensitive_pins.h
  98. 1
    0
      Marlin/src/sd/cardreader.cpp

+ 108
- 4
Marlin/Configuration.h View File

@@ -35,7 +35,7 @@
35 35
  *
36 36
  * Advanced settings can be found in Configuration_adv.h
37 37
  */
38
-#define CONFIGURATION_H_VERSION 02000801
38
+#define CONFIGURATION_H_VERSION 02000900
39 39
 
40 40
 //===========================================================================
41 41
 //============================= Getting Started =============================
@@ -66,6 +66,14 @@
66 66
 //
67 67
 //===========================================================================
68 68
 
69
+//===========================================================================
70
+//=========================== FOAMCUTTER_XYUV ==============================
71
+//===========================================================================
72
+// For a hot wire cutter with parallel horizontal axes X, I where the hights
73
+// of the two wire ends are controlled by parallel axes Y, J.
74
+//
75
+//#define FOAMCUTTER_XYUV
76
+
69 77
 // @section info
70 78
 
71 79
 // Author info of this build printed to the host during boot and M115
@@ -149,6 +157,45 @@
149 157
 // Choose your own or use a service like https://www.uuidgenerator.net/version4
150 158
 //#define MACHINE_UUID "00000000-0000-0000-0000-000000000000"
151 159
 
160
+/**
161
+ * Define the number of coordinated linear axes.
162
+ * See https://github.com/DerAndere1/Marlin/wiki
163
+ * Each linear axis gets its own stepper control and endstop:
164
+ *
165
+ *   Steppers: *_STEP_PIN, *_ENABLE_PIN, *_DIR_PIN, *_ENABLE_ON
166
+ *   Endstops: *_STOP_PIN, USE_*MIN_PLUG, USE_*MAX_PLUG
167
+ *       Axes: *_MIN_POS, *_MAX_POS, INVERT_*_DIR
168
+ *    Planner: DEFAULT_AXIS_STEPS_PER_UNIT, DEFAULT_MAX_FEEDRATE
169
+ *             DEFAULT_MAX_ACCELERATION, AXIS_RELATIVE_MODES,
170
+ *             MICROSTEP_MODES, MANUAL_FEEDRATE
171
+ *
172
+ * :[3, 4, 5, 6]
173
+ */
174
+//#define LINEAR_AXES 3
175
+
176
+/**
177
+ * Axis codes for additional axes:
178
+ * This defines the axis code that is used in G-code commands to
179
+ * reference a specific axis.
180
+ * 'A' for rotational axis parallel to X
181
+ * 'B' for rotational axis parallel to Y
182
+ * 'C' for rotational axis parallel to Z
183
+ * 'U' for secondary linear axis parallel to X
184
+ * 'V' for secondary linear axis parallel to Y
185
+ * 'W' for secondary linear axis parallel to Z
186
+ * Regardless of the settings, firmware-internal axis IDs are
187
+ * I (AXIS4), J (AXIS5), K (AXIS6).
188
+ */
189
+#if LINEAR_AXES >= 4
190
+  #define AXIS4_NAME 'A' // :['A', 'B', 'C', 'U', 'V', 'W']
191
+#endif
192
+#if LINEAR_AXES >= 5
193
+  #define AXIS5_NAME 'B' // :['A', 'B', 'C', 'U', 'V', 'W']
194
+#endif
195
+#if LINEAR_AXES >= 6
196
+  #define AXIS6_NAME 'C' // :['A', 'B', 'C', 'U', 'V', 'W']
197
+#endif
198
+
152 199
 // @section extruder
153 200
 
154 201
 // This defines the number of extruders
@@ -691,9 +738,15 @@
691 738
 #define USE_XMIN_PLUG
692 739
 #define USE_YMIN_PLUG
693 740
 #define USE_ZMIN_PLUG
741
+//#define USE_IMIN_PLUG
742
+//#define USE_JMIN_PLUG
743
+//#define USE_KMIN_PLUG
694 744
 //#define USE_XMAX_PLUG
695 745
 //#define USE_YMAX_PLUG
696 746
 //#define USE_ZMAX_PLUG
747
+//#define USE_IMAX_PLUG
748
+//#define USE_JMAX_PLUG
749
+//#define USE_KMAX_PLUG
697 750
 
698 751
 // Enable pullup for all endstops to prevent a floating state
699 752
 #define ENDSTOPPULLUPS
@@ -702,9 +755,15 @@
702 755
   //#define ENDSTOPPULLUP_XMAX
703 756
   //#define ENDSTOPPULLUP_YMAX
704 757
   //#define ENDSTOPPULLUP_ZMAX
758
+  //#define ENDSTOPPULLUP_IMAX
759
+  //#define ENDSTOPPULLUP_JMAX
760
+  //#define ENDSTOPPULLUP_KMAX
705 761
   //#define ENDSTOPPULLUP_XMIN
706 762
   //#define ENDSTOPPULLUP_YMIN
707 763
   //#define ENDSTOPPULLUP_ZMIN
764
+  //#define ENDSTOPPULLUP_IMIN
765
+  //#define ENDSTOPPULLUP_JMIN
766
+  //#define ENDSTOPPULLUP_KMIN
708 767
   //#define ENDSTOPPULLUP_ZMIN_PROBE
709 768
 #endif
710 769
 
@@ -715,9 +774,15 @@
715 774
   //#define ENDSTOPPULLDOWN_XMAX
716 775
   //#define ENDSTOPPULLDOWN_YMAX
717 776
   //#define ENDSTOPPULLDOWN_ZMAX
777
+  //#define ENDSTOPPULLDOWN_IMAX
778
+  //#define ENDSTOPPULLDOWN_JMAX
779
+  //#define ENDSTOPPULLDOWN_KMAX
718 780
   //#define ENDSTOPPULLDOWN_XMIN
719 781
   //#define ENDSTOPPULLDOWN_YMIN
720 782
   //#define ENDSTOPPULLDOWN_ZMIN
783
+  //#define ENDSTOPPULLDOWN_IMIN
784
+  //#define ENDSTOPPULLDOWN_JMIN
785
+  //#define ENDSTOPPULLDOWN_KMIN
721 786
   //#define ENDSTOPPULLDOWN_ZMIN_PROBE
722 787
 #endif
723 788
 
@@ -725,9 +790,15 @@
725 790
 #define X_MIN_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop.
726 791
 #define Y_MIN_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop.
727 792
 #define Z_MIN_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop.
793
+#define I_MIN_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop.
794
+#define J_MIN_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop.
795
+#define K_MIN_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop.
728 796
 #define X_MAX_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop.
729 797
 #define Y_MAX_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop.
730 798
 #define Z_MAX_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop.
799
+#define I_MAX_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop.
800
+#define J_MAX_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop.
801
+#define K_MAX_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop.
731 802
 #define Z_MIN_PROBE_ENDSTOP_INVERTING false // Set to true to invert the logic of the probe.
732 803
 
733 804
 /**
@@ -756,6 +827,9 @@
756 827
 //#define Z2_DRIVER_TYPE A4988
757 828
 //#define Z3_DRIVER_TYPE A4988
758 829
 //#define Z4_DRIVER_TYPE A4988
830
+//#define I_DRIVER_TYPE  A4988
831
+//#define J_DRIVER_TYPE  A4988
832
+//#define K_DRIVER_TYPE  A4988
759 833
 #define E0_DRIVER_TYPE A4988
760 834
 //#define E1_DRIVER_TYPE A4988
761 835
 //#define E2_DRIVER_TYPE A4988
@@ -809,14 +883,14 @@
809 883
 /**
810 884
  * Default Axis Steps Per Unit (steps/mm)
811 885
  * Override with M92
812
- *                                      X, Y, Z, E0 [, E1[, E2...]]
886
+ *                                      X, Y, Z [, I [, J [, K]]], E0 [, E1[, E2...]]
813 887
  */
814 888
 #define DEFAULT_AXIS_STEPS_PER_UNIT   { 80, 80, 400, 500 }
815 889
 
816 890
 /**
817 891
  * Default Max Feed Rate (mm/s)
818 892
  * Override with M203
819
- *                                      X, Y, Z, E0 [, E1[, E2...]]
893
+ *                                      X, Y, Z [, I [, J [, K]]], E0 [, E1[, E2...]]
820 894
  */
821 895
 #define DEFAULT_MAX_FEEDRATE          { 300, 300, 5, 25 }
822 896
 
@@ -829,7 +903,7 @@
829 903
  * Default Max Acceleration (change/s) change = mm/s
830 904
  * (Maximum start speed for accelerated moves)
831 905
  * Override with M201
832
- *                                      X, Y, Z, E0 [, E1[, E2...]]
906
+ *                                      X, Y, Z [, I [, J [, K]]], E0 [, E1[, E2...]]
833 907
  */
834 908
 #define DEFAULT_MAX_ACCELERATION      { 3000, 3000, 100, 10000 }
835 909
 
@@ -863,6 +937,9 @@
863 937
   #define DEFAULT_XJERK 10.0
864 938
   #define DEFAULT_YJERK 10.0
865 939
   #define DEFAULT_ZJERK  0.3
940
+  //#define DEFAULT_IJERK  0.3
941
+  //#define DEFAULT_JJERK  0.3
942
+  //#define DEFAULT_KJERK  0.3
866 943
 
867 944
   //#define TRAVEL_EXTRA_XYJERK 0.0     // Additional jerk allowance for all travel moves
868 945
 
@@ -1177,12 +1254,18 @@
1177 1254
 #define Y_ENABLE_ON 0
1178 1255
 #define Z_ENABLE_ON 0
1179 1256
 #define E_ENABLE_ON 0 // For all extruders
1257
+//#define I_ENABLE_ON 0
1258
+//#define J_ENABLE_ON 0
1259
+//#define K_ENABLE_ON 0
1180 1260
 
1181 1261
 // Disable axis steppers immediately when they're not being stepped.
1182 1262
 // WARNING: When motors turn off there is a chance of losing position accuracy!
1183 1263
 #define DISABLE_X false
1184 1264
 #define DISABLE_Y false
1185 1265
 #define DISABLE_Z false
1266
+//#define DISABLE_I false
1267
+//#define DISABLE_J false
1268
+//#define DISABLE_K false
1186 1269
 
1187 1270
 // Turn off the display blinking that warns about possible accuracy reduction
1188 1271
 //#define DISABLE_REDUCED_ACCURACY_WARNING
@@ -1198,6 +1281,9 @@
1198 1281
 #define INVERT_X_DIR false
1199 1282
 #define INVERT_Y_DIR true
1200 1283
 #define INVERT_Z_DIR false
1284
+//#define INVERT_I_DIR false
1285
+//#define INVERT_J_DIR false
1286
+//#define INVERT_K_DIR false
1201 1287
 
1202 1288
 // @section extruder
1203 1289
 
@@ -1233,6 +1319,9 @@
1233 1319
 #define X_HOME_DIR -1
1234 1320
 #define Y_HOME_DIR -1
1235 1321
 #define Z_HOME_DIR -1
1322
+//#define I_HOME_DIR -1
1323
+//#define J_HOME_DIR -1
1324
+//#define K_HOME_DIR -1
1236 1325
 
1237 1326
 // @section machine
1238 1327
 
@@ -1247,6 +1336,12 @@
1247 1336
 #define X_MAX_POS X_BED_SIZE
1248 1337
 #define Y_MAX_POS Y_BED_SIZE
1249 1338
 #define Z_MAX_POS 200
1339
+//#define I_MIN_POS 0
1340
+//#define I_MAX_POS 50
1341
+//#define J_MIN_POS 0
1342
+//#define J_MAX_POS 50
1343
+//#define K_MIN_POS 0
1344
+//#define K_MAX_POS 50
1250 1345
 
1251 1346
 /**
1252 1347
  * Software Endstops
@@ -1263,6 +1358,9 @@
1263 1358
   #define MIN_SOFTWARE_ENDSTOP_X
1264 1359
   #define MIN_SOFTWARE_ENDSTOP_Y
1265 1360
   #define MIN_SOFTWARE_ENDSTOP_Z
1361
+  #define MIN_SOFTWARE_ENDSTOP_I
1362
+  #define MIN_SOFTWARE_ENDSTOP_J
1363
+  #define MIN_SOFTWARE_ENDSTOP_K
1266 1364
 #endif
1267 1365
 
1268 1366
 // Max software endstops constrain movement within maximum coordinate bounds
@@ -1271,6 +1369,9 @@
1271 1369
   #define MAX_SOFTWARE_ENDSTOP_X
1272 1370
   #define MAX_SOFTWARE_ENDSTOP_Y
1273 1371
   #define MAX_SOFTWARE_ENDSTOP_Z
1372
+  #define MAX_SOFTWARE_ENDSTOP_I
1373
+  #define MAX_SOFTWARE_ENDSTOP_J
1374
+  #define MAX_SOFTWARE_ENDSTOP_K
1274 1375
 #endif
1275 1376
 
1276 1377
 #if EITHER(MIN_SOFTWARE_ENDSTOPS, MAX_SOFTWARE_ENDSTOPS)
@@ -1582,6 +1683,9 @@
1582 1683
 //#define MANUAL_X_HOME_POS 0
1583 1684
 //#define MANUAL_Y_HOME_POS 0
1584 1685
 //#define MANUAL_Z_HOME_POS 0
1686
+//#define MANUAL_I_HOME_POS 0
1687
+//#define MANUAL_J_HOME_POS 0
1688
+//#define MANUAL_K_HOME_POS 0
1585 1689
 
1586 1690
 // Use "Z Safe Homing" to avoid homing with a Z probe outside the bed area.
1587 1691
 //

+ 110
- 2
Marlin/Configuration_adv.h View File

@@ -30,7 +30,7 @@
30 30
  *
31 31
  * Basic settings can be found in Configuration.h
32 32
  */
33
-#define CONFIGURATION_ADV_H_VERSION 02000801
33
+#define CONFIGURATION_ADV_H_VERSION 02000900
34 34
 
35 35
 //===========================================================================
36 36
 //============================= Thermal Settings ============================
@@ -918,6 +918,9 @@
918 918
 #define INVERT_X_STEP_PIN false
919 919
 #define INVERT_Y_STEP_PIN false
920 920
 #define INVERT_Z_STEP_PIN false
921
+#define INVERT_I_STEP_PIN false
922
+#define INVERT_J_STEP_PIN false
923
+#define INVERT_K_STEP_PIN false
921 924
 #define INVERT_E_STEP_PIN false
922 925
 
923 926
 /**
@@ -929,6 +932,9 @@
929 932
 #define DISABLE_INACTIVE_X true
930 933
 #define DISABLE_INACTIVE_Y true
931 934
 #define DISABLE_INACTIVE_Z true  // Set 'false' if the nozzle could fall onto your printed part!
935
+#define DISABLE_INACTIVE_I true
936
+#define DISABLE_INACTIVE_J true
937
+#define DISABLE_INACTIVE_K true
932 938
 #define DISABLE_INACTIVE_E true
933 939
 
934 940
 // Default Minimum Feedrates for printing and travel moves
@@ -969,7 +975,7 @@
969 975
 #if ENABLED(BACKLASH_COMPENSATION)
970 976
   // Define values for backlash distance and correction.
971 977
   // If BACKLASH_GCODE is enabled these values are the defaults.
972
-  #define BACKLASH_DISTANCE_MM { 0, 0, 0 } // (mm)
978
+  #define BACKLASH_DISTANCE_MM { 0, 0, 0 } // (mm) One value for each linear axis
973 979
   #define BACKLASH_CORRECTION    0.0       // 0.0 = no correction; 1.0 = full correction
974 980
 
975 981
   // Add steps for motor direction changes on CORE kinematics
@@ -1040,6 +1046,13 @@
1040 1046
   #define CALIBRATION_MEASURE_LEFT
1041 1047
   #define CALIBRATION_MEASURE_BACK
1042 1048
 
1049
+  //#define CALIBRATION_MEASURE_IMIN
1050
+  //#define CALIBRATION_MEASURE_IMAX
1051
+  //#define CALIBRATION_MEASURE_JMIN
1052
+  //#define CALIBRATION_MEASURE_JMAX
1053
+  //#define CALIBRATION_MEASURE_KMIN
1054
+  //#define CALIBRATION_MEASURE_KMAX
1055
+
1043 1056
   // Probing at the exact top center only works if the center is flat. If
1044 1057
   // probing on a screwhead or hollow washer, probe near the edges.
1045 1058
   //#define CALIBRATION_MEASURE_AT_TOP_EDGES
@@ -2237,6 +2250,13 @@
2237 2250
   #endif
2238 2251
 
2239 2252
   /**
2253
+   * Extra G-code to run while executing tool-change commands. Can be used to use an additional
2254
+   * stepper motor (I axis, see option LINEAR_AXES in Configuration.h) to drive the tool-changer.
2255
+   */
2256
+  //#define EVENT_GCODE_TOOLCHANGE_T0 "G28 A\nG1 I0" // Extra G-code to run while executing tool-change command T0
2257
+  //#define EVENT_GCODE_TOOLCHANGE_T1 "G1 A10"       // Extra G-code to run while executing tool-change command T1
2258
+
2259
+  /**
2240 2260
    * Tool Sensors detect when tools have been picked up or dropped.
2241 2261
    * Requires the pins TOOL_SENSOR1_PIN, TOOL_SENSOR2_PIN, etc.
2242 2262
    */
@@ -2413,6 +2433,24 @@
2413 2433
     #define Z4_MICROSTEPS       Z_MICROSTEPS
2414 2434
   #endif
2415 2435
 
2436
+  #if AXIS_DRIVER_TYPE_I(TMC26X)
2437
+    #define I_MAX_CURRENT    1000
2438
+    #define I_SENSE_RESISTOR   91
2439
+    #define I_MICROSTEPS       16
2440
+  #endif
2441
+
2442
+  #if AXIS_DRIVER_TYPE_J(TMC26X)
2443
+    #define J_MAX_CURRENT    1000
2444
+    #define J_SENSE_RESISTOR   91
2445
+    #define J_MICROSTEPS       16
2446
+  #endif
2447
+
2448
+  #if AXIS_DRIVER_TYPE_K(TMC26X)
2449
+    #define K_MAX_CURRENT    1000
2450
+    #define K_SENSE_RESISTOR   91
2451
+    #define K_MICROSTEPS       16
2452
+  #endif
2453
+
2416 2454
   #if AXIS_DRIVER_TYPE_E0(TMC26X)
2417 2455
     #define E0_MAX_CURRENT    1000
2418 2456
     #define E0_SENSE_RESISTOR   91
@@ -2563,6 +2601,33 @@
2563 2601
     //#define Z4_INTERPOLATE true
2564 2602
   #endif
2565 2603
 
2604
+  #if AXIS_IS_TMC(I)
2605
+    #define I_CURRENT      800
2606
+    #define I_CURRENT_HOME I_CURRENT
2607
+    #define I_MICROSTEPS    16
2608
+    #define I_RSENSE         0.11
2609
+    #define I_CHAIN_POS     -1
2610
+    //#define I_INTERPOLATE  true
2611
+  #endif
2612
+
2613
+  #if AXIS_IS_TMC(J)
2614
+    #define J_CURRENT      800
2615
+    #define J_CURRENT_HOME J_CURRENT
2616
+    #define J_MICROSTEPS    16
2617
+    #define J_RSENSE         0.11
2618
+    #define J_CHAIN_POS     -1
2619
+    //#define J_INTERPOLATE  true
2620
+  #endif
2621
+
2622
+  #if AXIS_IS_TMC(K)
2623
+    #define K_CURRENT      800
2624
+    #define K_CURRENT_HOME K_CURRENT
2625
+    #define K_MICROSTEPS    16
2626
+    #define K_RSENSE         0.11
2627
+    #define K_CHAIN_POS     -1
2628
+    //#define K_INTERPOLATE  true
2629
+  #endif
2630
+
2566 2631
   #if AXIS_IS_TMC(E0)
2567 2632
     #define E0_CURRENT      800
2568 2633
     #define E0_MICROSTEPS    16
@@ -2638,6 +2703,10 @@
2638 2703
   //#define Y2_CS_PIN         -1
2639 2704
   //#define Z2_CS_PIN         -1
2640 2705
   //#define Z3_CS_PIN         -1
2706
+  //#define Z4_CS_PIN         -1
2707
+  //#define I_CS_PIN          -1
2708
+  //#define J_CS_PIN          -1
2709
+  //#define K_CS_PIN          -1
2641 2710
   //#define E0_CS_PIN         -1
2642 2711
   //#define E1_CS_PIN         -1
2643 2712
   //#define E2_CS_PIN         -1
@@ -2677,6 +2746,9 @@
2677 2746
   //#define Z2_SLAVE_ADDRESS 0
2678 2747
   //#define Z3_SLAVE_ADDRESS 0
2679 2748
   //#define Z4_SLAVE_ADDRESS 0
2749
+  //#define  I_SLAVE_ADDRESS 0
2750
+  //#define  J_SLAVE_ADDRESS 0
2751
+  //#define  K_SLAVE_ADDRESS 0
2680 2752
   //#define E0_SLAVE_ADDRESS 0
2681 2753
   //#define E1_SLAVE_ADDRESS 0
2682 2754
   //#define E2_SLAVE_ADDRESS 0
@@ -2701,6 +2773,9 @@
2701 2773
    */
2702 2774
   #define STEALTHCHOP_XY
2703 2775
   #define STEALTHCHOP_Z
2776
+  #define STEALTHCHOP_I
2777
+  #define STEALTHCHOP_J
2778
+  #define STEALTHCHOP_K
2704 2779
   #define STEALTHCHOP_E
2705 2780
 
2706 2781
   /**
@@ -2772,6 +2847,9 @@
2772 2847
   #define Z2_HYBRID_THRESHOLD      3
2773 2848
   #define Z3_HYBRID_THRESHOLD      3
2774 2849
   #define Z4_HYBRID_THRESHOLD      3
2850
+  #define I_HYBRID_THRESHOLD       3
2851
+  #define J_HYBRID_THRESHOLD       3
2852
+  #define K_HYBRID_THRESHOLD       3
2775 2853
   #define E0_HYBRID_THRESHOLD     30
2776 2854
   #define E1_HYBRID_THRESHOLD     30
2777 2855
   #define E2_HYBRID_THRESHOLD     30
@@ -2818,6 +2896,9 @@
2818 2896
     //#define Z2_STALL_SENSITIVITY Z_STALL_SENSITIVITY
2819 2897
     //#define Z3_STALL_SENSITIVITY Z_STALL_SENSITIVITY
2820 2898
     //#define Z4_STALL_SENSITIVITY Z_STALL_SENSITIVITY
2899
+    //#define I_STALL_SENSITIVITY  8
2900
+    //#define J_STALL_SENSITIVITY  8
2901
+    //#define K_STALL_SENSITIVITY  8
2821 2902
     //#define SPI_ENDSTOPS              // TMC2130 only
2822 2903
     //#define IMPROVE_HOMING_RELIABILITY
2823 2904
   #endif
@@ -2958,6 +3039,33 @@
2958 3039
     #define Z4_SLEW_RATE                 1
2959 3040
   #endif
2960 3041
 
3042
+  #if AXIS_DRIVER_TYPE_I(L6470)
3043
+    #define I_MICROSTEPS      128
3044
+    #define I_OVERCURRENT    2000
3045
+    #define I_STALLCURRENT   1500
3046
+    #define I_MAX_VOLTAGE     127
3047
+    #define I_CHAIN_POS        -1
3048
+    #define I_SLEW_RATE         1
3049
+  #endif
3050
+
3051
+  #if AXIS_DRIVER_TYPE_J(L6470)
3052
+    #define J_MICROSTEPS      128
3053
+    #define J_OVERCURRENT    2000
3054
+    #define J_STALLCURRENT   1500
3055
+    #define J_MAX_VOLTAGE     127
3056
+    #define J_CHAIN_POS        -1
3057
+    #define J_SLEW_RATE         1
3058
+  #endif
3059
+
3060
+  #if AXIS_DRIVER_TYPE_K(L6470)
3061
+    #define K_MICROSTEPS      128
3062
+    #define K_OVERCURRENT    2000
3063
+    #define K_STALLCURRENT   1500
3064
+    #define K_MAX_VOLTAGE     127
3065
+    #define K_CHAIN_POS        -1
3066
+    #define K_SLEW_RATE         1
3067
+  #endif
3068
+
2961 3069
   #if AXIS_IS_L64XX(E0)
2962 3070
     #define E0_MICROSTEPS              128
2963 3071
     #define E0_OVERCURRENT            2000

+ 45
- 1
Marlin/src/HAL/AVR/endstop_interrupts.h View File

@@ -168,6 +168,51 @@ void setup_endstop_interrupts() {
168 168
       pciSetup(Z_MIN_PIN);
169 169
     #endif
170 170
   #endif
171
+  #if HAS_I_MAX
172
+    #if (digitalPinToInterrupt(I_MAX_PIN) != NOT_AN_INTERRUPT)
173
+      _ATTACH(I_MAX_PIN);
174
+    #else
175
+      static_assert(digitalPinHasPCICR(I_MAX_PIN), "I_MAX_PIN is not interrupt-capable");
176
+      pciSetup(I_MAX_PIN);
177
+    #endif
178
+  #elif HAS_I_MIN
179
+    #if (digitalPinToInterrupt(I_MIN_PIN) != NOT_AN_INTERRUPT)
180
+      _ATTACH(I_MIN_PIN);
181
+    #else
182
+      static_assert(digitalPinHasPCICR(I_MIN_PIN), "I_MIN_PIN is not interrupt-capable");
183
+      pciSetup(I_MIN_PIN);
184
+    #endif
185
+  #endif
186
+  #if HAS_J_MAX
187
+    #if (digitalPinToInterrupt(J_MAX_PIN) != NOT_AN_INTERRUPT)
188
+      _ATTACH(J_MAX_PIN);
189
+    #else
190
+      static_assert(digitalPinHasPCICR(J_MAX_PIN), "J_MAX_PIN is not interrupt-capable");
191
+      pciSetup(J_MAX_PIN);
192
+    #endif
193
+  #elif HAS_J_MIN
194
+    #if (digitalPinToInterrupt(J_MIN_PIN) != NOT_AN_INTERRUPT)
195
+      _ATTACH(J_MIN_PIN);
196
+    #else
197
+      static_assert(digitalPinHasPCICR(J_MIN_PIN), "J_MIN_PIN is not interrupt-capable");
198
+      pciSetup(J_MIN_PIN);
199
+    #endif
200
+  #endif
201
+  #if HAS_K_MAX
202
+    #if (digitalPinToInterrupt(K_MAX_PIN) != NOT_AN_INTERRUPT)
203
+      _ATTACH(K_MAX_PIN);
204
+    #else
205
+      static_assert(digitalPinHasPCICR(K_MAX_PIN), "K_MAX_PIN is not interrupt-capable");
206
+      pciSetup(K_MAX_PIN);
207
+    #endif
208
+  #elif HAS_K_MIN
209
+    #if (digitalPinToInterrupt(K_MIN_PIN) != NOT_AN_INTERRUPT)
210
+      _ATTACH(K_MIN_PIN);
211
+    #else
212
+      static_assert(digitalPinHasPCICR(K_MIN_PIN), "K_MIN_PIN is not interrupt-capable");
213
+      pciSetup(K_MIN_PIN);
214
+    #endif
215
+  #endif
171 216
   #if HAS_X2_MAX
172 217
     #if (digitalPinToInterrupt(X2_MAX_PIN) != NOT_AN_INTERRUPT)
173 218
       _ATTACH(X2_MAX_PIN);
@@ -256,6 +301,5 @@ void setup_endstop_interrupts() {
256 301
       pciSetup(Z_MIN_PROBE_PIN);
257 302
     #endif
258 303
   #endif
259
-
260 304
   // If we arrive here without raising an assertion, each pin has either an EXT-interrupt or a PCI.
261 305
 }

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

@@ -64,4 +64,10 @@ void setup_endstop_interrupts() {
64 64
   TERN_(HAS_Z4_MAX, _ATTACH(Z4_MAX_PIN));
65 65
   TERN_(HAS_Z4_MIN, _ATTACH(Z4_MIN_PIN));
66 66
   TERN_(HAS_Z_MIN_PROBE_PIN, _ATTACH(Z_MIN_PROBE_PIN));
67
+  TERN_(HAS_I_MAX, _ATTACH(I_MAX_PIN));
68
+  TERN_(HAS_I_MIN, _ATTACH(I_MIN_PIN));
69
+  TERN_(HAS_J_MAX, _ATTACH(J_MAX_PIN));
70
+  TERN_(HAS_J_MIN, _ATTACH(J_MIN_PIN));
71
+  TERN_(HAS_K_MAX, _ATTACH(K_MAX_PIN));
72
+  TERN_(HAS_K_MIN, _ATTACH(K_MIN_PIN));
67 73
 }

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

@@ -59,4 +59,10 @@ void setup_endstop_interrupts() {
59 59
   TERN_(HAS_Z4_MAX, _ATTACH(Z4_MAX_PIN));
60 60
   TERN_(HAS_Z4_MIN, _ATTACH(Z4_MIN_PIN));
61 61
   TERN_(HAS_Z_MIN_PROBE_PIN, _ATTACH(Z_MIN_PROBE_PIN));
62
+  TERN_(HAS_I_MAX, _ATTACH(I_MAX_PIN));
63
+  TERN_(HAS_I_MIN, _ATTACH(I_MIN_PIN));
64
+  TERN_(HAS_J_MAX, _ATTACH(J_MAX_PIN));
65
+  TERN_(HAS_J_MIN, _ATTACH(J_MIN_PIN));
66
+  TERN_(HAS_K_MAX, _ATTACH(K_MAX_PIN));
67
+  TERN_(HAS_K_MIN, _ATTACH(K_MIN_PIN));
62 68
 }

+ 33
- 0
Marlin/src/HAL/LPC1768/endstop_interrupts.h View File

@@ -122,4 +122,37 @@ void setup_endstop_interrupts() {
122 122
     #endif
123 123
     _ATTACH(Z_MIN_PROBE_PIN);
124 124
   #endif
125
+  #if HAS_I_MAX
126
+    #if !LPC1768_PIN_INTERRUPT_M(I_MAX_PIN)
127
+      #error "I_MAX_PIN is not INTERRUPT-capable."
128
+    #endif
129
+    _ATTACH(I_MAX_PIN);
130
+  #elif HAS_I_MIN
131
+    #if !LPC1768_PIN_INTERRUPT_M(I_MIN_PIN)
132
+      #error "I_MIN_PIN is not INTERRUPT-capable."
133
+    #endif
134
+    _ATTACH(I_MIN_PIN);
135
+  #endif
136
+  #if HAS_J_MAX
137
+    #if !LPC1768_PIN_INTERRUPT_M(J_MAX_PIN)
138
+      #error "J_MAX_PIN is not INTERRUPT-capable."
139
+    #endif
140
+    _ATTACH(J_MAX_PIN);
141
+  #elif HAS_J_MIN
142
+    #if !LPC1768_PIN_INTERRUPT_M(J_MIN_PIN)
143
+      #error "J_MIN_PIN is not INTERRUPT-capable."
144
+    #endif
145
+    _ATTACH(J_MIN_PIN);
146
+  #endif
147
+  #if HAS_K_MAX
148
+    #if !LPC1768_PIN_INTERRUPT_M(K_MAX_PIN)
149
+      #error "K_MAX_PIN is not INTERRUPT-capable."
150
+    #endif
151
+    _ATTACH(K_MAX_PIN);
152
+  #elif HAS_K_MIN
153
+    #if !LPC1768_PIN_INTERRUPT_M(K_MIN_PIN)
154
+      #error "K_MIN_PIN is not INTERRUPT-capable."
155
+    #endif
156
+    _ATTACH(K_MIN_PIN);
157
+  #endif
125 158
 }

+ 64
- 74
Marlin/src/HAL/SAMD51/endstop_interrupts.h View File

@@ -47,80 +47,38 @@
47 47
 
48 48
 #include "../../module/endstops.h"
49 49
 
50
-#define MATCH_EILINE(P1,P2)     (P1 != P2 && PIN_TO_EILINE(P1) == PIN_TO_EILINE(P2))
51
-#if HAS_X_MAX
52
-  #define MATCH_X_MAX_EILINE(P) MATCH_EILINE(P, X_MAX_PIN)
53
-#else
54
-  #define MATCH_X_MAX_EILINE(P) false
55
-#endif
56
-#if HAS_X_MIN
57
-  #define MATCH_X_MIN_EILINE(P) MATCH_EILINE(P, X_MIN_PIN)
58
-#else
59
-  #define MATCH_X_MIN_EILINE(P) false
60
-#endif
61
-#if HAS_Y_MAX
62
-   #define MATCH_Y_MAX_EILINE(P) MATCH_EILINE(P, Y_MAX_PIN)
63
-#else
64
-   #define MATCH_Y_MAX_EILINE(P) false
65
-#endif
66
-#if HAS_Y_MIN
67
-  #define MATCH_Y_MIN_EILINE(P) MATCH_EILINE(P, Y_MIN_PIN)
68
-#else
69
-  #define MATCH_Y_MIN_EILINE(P) false
70
-#endif
71
-#if HAS_Z_MAX
72
-   #define MATCH_Z_MAX_EILINE(P) MATCH_EILINE(P, Z_MAX_PIN)
73
-#else
74
-  #define MATCH_Z_MAX_EILINE(P) false
75
-#endif
76
-#if HAS_Z_MIN
77
-  #define MATCH_Z_MIN_EILINE(P) MATCH_EILINE(P, Z_MIN_PIN)
78
-#else
79
-  #define MATCH_Z_MIN_EILINE(P) false
80
-#endif
81
-#if HAS_Z2_MAX
82
-  #define MATCH_Z2_MAX_EILINE(P) MATCH_EILINE(P, Z2_MAX_PIN)
83
-#else
84
-  #define MATCH_Z2_MAX_EILINE(P) false
85
-#endif
86
-#if HAS_Z2_MIN
87
-  #define MATCH_Z2_MIN_EILINE(P) MATCH_EILINE(P, Z2_MIN_PIN)
88
-#else
89
-  #define MATCH_Z2_MIN_EILINE(P) false
90
-#endif
91
-#if HAS_Z3_MAX
92
-  #define MATCH_Z3_MAX_EILINE(P) MATCH_EILINE(P, Z3_MAX_PIN)
93
-#else
94
-  #define MATCH_Z3_MAX_EILINE(P) false
95
-#endif
96
-#if HAS_Z3_MIN
97
-  #define MATCH_Z3_MIN_EILINE(P) MATCH_EILINE(P, Z3_MIN_PIN)
98
-#else
99
-  #define MATCH_Z3_MIN_EILINE(P) false
100
-#endif
101
-#if HAS_Z4_MAX
102
-  #define MATCH_Z4_MAX_EILINE(P) MATCH_EILINE(P, Z4_MAX_PIN)
103
-#else
104
-  #define MATCH_Z4_MAX_EILINE(P) false
105
-#endif
106
-#if HAS_Z4_MIN
107
-  #define MATCH_Z4_MIN_EILINE(P) MATCH_EILINE(P, Z4_MIN_PIN)
108
-#else
109
-  #define MATCH_Z4_MIN_EILINE(P) false
110
-#endif
111
-#if HAS_Z_MIN_PROBE_PIN
112
-  #define MATCH_Z_MIN_PROBE_EILINE(P)   MATCH_EILINE(P, Z_MIN_PROBE_PIN)
113
-#else
114
-  #define MATCH_Z_MIN_PROBE_EILINE(P) false
115
-#endif
116
-#define AVAILABLE_EILINE(P)     (PIN_TO_EILINE(P) != -1                                 \
117
-                                 && !MATCH_X_MAX_EILINE(P) && !MATCH_X_MIN_EILINE(P)    \
118
-                                 && !MATCH_Y_MAX_EILINE(P) && !MATCH_Y_MIN_EILINE(P)    \
119
-                                 && !MATCH_Z_MAX_EILINE(P) && !MATCH_Z_MIN_EILINE(P)    \
120
-                                 && !MATCH_Z2_MAX_EILINE(P) && !MATCH_Z2_MIN_EILINE(P)  \
121
-                                 && !MATCH_Z3_MAX_EILINE(P) && !MATCH_Z3_MIN_EILINE(P)  \
122
-                                 && !MATCH_Z4_MAX_EILINE(P) && !MATCH_Z4_MIN_EILINE(P)  \
123
-                                 && !MATCH_Z_MIN_PROBE_EILINE(P))
50
+#define MATCH_EILINE(P1,P2) (P1 != P2 && PIN_TO_EILINE(P1) == PIN_TO_EILINE(P2))
51
+#define MATCH_X_MAX_EILINE(P)   TERN0(HAS_X_MAX,  DEFER4(MATCH_EILINE)(P, X_MAX_PIN))
52
+#define MATCH_X_MIN_EILINE(P)   TERN0(HAS_X_MIN,  DEFER4(MATCH_EILINE)(P, X_MIN_PIN))
53
+#define MATCH_Y_MAX_EILINE(P)   TERN0(HAS_Y_MAX,  DEFER4(MATCH_EILINE)(P, Y_MAX_PIN))
54
+#define MATCH_Y_MIN_EILINE(P)   TERN0(HAS_Y_MIN,  DEFER4(MATCH_EILINE)(P, Y_MIN_PIN))
55
+#define MATCH_Z_MAX_EILINE(P)   TERN0(HAS_Z_MAX,  DEFER4(MATCH_EILINE)(P, Z_MAX_PIN))
56
+#define MATCH_Z_MIN_EILINE(P)   TERN0(HAS_Z_MIN,  DEFER4(MATCH_EILINE)(P, Z_MIN_PIN))
57
+#define MATCH_I_MAX_EILINE(P)   TERN0(HAS_I_MAX,  DEFER4(MATCH_EILINE)(P, I_MAX_PIN))
58
+#define MATCH_I_MIN_EILINE(P)   TERN0(HAS_I_MIN,  DEFER4(MATCH_EILINE)(P, I_MIN_PIN))
59
+#define MATCH_J_MAX_EILINE(P)   TERN0(HAS_J_MAX,  DEFER4(MATCH_EILINE)(P, J_MAX_PIN))
60
+#define MATCH_J_MIN_EILINE(P)   TERN0(HAS_J_MIN,  DEFER4(MATCH_EILINE)(P, J_MIN_PIN))
61
+#define MATCH_K_MAX_EILINE(P)   TERN0(HAS_K_MAX,  DEFER4(MATCH_EILINE)(P, K_MAX_PIN))
62
+#define MATCH_K_MIN_EILINE(P)   TERN0(HAS_K_MIN,  DEFER4(MATCH_EILINE)(P, K_MIN_PIN))
63
+#define MATCH_Z2_MAX_EILINE(P)  TERN0(HAS_Z2_MAX, DEFER4(MATCH_EILINE)(P, Z2_MAX_PIN))
64
+#define MATCH_Z2_MIN_EILINE(P)  TERN0(HAS_Z2_MIN, DEFER4(MATCH_EILINE)(P, Z2_MIN_PIN))
65
+#define MATCH_Z3_MAX_EILINE(P)  TERN0(HAS_Z3_MAX, DEFER4(MATCH_EILINE)(P, Z3_MAX_PIN))
66
+#define MATCH_Z3_MIN_EILINE(P)  TERN0(HAS_Z3_MIN, DEFER4(MATCH_EILINE)(P, Z3_MIN_PIN))
67
+#define MATCH_Z4_MAX_EILINE(P)  TERN0(HAS_Z4_MAX, DEFER4(MATCH_EILINE)(P, Z4_MAX_PIN))
68
+#define MATCH_Z4_MIN_EILINE(P)  TERN0(HAS_Z4_MIN, DEFER4(MATCH_EILINE)(P, Z4_MIN_PIN))
69
+#define MATCH_Z_MIN_PROBE_EILINE(P) TERN0(HAS_Z_MIN_PROBE_PIN, DEFER4(MATCH_EILINE)(P, Z_MIN_PROBE_PIN))
70
+
71
+#define AVAILABLE_EILINE(P) ( PIN_TO_EILINE(P) != -1    \
72
+  && !MATCH_X_MAX_EILINE(P) && !MATCH_X_MIN_EILINE(P)   \
73
+  && !MATCH_Y_MAX_EILINE(P) && !MATCH_Y_MIN_EILINE(P)   \
74
+  && !MATCH_Z_MAX_EILINE(P) && !MATCH_Z_MIN_EILINE(P)   \
75
+  && !MATCH_I_MAX_EILINE(P) && !MATCH_I_MIN_EILINE(P)   \
76
+  && !MATCH_J_MAX_EILINE(P) && !MATCH_J_MIN_EILINE(P)   \
77
+  && !MATCH_K_MAX_EILINE(P) && !MATCH_K_MIN_EILINE(P)   \
78
+  && !MATCH_Z2_MAX_EILINE(P) && !MATCH_Z2_MIN_EILINE(P) \
79
+  && !MATCH_Z3_MAX_EILINE(P) && !MATCH_Z3_MIN_EILINE(P) \
80
+  && !MATCH_Z4_MAX_EILINE(P) && !MATCH_Z4_MIN_EILINE(P) \
81
+  && !MATCH_Z_MIN_PROBE_EILINE(P) )
124 82
 
125 83
 // One ISR for all EXT-Interrupts
126 84
 void endstop_ISR() { endstops.update(); }
@@ -204,5 +162,37 @@ void setup_endstop_interrupts() {
204 162
       #error "Z_MIN_PROBE_PIN has no EXTINT line available."
205 163
     #endif
206 164
     _ATTACH(Z_MIN_PROBE_PIN);
165
+  #elif HAS_I_MAX
166
+    #if !AVAILABLE_EILINE(I_MAX_PIN)
167
+      #error "I_MAX_PIN has no EXTINT line available."
168
+    #endif
169
+    attachInterrupt(I_MAX_PIN, endstop_ISR, CHANGE);
170
+  #elif HAS_I_MIN
171
+    #if !AVAILABLE_EILINE(I_MIN_PIN)
172
+      #error "I_MIN_PIN has no EXTINT line available."
173
+    #endif
174
+    attachInterrupt(I_MIN_PIN, endstop_ISR, CHANGE);
175
+  #endif
176
+  #if HAS_J_MAX
177
+    #if !AVAILABLE_EILINE(J_MAX_PIN)
178
+      #error "J_MAX_PIN has no EXTINT line available."
179
+    #endif
180
+    attachInterrupt(J_MAX_PIN, endstop_ISR, CHANGE);
181
+  #elif HAS_J_MIN
182
+    #if !AVAILABLE_EILINE(J_MIN_PIN)
183
+      #error "J_MIN_PIN has no EXTINT line available."
184
+    #endif
185
+    attachInterrupt(J_MIN_PIN, endstop_ISR, CHANGE);
186
+  #endif
187
+  #if HAS_K_MAX
188
+    #if !AVAILABLE_EILINE(K_MAX_PIN)
189
+      #error "K_MAX_PIN has no EXTINT line available."
190
+    #endif
191
+    attachInterrupt(K_MAX_PIN, endstop_ISR, CHANGE);
192
+  #elif HAS_K_MIN
193
+    #if !AVAILABLE_EILINE(K_MIN_PIN)
194
+      #error "K_MIN_PIN has no EXTINT line available."
195
+    #endif
196
+    attachInterrupt(K_MIN_PIN, endstop_ISR, CHANGE);
207 197
   #endif
208 198
 }

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

@@ -46,4 +46,10 @@ void setup_endstop_interrupts() {
46 46
   TERN_(HAS_Z4_MAX, _ATTACH(Z4_MAX_PIN));
47 47
   TERN_(HAS_Z4_MIN, _ATTACH(Z4_MIN_PIN));
48 48
   TERN_(HAS_Z_MIN_PROBE_PIN, _ATTACH(Z_MIN_PROBE_PIN));
49
+  TERN_(HAS_I_MAX, _ATTACH(I_MAX_PIN));
50
+  TERN_(HAS_I_MIN, _ATTACH(I_MIN_PIN));
51
+  TERN_(HAS_J_MAX, _ATTACH(J_MAX_PIN));
52
+  TERN_(HAS_J_MIN, _ATTACH(J_MIN_PIN));
53
+  TERN_(HAS_K_MAX, _ATTACH(K_MAX_PIN));
54
+  TERN_(HAS_K_MIN, _ATTACH(K_MIN_PIN));
49 55
 }

+ 9
- 0
Marlin/src/HAL/STM32F1/MarlinSerial.cpp View File

@@ -167,6 +167,15 @@ constexpr bool IsSerialClassAllowed(const HardwareSerial&) { return false; }
167 167
 #if AXIS_HAS_HW_SERIAL(Z4)
168 168
   CHECK_AXIS_SERIAL(Z4);
169 169
 #endif
170
+#if AXIS_HAS_HW_SERIAL(I)
171
+  CHECK_AXIS_SERIAL(I);
172
+#endif
173
+#if AXIS_HAS_HW_SERIAL(J)
174
+  CHECK_AXIS_SERIAL(J);
175
+#endif
176
+#if AXIS_HAS_HW_SERIAL(K)
177
+  CHECK_AXIS_SERIAL(K);
178
+#endif
170 179
 #if AXIS_HAS_HW_SERIAL(E0)
171 180
   CHECK_AXIS_SERIAL(E0);
172 181
 #endif

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

@@ -71,4 +71,10 @@ void setup_endstop_interrupts() {
71 71
   TERN_(HAS_Z4_MAX, _ATTACH(Z4_MAX_PIN));
72 72
   TERN_(HAS_Z4_MIN, _ATTACH(Z4_MIN_PIN));
73 73
   TERN_(HAS_Z_MIN_PROBE_PIN, _ATTACH(Z_MIN_PROBE_PIN));
74
+  TERN_(HAS_I_MAX, _ATTACH(I_MAX_PIN));
75
+  TERN_(HAS_I_MIN, _ATTACH(I_MIN_PIN));
76
+  TERN_(HAS_J_MAX, _ATTACH(J_MAX_PIN));
77
+  TERN_(HAS_J_MIN, _ATTACH(J_MIN_PIN));
78
+  TERN_(HAS_K_MAX, _ATTACH(K_MAX_PIN));
79
+  TERN_(HAS_K_MIN, _ATTACH(K_MIN_PIN));
74 80
 }

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

@@ -64,4 +64,10 @@ void setup_endstop_interrupts() {
64 64
   TERN_(HAS_Z4_MAX, _ATTACH(Z4_MAX_PIN));
65 65
   TERN_(HAS_Z4_MIN, _ATTACH(Z4_MIN_PIN));
66 66
   TERN_(HAS_Z_MIN_PROBE_PIN, _ATTACH(Z_MIN_PROBE_PIN));
67
+  TERN_(HAS_I_MAX, _ATTACH(I_MAX_PIN));
68
+  TERN_(HAS_I_MIN, _ATTACH(I_MIN_PIN));
69
+  TERN_(HAS_J_MAX, _ATTACH(J_MAX_PIN));
70
+  TERN_(HAS_J_MIN, _ATTACH(J_MIN_PIN));
71
+  TERN_(HAS_K_MAX, _ATTACH(K_MAX_PIN));
72
+  TERN_(HAS_K_MIN, _ATTACH(K_MIN_PIN));
67 73
 }

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

@@ -63,4 +63,10 @@ void setup_endstop_interrupts() {
63 63
   TERN_(HAS_Z4_MAX, _ATTACH(Z4_MAX_PIN));
64 64
   TERN_(HAS_Z4_MIN, _ATTACH(Z4_MIN_PIN));
65 65
   TERN_(HAS_Z_MIN_PROBE_PIN, _ATTACH(Z_MIN_PROBE_PIN));
66
+  TERN_(HAS_I_MAX, _ATTACH(I_MAX_PIN));
67
+  TERN_(HAS_I_MIN, _ATTACH(I_MIN_PIN));
68
+  TERN_(HAS_J_MAX, _ATTACH(J_MAX_PIN));
69
+  TERN_(HAS_J_MIN, _ATTACH(J_MIN_PIN));
70
+  TERN_(HAS_K_MAX, _ATTACH(K_MAX_PIN));
71
+  TERN_(HAS_K_MIN, _ATTACH(K_MIN_PIN));
66 72
 }

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

@@ -63,4 +63,10 @@ void setup_endstop_interrupts() {
63 63
   TERN_(HAS_Z4_MAX, _ATTACH(Z4_MAX_PIN));
64 64
   TERN_(HAS_Z4_MIN, _ATTACH(Z4_MIN_PIN));
65 65
   TERN_(HAS_Z_MIN_PROBE_PIN, _ATTACH(Z_MIN_PROBE_PIN));
66
+  TERN_(HAS_I_MAX, _ATTACH(I_MAX_PIN));
67
+  TERN_(HAS_I_MIN, _ATTACH(I_MIN_PIN));
68
+  TERN_(HAS_J_MAX, _ATTACH(J_MAX_PIN));
69
+  TERN_(HAS_J_MIN, _ATTACH(J_MIN_PIN));
70
+  TERN_(HAS_K_MAX, _ATTACH(K_MAX_PIN));
71
+  TERN_(HAS_K_MIN, _ATTACH(K_MIN_PIN));
66 72
 }

+ 18
- 0
Marlin/src/MarlinCore.cpp View File

@@ -304,6 +304,9 @@ void enable_all_steppers() {
304 304
   ENABLE_AXIS_X();
305 305
   ENABLE_AXIS_Y();
306 306
   ENABLE_AXIS_Z();
307
+  ENABLE_AXIS_I(); // Marlin 6-axis support by DerAndere (https://github.com/DerAndere1/Marlin/wiki)
308
+  ENABLE_AXIS_J();
309
+  ENABLE_AXIS_K();
307 310
   enable_e_steppers();
308 311
 
309 312
   TERN_(EXTENSIBLE_UI, ExtUI::onSteppersEnabled());
@@ -325,6 +328,9 @@ void disable_all_steppers() {
325 328
   DISABLE_AXIS_X();
326 329
   DISABLE_AXIS_Y();
327 330
   DISABLE_AXIS_Z();
331
+  DISABLE_AXIS_I();
332
+  DISABLE_AXIS_J();
333
+  DISABLE_AXIS_K();
328 334
   disable_e_steppers();
329 335
 
330 336
   TERN_(EXTENSIBLE_UI, ExtUI::onSteppersDisabled());
@@ -444,6 +450,9 @@ inline void manage_inactivity(const bool ignore_stepper_queue=false) {
444 450
         if (ENABLED(DISABLE_INACTIVE_X)) DISABLE_AXIS_X();
445 451
         if (ENABLED(DISABLE_INACTIVE_Y)) DISABLE_AXIS_Y();
446 452
         if (ENABLED(DISABLE_INACTIVE_Z)) DISABLE_AXIS_Z();
453
+        if (ENABLED(DISABLE_INACTIVE_I)) DISABLE_AXIS_I();
454
+        if (ENABLED(DISABLE_INACTIVE_J)) DISABLE_AXIS_J();
455
+        if (ENABLED(DISABLE_INACTIVE_K)) DISABLE_AXIS_K();
447 456
         if (ENABLED(DISABLE_INACTIVE_E)) disable_e_steppers();
448 457
 
449 458
         TERN_(AUTO_BED_LEVELING_UBL, ubl.steppers_were_disabled());
@@ -935,6 +944,15 @@ inline void tmc_standby_setup() {
935 944
   #if PIN_EXISTS(Z4_STDBY)
936 945
     SET_INPUT_PULLDOWN(Z4_STDBY_PIN);
937 946
   #endif
947
+  #if PIN_EXISTS(I_STDBY)
948
+    SET_INPUT_PULLDOWN(I_STDBY_PIN);
949
+  #endif
950
+  #if PIN_EXISTS(J_STDBY)
951
+    SET_INPUT_PULLDOWN(J_STDBY_PIN);
952
+  #endif
953
+  #if PIN_EXISTS(K_STDBY)
954
+    SET_INPUT_PULLDOWN(K_STDBY_PIN);
955
+  #endif
938 956
   #if PIN_EXISTS(E0_STDBY)
939 957
     SET_INPUT_PULLDOWN(E0_STDBY_PIN);
940 958
   #endif

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

@@ -60,6 +60,9 @@
60 60
 #define AXIS_DRIVER_TYPE_X(T) _AXIS_DRIVER_TYPE(X,T)
61 61
 #define AXIS_DRIVER_TYPE_Y(T) _AXIS_DRIVER_TYPE(Y,T)
62 62
 #define AXIS_DRIVER_TYPE_Z(T) _AXIS_DRIVER_TYPE(Z,T)
63
+#define AXIS_DRIVER_TYPE_I(T) _AXIS_DRIVER_TYPE(I,T)
64
+#define AXIS_DRIVER_TYPE_J(T) _AXIS_DRIVER_TYPE(J,T)
65
+#define AXIS_DRIVER_TYPE_K(T) _AXIS_DRIVER_TYPE(K,T)
63 66
 
64 67
 #define AXIS_DRIVER_TYPE_X2(T) (EITHER(X_DUAL_STEPPER_DRIVERS, DUAL_X_CARRIAGE) && _AXIS_DRIVER_TYPE(X2,T))
65 68
 #define AXIS_DRIVER_TYPE_Y2(T) (ENABLED(Y_DUAL_STEPPER_DRIVERS) && _AXIS_DRIVER_TYPE(Y2,T))
@@ -83,6 +86,7 @@
83 86
 #define HAS_E_DRIVER(T) (0 RREPEAT2(E_STEPPERS, _OR_ADTE, T))
84 87
 
85 88
 #define HAS_DRIVER(T) (  AXIS_DRIVER_TYPE_X(T)  || AXIS_DRIVER_TYPE_Y(T)  || AXIS_DRIVER_TYPE_Z(T)  \
89
+                      || AXIS_DRIVER_TYPE_I(T)  || AXIS_DRIVER_TYPE_J(T)  || AXIS_DRIVER_TYPE_K(T)  \
86 90
                       || AXIS_DRIVER_TYPE_X2(T) || AXIS_DRIVER_TYPE_Y2(T) || AXIS_DRIVER_TYPE_Z2(T) \
87 91
                       || AXIS_DRIVER_TYPE_Z3(T) || AXIS_DRIVER_TYPE_Z4(T) || HAS_E_DRIVER(T) )
88 92
 
@@ -153,9 +157,11 @@
153 157
 #define _OR_EAH(N,T)    || AXIS_HAS_##T(E##N)
154 158
 #define E_AXIS_HAS(T)   (0 _OR_EAH(0,T) _OR_EAH(1,T) _OR_EAH(2,T) _OR_EAH(3,T) _OR_EAH(4,T) _OR_EAH(5,T) _OR_EAH(6,T) _OR_EAH(7,T))
155 159
 
156
-#define ANY_AXIS_HAS(T) (    AXIS_HAS_##T(X)  || AXIS_HAS_##T(Y)  || AXIS_HAS_##T(Z)  \
157
-                          || AXIS_HAS_##T(X2) || AXIS_HAS_##T(Y2) || AXIS_HAS_##T(Z2) \
158
-                          || AXIS_HAS_##T(Z3) || AXIS_HAS_##T(Z4) || E_AXIS_HAS(T) )
160
+#define ANY_AXIS_HAS(T) (    AXIS_HAS_##T(X) || AXIS_HAS_##T(X2) \
161
+                          || AXIS_HAS_##T(Y) || AXIS_HAS_##T(Y2) \
162
+                          || AXIS_HAS_##T(Z) || AXIS_HAS_##T(Z2) || AXIS_HAS_##T(Z3) || AXIS_HAS_##T(Z4) \
163
+                          || AXIS_HAS_##T(I) || AXIS_HAS_##T(J)  || AXIS_HAS_##T(K) \
164
+                          || E_AXIS_HAS(T) )
159 165
 
160 166
 #if ANY_AXIS_HAS(STEALTHCHOP)
161 167
   #define HAS_STEALTHCHOP 1

+ 128
- 12
Marlin/src/core/language.h View File

@@ -266,18 +266,25 @@
266 266
 #define STR_X_MAX                           "x_max"
267 267
 #define STR_X2_MIN                          "x2_min"
268 268
 #define STR_X2_MAX                          "x2_max"
269
-#define STR_Y_MIN                           "y_min"
270
-#define STR_Y_MAX                           "y_max"
271
-#define STR_Y2_MIN                          "y2_min"
272
-#define STR_Y2_MAX                          "y2_max"
273
-#define STR_Z_MIN                           "z_min"
274
-#define STR_Z_MAX                           "z_max"
275
-#define STR_Z2_MIN                          "z2_min"
276
-#define STR_Z2_MAX                          "z2_max"
277
-#define STR_Z3_MIN                          "z3_min"
278
-#define STR_Z3_MAX                          "z3_max"
279
-#define STR_Z4_MIN                          "z4_min"
280
-#define STR_Z4_MAX                          "z4_max"
269
+
270
+#if HAS_Y_AXIS
271
+  #define STR_Y_MIN                         "y_min"
272
+  #define STR_Y_MAX                         "y_max"
273
+  #define STR_Y2_MIN                        "y2_min"
274
+  #define STR_Y2_MAX                        "y2_max"
275
+#endif
276
+
277
+#if HAS_Z_AXIS
278
+  #define STR_Z_MIN                         "z_min"
279
+  #define STR_Z_MAX                         "z_max"
280
+  #define STR_Z2_MIN                        "z2_min"
281
+  #define STR_Z2_MAX                        "z2_max"
282
+  #define STR_Z3_MIN                        "z3_min"
283
+  #define STR_Z3_MAX                        "z3_max"
284
+  #define STR_Z4_MIN                        "z4_min"
285
+  #define STR_Z4_MAX                        "z4_max"
286
+#endif
287
+
281 288
 #define STR_Z_PROBE                         "z_probe"
282 289
 #define STR_PROBE_EN                        "probe_en"
283 290
 #define STR_FILAMENT_RUNOUT_SENSOR          "filament"
@@ -286,6 +293,9 @@
286 293
 #define STR_X "X"
287 294
 #define STR_Y "Y"
288 295
 #define STR_Z "Z"
296
+#define STR_I AXIS4_STR
297
+#define STR_J AXIS5_STR
298
+#define STR_K AXIS6_STR
289 299
 #define STR_E "E"
290 300
 #if IS_KINEMATIC
291 301
   #define STR_A "A"
@@ -305,8 +315,114 @@
305 315
 #define LCD_STR_A STR_A
306 316
 #define LCD_STR_B STR_B
307 317
 #define LCD_STR_C STR_C
318
+#define LCD_STR_I STR_I
319
+#define LCD_STR_J STR_J
320
+#define LCD_STR_K STR_K
308 321
 #define LCD_STR_E STR_E
309 322
 
323
+// Extra Axis and Endstop Names
324
+#if LINEAR_AXES >= 4
325
+  #if AXIS4_NAME == 'A'
326
+    #define AXIS4_STR "A"
327
+    #define STR_I_MIN "a_min"
328
+    #define STR_I_MAX "a_max"
329
+  #elif AXIS4_NAME == 'B'
330
+    #define AXIS4_STR "B"
331
+    #define STR_I_MIN "b_min"
332
+    #define STR_I_MAX "b_max"
333
+  #elif AXIS4_NAME == 'C'
334
+    #define AXIS4_STR "C"
335
+    #define STR_I_MIN "c_min"
336
+    #define STR_I_MAX "c_max"
337
+  #elif AXIS4_NAME == 'U'
338
+    #define AXIS4_STR "U"
339
+    #define STR_I_MIN "u_min"
340
+    #define STR_I_MAX "u_max"
341
+  #elif AXIS4_NAME == 'V'
342
+    #define AXIS4_STR "V"
343
+    #define STR_I_MIN "v_min"
344
+    #define STR_I_MAX "v_max"
345
+  #elif AXIS4_NAME == 'W'
346
+    #define AXIS4_STR "W"
347
+    #define STR_I_MIN "w_min"
348
+    #define STR_I_MAX "w_max"
349
+  #else
350
+    #define AXIS4_STR "A"
351
+    #define STR_I_MIN "a_min"
352
+    #define STR_I_MAX "a_max"
353
+  #endif
354
+#else
355
+  #define AXIS4_STR   ""
356
+#endif
357
+
358
+#if LINEAR_AXES >= 5
359
+  #if AXIS5_NAME == 'A'
360
+    #define AXIS5_STR "A"
361
+    #define STR_J_MIN "a_min"
362
+    #define STR_J_MAX "a_max"
363
+  #elif AXIS5_NAME == 'B'
364
+    #define AXIS5_STR "B"
365
+    #define STR_J_MIN "b_min"
366
+    #define STR_J_MAX "b_max"
367
+  #elif AXIS5_NAME == 'C'
368
+    #define AXIS5_STR "C"
369
+    #define STR_J_MIN "c_min"
370
+    #define STR_J_MAX "c_max"
371
+  #elif AXIS5_NAME == 'U'
372
+    #define AXIS5_STR "U"
373
+    #define STR_J_MIN "u_min"
374
+    #define STR_J_MAX "u_max"
375
+  #elif AXIS5_NAME == 'V'
376
+    #define AXIS5_STR "V"
377
+    #define STR_J_MIN "v_min"
378
+    #define STR_J_MAX "v_max"
379
+  #elif AXIS5_NAME == 'W'
380
+    #define AXIS5_STR "W"
381
+    #define STR_J_MIN "w_min"
382
+    #define STR_J_MAX "w_max"
383
+  #else
384
+    #define AXIS5_STR "B"
385
+    #define STR_J_MIN "b_min"
386
+    #define STR_J_MAX "b_max"
387
+  #endif
388
+#else
389
+  #define AXIS5_STR   ""
390
+#endif
391
+
392
+#if LINEAR_AXES >= 6
393
+  #if AXIS6_NAME == 'A'
394
+    #define AXIS6_STR "A"
395
+    #define STR_K_MIN "a_min"
396
+    #define STR_K_MAX "a_max"
397
+  #elif AXIS6_NAME == 'B'
398
+    #define AXIS6_STR "B"
399
+    #define STR_K_MIN "b_min"
400
+    #define STR_K_MAX "b_max"
401
+  #elif AXIS6_NAME == 'C'
402
+    #define AXIS6_STR "C"
403
+    #define STR_K_MIN "c_min"
404
+    #define STR_K_MAX "c_max"
405
+  #elif AXIS6_NAME == 'U'
406
+    #define AXIS6_STR "U"
407
+    #define STR_K_MIN "u_min"
408
+    #define STR_K_MAX "u_max"
409
+  #elif AXIS6_NAME == 'V'
410
+    #define AXIS6_STR "V"
411
+    #define STR_K_MIN "v_min"
412
+    #define STR_K_MAX "v_max"
413
+  #elif AXIS6_NAME == 'W'
414
+    #define AXIS6_STR "W"
415
+    #define STR_K_MIN "w_min"
416
+    #define STR_K_MAX "w_max"
417
+  #else
418
+    #define AXIS6_STR "C"
419
+    #define STR_K_MIN "c_min"
420
+    #define STR_K_MAX "c_max"
421
+  #endif
422
+#else
423
+  #define AXIS6_STR   ""
424
+#endif
425
+
310 426
 #if EITHER(HAS_MARLINUI_HD44780, IS_TFTGLCD_PANEL)
311 427
 
312 428
   // Custom characters defined in the first 8 characters of the LCD

+ 9
- 0
Marlin/src/core/macros.h View File

@@ -36,12 +36,21 @@
36 36
 #define _XMIN_   100
37 37
 #define _YMIN_   200
38 38
 #define _ZMIN_   300
39
+#define _IMIN_   400
40
+#define _JMIN_   500
41
+#define _KMIN_   600
39 42
 #define _XMAX_   101
40 43
 #define _YMAX_   201
41 44
 #define _ZMAX_   301
45
+#define _IMAX_   401
46
+#define _JMAX_   501
47
+#define _KMAX_   601
42 48
 #define _XDIAG_  102
43 49
 #define _YDIAG_  202
44 50
 #define _ZDIAG_  302
51
+#define _IDIAG_  502
52
+#define _JDIAG_  602
53
+#define _KDIAG_  702
45 54
 #define _E0DIAG_ 400
46 55
 #define _E1DIAG_ 401
47 56
 #define _E2DIAG_ 402

+ 8
- 5
Marlin/src/core/serial.cpp View File

@@ -36,6 +36,10 @@ PGMSTR(X_LBL,     "X:"); PGMSTR(Y_LBL,     "Y:"); PGMSTR(Z_LBL,     "Z:"); PGMST
36 36
 PGMSTR(SP_A_STR, " A");  PGMSTR(SP_B_STR, " B");  PGMSTR(SP_C_STR, " C");
37 37
 PGMSTR(SP_X_STR, " X");  PGMSTR(SP_Y_STR, " Y");  PGMSTR(SP_Z_STR, " Z");  PGMSTR(SP_E_STR, " E");
38 38
 PGMSTR(SP_X_LBL, " X:"); PGMSTR(SP_Y_LBL, " Y:"); PGMSTR(SP_Z_LBL, " Z:"); PGMSTR(SP_E_LBL, " E:");
39
+PGMSTR(I_STR, AXIS4_STR);     PGMSTR(J_STR, AXIS5_STR);     PGMSTR(K_STR, AXIS6_STR);
40
+PGMSTR(I_LBL, AXIS4_STR ":"); PGMSTR(J_LBL, AXIS5_STR ":"); PGMSTR(K_LBL, AXIS6_STR ":");
41
+PGMSTR(SP_I_STR, " " AXIS4_STR);     PGMSTR(SP_J_STR, " " AXIS5_STR);     PGMSTR(SP_K_STR, " " AXIS6_STR);
42
+PGMSTR(SP_I_LBL, " " AXIS4_STR ":"); PGMSTR(SP_J_LBL, " " AXIS5_STR ":"); PGMSTR(SP_K_LBL, " " AXIS6_STR ":");
39 43
 
40 44
 // Hook Meatpack if it's enabled on the first leaf
41 45
 #if ENABLED(MEATPACK_ON_SERIAL_PORT_1)
@@ -101,11 +105,10 @@ void print_bin(uint16_t val) {
101 105
   }
102 106
 }
103 107
 
104
-void print_pos(
105
-  LINEAR_AXIS_LIST(const_float_t x, const_float_t y, const_float_t z)
106
-  , PGM_P const prefix/*=nullptr*/, PGM_P const suffix/*=nullptr*/
107
-) {
108
+void print_pos(LINEAR_AXIS_ARGS(const_float_t), PGM_P const prefix/*=nullptr*/, PGM_P const suffix/*=nullptr*/) {
108 109
   if (prefix) serialprintPGM(prefix);
109
-  SERIAL_ECHOPAIR_P(LIST_N(DOUBLE(LINEAR_AXES), SP_X_STR, x, SP_Y_STR, y, SP_Z_STR, z));
110
+  SERIAL_ECHOPAIR_P(
111
+    LIST_N(DOUBLE(LINEAR_AXES), SP_X_STR, x, SP_Y_STR, y, SP_Z_STR, z, SP_I_STR, i, SP_J_STR, j, SP_K_STR, k)
112
+  );
110 113
   if (suffix) serialprintPGM(suffix); else SERIAL_EOL();
111 114
 }

+ 10
- 9
Marlin/src/core/serial.h View File

@@ -29,12 +29,16 @@
29 29
 #endif
30 30
 
31 31
 // Commonly-used strings in serial output
32
-extern const char NUL_STR[], SP_P_STR[], SP_T_STR[],
32
+extern const char NUL_STR[],
33
+                  SP_X_STR[], SP_Y_STR[], SP_Z_STR[],
34
+                  SP_A_STR[], SP_B_STR[], SP_C_STR[], SP_E_STR[],
35
+                  SP_X_LBL[], SP_Y_LBL[], SP_Z_LBL[], SP_E_LBL[],
36
+                  SP_I_STR[], SP_J_STR[], SP_K_STR[],
37
+                  SP_I_LBL[], SP_J_LBL[], SP_K_LBL[],
38
+                  SP_P_STR[], SP_T_STR[],
33 39
                   X_STR[], Y_STR[], Z_STR[], E_STR[],
34 40
                   X_LBL[], Y_LBL[], Z_LBL[], E_LBL[],
35
-                  SP_A_STR[], SP_B_STR[], SP_C_STR[],
36
-                  SP_X_STR[], SP_Y_STR[], SP_Z_STR[], SP_E_STR[],
37
-                  SP_X_LBL[], SP_Y_LBL[], SP_Z_LBL[], SP_E_LBL[];
41
+                  I_LBL[], J_LBL[], K_LBL[];
38 42
 
39 43
 //
40 44
 // Debugging flags for use by M111
@@ -310,13 +314,10 @@ void serialprint_truefalse(const bool tf);
310 314
 void serial_spaces(uint8_t count);
311 315
 
312 316
 void print_bin(const uint16_t val);
313
-void print_pos(
314
-  LINEAR_AXIS_LIST(const_float_t x, const_float_t y, const_float_t z),
315
-  PGM_P const prefix=nullptr, PGM_P const suffix=nullptr
316
-);
317
+void print_pos(LINEAR_AXIS_ARGS(const_float_t), PGM_P const prefix=nullptr, PGM_P const suffix=nullptr);
317 318
 
318 319
 inline void print_pos(const xyz_pos_t &xyz, PGM_P const prefix=nullptr, PGM_P const suffix=nullptr) {
319
-  print_pos(LINEAR_AXIS_LIST(xyz.x, xyz.y, xyz.z), prefix, suffix);
320
+  print_pos(LINEAR_AXIS_ELEM(xyz), prefix, suffix);
320 321
 }
321 322
 
322 323
 #define SERIAL_POS(SUFFIX,VAR) do { print_pos(VAR, PSTR("  " STRINGIFY(VAR) "="), PSTR(" : " SUFFIX "\n")); }while(0)

+ 285
- 192
Marlin/src/core/types.h View File

@@ -43,11 +43,17 @@ struct IF<true, L, R> { typedef L type; };
43 43
 #define LINEAR_AXIS_CODE(V...) CODE_N(LINEAR_AXES, V)
44 44
 #define LINEAR_AXIS_LIST(V...) LIST_N(LINEAR_AXES, V)
45 45
 #define LINEAR_AXIS_ARRAY(V...) { LINEAR_AXIS_LIST(V) }
46
+#define LINEAR_AXIS_ARGS(T...) LINEAR_AXIS_LIST(T x, T y, T z, T i, T j, T k)
47
+#define LINEAR_AXIS_ELEM(O)    LINEAR_AXIS_LIST(O.x, O.y, O.z, O.i, O.j, O.k)
48
+#define LINEAR_AXIS_DEFS(T,V)  LINEAR_AXIS_LIST(T x=V, T y=V, T z=V, T i=V, T j=V, T k=V)
46 49
 
47 50
 #define LOGICAL_AXIS_GANG(E,V...) LINEAR_AXIS_GANG(V) GANG_ITEM_E(E)
48 51
 #define LOGICAL_AXIS_CODE(E,V...) LINEAR_AXIS_CODE(V) CODE_ITEM_E(E)
49 52
 #define LOGICAL_AXIS_LIST(E,V...) LINEAR_AXIS_LIST(V) LIST_ITEM_E(E)
50 53
 #define LOGICAL_AXIS_ARRAY(E,V...) { LOGICAL_AXIS_LIST(E,V) }
54
+#define LOGICAL_AXIS_ARGS(T...) LOGICAL_AXIS_LIST(T e, T x, T y, T z, T i, T j, T k)
55
+#define LOGICAL_AXIS_ELEM(O)    LOGICAL_AXIS_LIST(O.e, O.x, O.y, O.z, O.i, O.j, O.k)
56
+#define LOGICAL_AXIS_DECL(T,V)  LOGICAL_AXIS_LIST(T e=V, T x=V, T y=V, T z=V, T i=V, T j=V, T k=V)
51 57
 
52 58
 #if HAS_EXTRUDERS
53 59
   #define LIST_ITEM_E(N) , N
@@ -69,37 +75,37 @@ struct IF<true, L, R> { typedef L type; };
69 75
 enum AxisEnum : uint8_t {
70 76
 
71 77
   // Linear axes may be controlled directly or indirectly
72
-  LINEAR_AXIS_LIST(X_AXIS, Y_AXIS, Z_AXIS),
78
+  LINEAR_AXIS_LIST(X_AXIS, Y_AXIS, Z_AXIS, I_AXIS, J_AXIS, K_AXIS)
73 79
 
74 80
   // Extruder axes may be considered distinctly
75
-  #define _EN_ITEM(N) E##N##_AXIS,
81
+  #define _EN_ITEM(N) , E##N##_AXIS
76 82
   REPEAT(EXTRUDERS, _EN_ITEM)
77 83
   #undef _EN_ITEM
78 84
 
79 85
   // Core also keeps toolhead directions
80 86
   #if IS_CORE
81
-    X_HEAD, Y_HEAD, Z_HEAD,
87
+    , X_HEAD, Y_HEAD, Z_HEAD
82 88
   #endif
83 89
 
84 90
   // Distinct axes, including all E and Core
85
-  NUM_AXIS_ENUMS,
91
+  , NUM_AXIS_ENUMS
86 92
 
87 93
   // Most of the time we refer only to the single E_AXIS
88 94
   #if HAS_EXTRUDERS
89
-    E_AXIS = E0_AXIS,
95
+    , E_AXIS = E0_AXIS
90 96
   #endif
91 97
 
92 98
   // A, B, and C are for DELTA, SCARA, etc.
93
-  A_AXIS = X_AXIS,
99
+  , A_AXIS = X_AXIS
94 100
   #if LINEAR_AXES >= 2
95
-    B_AXIS = Y_AXIS,
101
+    , B_AXIS = Y_AXIS
96 102
   #endif
97 103
   #if LINEAR_AXES >= 3
98
-    C_AXIS = Z_AXIS,
104
+    , C_AXIS = Z_AXIS
99 105
   #endif
100 106
 
101 107
   // To refer to all or none
102
-  ALL_AXES_ENUM = 0xFE, NO_AXIS_ENUM = 0xFF
108
+  , ALL_AXES_ENUM = 0xFE, NO_AXIS_ENUM = 0xFF
103 109
 };
104 110
 
105 111
 typedef IF<(NUM_AXIS_ENUMS > 8), uint16_t, uint8_t>::type axis_bits_t;
@@ -241,9 +247,16 @@ struct XYval {
241 247
     struct { T a, b; };
242 248
     T pos[2];
243 249
   };
250
+
251
+  // Set all to 0
252
+  FI void reset()                                       { x = y = 0; }
253
+
254
+  // Setters taking struct types and arrays
244 255
   FI void set(const T px)                               { x = px; }
245
-  FI void set(const T px, const T py)                   { x = px; y = py; }
246
-  FI void set(const T (&arr)[XY])                       { x = arr[0]; y = arr[1]; }
256
+  #if HAS_Y_AXIS
257
+    FI void set(const T px, const T py)                 { x = px; y = py; }
258
+    FI void set(const T (&arr)[XY])                     { x = arr[0]; y = arr[1]; }
259
+  #endif
247 260
   #if LINEAR_AXES > XY
248 261
     FI void set(const T (&arr)[LINEAR_AXES])            { x = arr[0]; y = arr[1]; }
249 262
   #endif
@@ -253,10 +266,15 @@ struct XYval {
253 266
       FI void set(const T (&arr)[DISTINCT_AXES])        { x = arr[0]; y = arr[1]; }
254 267
     #endif
255 268
   #endif
256
-  FI void reset()                                       { x = y = 0; }
269
+
270
+  // Length reduced to one dimension
257 271
   FI T magnitude()                                const { return (T)sqrtf(x*x + y*y); }
272
+  // Pointer to the data as a simple array
258 273
   FI operator T* ()                                     { return pos; }
274
+  // If any element is true then it's true
259 275
   FI operator bool()                                    { return x || y; }
276
+
277
+  // Explicit copy and copies with conversion
260 278
   FI XYval<T>           copy()                    const { return *this; }
261 279
   FI XYval<T>            ABS()                    const { return { T(_ABS(x)), T(_ABS(y)) }; }
262 280
   FI XYval<int16_t>    asInt()                          { return { int16_t(x), int16_t(y) }; }
@@ -268,17 +286,27 @@ struct XYval {
268 286
   FI XYval<float>    asFloat()                          { return { static_cast<float>(x), static_cast<float>(y) }; }
269 287
   FI XYval<float>    asFloat()                    const { return { static_cast<float>(x), static_cast<float>(y) }; }
270 288
   FI XYval<float> reciprocal()                    const { return {  _RECIP(x),  _RECIP(y) }; }
289
+
290
+  // Marlin workspace shifting is done with G92 and M206
271 291
   FI XYval<float>  asLogical()                    const { XYval<float> o = asFloat(); toLogical(o); return o; }
272 292
   FI XYval<float>   asNative()                    const { XYval<float> o = asFloat(); toNative(o);  return o; }
293
+
294
+  // Cast to a type with more fields by making a new object
273 295
   FI operator XYZval<T>()                               { return { x, y }; }
274 296
   FI operator XYZval<T>()                         const { return { x, y }; }
275 297
   FI operator XYZEval<T>()                              { return { x, y }; }
276 298
   FI operator XYZEval<T>()                        const { return { x, y }; }
299
+
300
+  // Accessor via an AxisEnum (or any integer) [index]
277 301
   FI       T&  operator[](const int n)                  { return pos[n]; }
278 302
   FI const T&  operator[](const int n)            const { return pos[n]; }
303
+
304
+  // Assignment operator overrides do the expected thing
279 305
   FI XYval<T>& operator= (const T v)                    { set(v,    v   ); return *this; }
280 306
   FI XYval<T>& operator= (const XYZval<T>  &rs)         { set(rs.x, rs.y); return *this; }
281 307
   FI XYval<T>& operator= (const XYZEval<T> &rs)         { set(rs.x, rs.y); return *this; }
308
+
309
+  // Override other operators to get intuitive behaviors
282 310
   FI XYval<T>  operator+ (const XYval<T>   &rs)   const { XYval<T> ls = *this; ls.x += rs.x; ls.y += rs.y; return ls; }
283 311
   FI XYval<T>  operator+ (const XYval<T>   &rs)         { XYval<T> ls = *this; ls.x += rs.x; ls.y += rs.y; return ls; }
284 312
   FI XYval<T>  operator- (const XYval<T>   &rs)   const { XYval<T> ls = *this; ls.x -= rs.x; ls.y -= rs.y; return ls; }
@@ -315,6 +343,10 @@ struct XYval {
315 343
   FI XYval<T>  operator>>(const int &v)                 { XYval<T> ls = *this; _RS(ls.x);    _RS(ls.y);    return ls; }
316 344
   FI XYval<T>  operator<<(const int &v)           const { XYval<T> ls = *this; _LS(ls.x);    _LS(ls.y);    return ls; }
317 345
   FI XYval<T>  operator<<(const int &v)                 { XYval<T> ls = *this; _LS(ls.x);    _LS(ls.y);    return ls; }
346
+  FI const XYval<T> operator-()                   const { XYval<T> o = *this; o.x = -x; o.y = -y; return o; }
347
+  FI XYval<T>       operator-()                         { XYval<T> o = *this; o.x = -x; o.y = -y; return o; }
348
+
349
+  // Modifier operators
318 350
   FI XYval<T>& operator+=(const XYval<T>   &rs)         { x += rs.x; y += rs.y; return *this; }
319 351
   FI XYval<T>& operator-=(const XYval<T>   &rs)         { x -= rs.x; y -= rs.y; return *this; }
320 352
   FI XYval<T>& operator*=(const XYval<T>   &rs)         { x *= rs.x; y *= rs.y; return *this; }
@@ -328,6 +360,8 @@ struct XYval {
328 360
   FI XYval<T>& operator*=(const int &v)                 { x *= v;    y *= v;    return *this; }
329 361
   FI XYval<T>& operator>>=(const int &v)                { _RS(x);    _RS(y);    return *this; }
330 362
   FI XYval<T>& operator<<=(const int &v)                { _LS(x);    _LS(y);    return *this; }
363
+
364
+  // Exact comparisons. For floats a "NEAR" operation may be better.
331 365
   FI bool      operator==(const XYval<T>   &rs)         { return x == rs.x && y == rs.y; }
332 366
   FI bool      operator==(const XYZval<T>  &rs)         { return x == rs.x && y == rs.y; }
333 367
   FI bool      operator==(const XYZEval<T> &rs)         { return x == rs.x && y == rs.y; }
@@ -340,8 +374,6 @@ struct XYval {
340 374
   FI bool      operator!=(const XYval<T>   &rs)   const { return !operator==(rs); }
341 375
   FI bool      operator!=(const XYZval<T>  &rs)   const { return !operator==(rs); }
342 376
   FI bool      operator!=(const XYZEval<T> &rs)   const { return !operator==(rs); }
343
-  FI XYval<T>       operator-()                         { XYval<T> o = *this; o.x = -x; o.y = -y; return o; }
344
-  FI const XYval<T> operator-()                   const { XYval<T> o = *this; o.x = -x; o.y = -y; return o; }
345 377
 };
346 378
 
347 379
 //
@@ -350,111 +382,144 @@ struct XYval {
350 382
 template<typename T>
351 383
 struct XYZval {
352 384
   union {
353
-    struct { T LINEAR_AXIS_LIST(x, y, z); };
354
-    struct { T LINEAR_AXIS_LIST(a, b, c); };
385
+    struct { T LINEAR_AXIS_ARGS(); };
386
+    struct { T LINEAR_AXIS_LIST(a, b, c, u, v, w); };
355 387
     T pos[LINEAR_AXES];
356 388
   };
389
+
390
+  // Set all to 0
391
+  FI void reset()                                      { LINEAR_AXIS_GANG(x =, y =, z =, i =, j =, k =) 0; }
392
+
393
+  // Setters taking struct types and arrays
357 394
   FI void set(const T px)                              { x = px; }
358 395
   FI void set(const T px, const T py)                  { x = px; y = py; }
359 396
   FI void set(const XYval<T> pxy)                      { x = pxy.x; y = pxy.y; }
360
-  FI void set(const XYval<T> pxy, const T pz)          { x = pxy.x; y = pxy.y; z = pz; }
397
+  FI void set(const XYval<T> pxy, const T pz)          { LINEAR_AXIS_CODE(x = pxy.x, y = pxy.y, z = pz, NOOP, NOOP, NOOP); }
361 398
   FI void set(const T (&arr)[XY])                      { x = arr[0]; y = arr[1]; }
362
-  FI void set(const T (&arr)[LINEAR_AXES])             { LINEAR_AXIS_CODE(x = arr[0], y = arr[1], z = arr[2]); }
363 399
   #if HAS_Z_AXIS
364
-    FI void set(LINEAR_AXIS_LIST(const T px, const T py, const T pz))
365
-                                                       { LINEAR_AXIS_CODE(x = px, y = py, z = pz); }
400
+    FI void set(const T (&arr)[LINEAR_AXES])           { LINEAR_AXIS_CODE(x = arr[0], y = arr[1], z = arr[2], i = arr[3], j = arr[4], k = arr[5]); }
401
+    FI void set(LINEAR_AXIS_ARGS(const T))             { LINEAR_AXIS_CODE(a = x,      b = y,      c = z,      u = i,      v = j,      w = k    ); }
366 402
   #endif
367 403
   #if LOGICAL_AXES > LINEAR_AXES
368
-    FI void set(const T (&arr)[LOGICAL_AXES])          { LINEAR_AXIS_CODE(x = arr[0], y = arr[1], z = arr[2]); }
369
-    FI void set(LOGICAL_AXIS_LIST(const T, const T px, const T py, const T pz))
370
-                                                       { LINEAR_AXIS_CODE(x = px, y = py, z = pz); }
404
+    FI void set(const T (&arr)[LOGICAL_AXES])          { LINEAR_AXIS_CODE(x = arr[0], y = arr[1], z = arr[2], i = arr[3], j = arr[4], k = arr[5]); }
405
+    FI void set(LOGICAL_AXIS_ARGS(const T))            { LINEAR_AXIS_CODE(a = x,      b = y,      c = z,      u = i,      v = j,      w = k    ); }
371 406
     #if DISTINCT_AXES > LOGICAL_AXES
372
-      FI void set(const T (&arr)[DISTINCT_AXES])       { LINEAR_AXIS_CODE(x = arr[0], y = arr[1], z = arr[2]); }
407
+      FI void set(const T (&arr)[DISTINCT_AXES])       { LINEAR_AXIS_CODE(x = arr[0], y = arr[1], z = arr[2], i = arr[3], j = arr[4], k = arr[5]); }
373 408
     #endif
374 409
   #endif
375
-  FI void reset()                                      { LINEAR_AXIS_GANG(x =, y =, z =) 0; }
376
-  FI T magnitude()                               const { return (T)sqrtf(LINEAR_AXIS_GANG(x*x, + y*y, + z*z)); }
410
+  #if LINEAR_AXES >= 4
411
+    FI void set(const T px, const T py, const T pz)                         { x = px; y = py; z = pz; }
412
+  #endif
413
+  #if LINEAR_AXES >= 5
414
+    FI void set(const T px, const T py, const T pz, const T pi)             { x = px; y = py; z = pz; i = pi; }
415
+  #endif
416
+  #if LINEAR_AXES >= 6
417
+    FI void set(const T px, const T py, const T pz, const T pi, const T pj) { x = px; y = py; z = pz; i = pi; j = pj; }
418
+  #endif
419
+
420
+  // Length reduced to one dimension
421
+  FI T magnitude()                               const { return (T)sqrtf(LINEAR_AXIS_GANG(x*x, + y*y, + z*z, + i*i, + j*j, + k*k)); }
422
+  // Pointer to the data as a simple array
377 423
   FI operator T* ()                                    { return pos; }
378
-  FI operator bool()                                   { return LINEAR_AXIS_GANG(z, || x, || y); }
424
+  // If any element is true then it's true
425
+  FI operator bool()                                   { return LINEAR_AXIS_GANG(x, || y, || z, || i, || j, || k); }
426
+
427
+  // Explicit copy and copies with conversion
379 428
   FI XYZval<T>          copy()                   const { XYZval<T> o = *this; return o; }
380
-  FI XYZval<T>           ABS()                   const { return LINEAR_AXIS_ARRAY(T(_ABS(x)), T(_ABS(y)), T(_ABS(z))); }
381
-  FI XYZval<int16_t>   asInt()                         { return LINEAR_AXIS_ARRAY(int16_t(x), int16_t(y), int16_t(z)); }
382
-  FI XYZval<int16_t>   asInt()                   const { return LINEAR_AXIS_ARRAY(int16_t(x), int16_t(y), int16_t(z)); }
383
-  FI XYZval<int32_t>  asLong()                         { return LINEAR_AXIS_ARRAY(int32_t(x), int32_t(y), int32_t(z)); }
384
-  FI XYZval<int32_t>  asLong()                   const { return LINEAR_AXIS_ARRAY(int32_t(x), int32_t(y), int32_t(z)); }
385
-  FI XYZval<int32_t>  ROUNDL()                         { return LINEAR_AXIS_ARRAY(int32_t(LROUND(x)), int32_t(LROUND(y)), int32_t(LROUND(z))); }
386
-  FI XYZval<int32_t>  ROUNDL()                   const { return LINEAR_AXIS_ARRAY(int32_t(LROUND(x)), int32_t(LROUND(y)), int32_t(LROUND(z))); }
387
-  FI XYZval<float>   asFloat()                         { return LINEAR_AXIS_ARRAY(static_cast<float>(x), static_cast<float>(y), static_cast<float>(z)); }
388
-  FI XYZval<float>   asFloat()                   const { return LINEAR_AXIS_ARRAY(static_cast<float>(x), static_cast<float>(y), static_cast<float>(z)); }
389
-  FI XYZval<float> reciprocal()                  const { return LINEAR_AXIS_ARRAY(_RECIP(x),  _RECIP(y),  _RECIP(z)); }
429
+  FI XYZval<T>           ABS()                   const { return LINEAR_AXIS_ARRAY(T(_ABS(x)), T(_ABS(y)), T(_ABS(z)), T(_ABS(i)), T(_ABS(j)), T(_ABS(k))); }
430
+  FI XYZval<int16_t>   asInt()                         { return LINEAR_AXIS_ARRAY(int16_t(x), int16_t(y), int16_t(z), int16_t(i), int16_t(j), int16_t(k)); }
431
+  FI XYZval<int16_t>   asInt()                   const { return LINEAR_AXIS_ARRAY(int16_t(x), int16_t(y), int16_t(z), int16_t(i), int16_t(j), int16_t(k)); }
432
+  FI XYZval<int32_t>  asLong()                         { return LINEAR_AXIS_ARRAY(int32_t(x), int32_t(y), int32_t(z), int32_t(i), int32_t(j), int32_t(k)); }
433
+  FI XYZval<int32_t>  asLong()                   const { return LINEAR_AXIS_ARRAY(int32_t(x), int32_t(y), int32_t(z), int32_t(i), int32_t(j), int32_t(k)); }
434
+  FI XYZval<int32_t>  ROUNDL()                         { return LINEAR_AXIS_ARRAY(int32_t(LROUND(x)), int32_t(LROUND(y)), int32_t(LROUND(z)), int32_t(LROUND(i)), int32_t(LROUND(j)), int32_t(LROUND(k))); }
435
+  FI XYZval<int32_t>  ROUNDL()                   const { return LINEAR_AXIS_ARRAY(int32_t(LROUND(x)), int32_t(LROUND(y)), int32_t(LROUND(z)), int32_t(LROUND(i)), int32_t(LROUND(j)), int32_t(LROUND(k))); }
436
+  FI XYZval<float>   asFloat()                         { return LINEAR_AXIS_ARRAY(static_cast<float>(x), static_cast<float>(y), static_cast<float>(z), static_cast<float>(i), static_cast<float>(j), static_cast<float>(k)); }
437
+  FI XYZval<float>   asFloat()                   const { return LINEAR_AXIS_ARRAY(static_cast<float>(x), static_cast<float>(y), static_cast<float>(z), static_cast<float>(i), static_cast<float>(j), static_cast<float>(k)); }
438
+  FI XYZval<float> reciprocal()                  const { return LINEAR_AXIS_ARRAY(_RECIP(x),  _RECIP(y),  _RECIP(z),  _RECIP(i),  _RECIP(j),  _RECIP(k)); }
439
+
440
+  // Marlin workspace shifting is done with G92 and M206
390 441
   FI XYZval<float> asLogical()                   const { XYZval<float> o = asFloat(); toLogical(o); return o; }
391 442
   FI XYZval<float>  asNative()                   const { XYZval<float> o = asFloat(); toNative(o);  return o; }
443
+
444
+  // In-place cast to types having fewer fields
392 445
   FI operator       XYval<T>&()                        { return *(XYval<T>*)this; }
393 446
   FI operator const XYval<T>&()                  const { return *(const XYval<T>*)this; }
394
-  FI operator       XYZEval<T>()                 const { return LINEAR_AXIS_ARRAY(x, y, z); }
447
+
448
+  // Cast to a type with more fields by making a new object
449
+  FI operator       XYZEval<T>()                 const { return LINEAR_AXIS_ARRAY(x, y, z, i, j, k); }
450
+
451
+  // Accessor via an AxisEnum (or any integer) [index]
395 452
   FI       T&   operator[](const int n)                { return pos[n]; }
396 453
   FI const T&   operator[](const int n)          const { return pos[n]; }
454
+
455
+  // Assignment operator overrides do the expected thing
397 456
   FI XYZval<T>& operator= (const T v)                  { set(ARRAY_N_1(LINEAR_AXES, v)); return *this; }
398 457
   FI XYZval<T>& operator= (const XYval<T>   &rs)       { set(rs.x, rs.y      ); return *this; }
399
-  FI XYZval<T>& operator= (const XYZEval<T> &rs)       { set(LINEAR_AXIS_LIST(rs.x, rs.y, rs.z)); return *this; }
400
-  FI XYZval<T>  operator+ (const XYval<T>   &rs) const { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x += rs.x, ls.y += rs.y, NOOP        ); return ls; }
401
-  FI XYZval<T>  operator+ (const XYval<T>   &rs)       { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x += rs.x, ls.y += rs.y, NOOP        ); return ls; }
402
-  FI XYZval<T>  operator- (const XYval<T>   &rs) const { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x -= rs.x, ls.y -= rs.y, NOOP        ); return ls; }
403
-  FI XYZval<T>  operator- (const XYval<T>   &rs)       { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x -= rs.x, ls.y -= rs.y, NOOP        ); return ls; }
404
-  FI XYZval<T>  operator* (const XYval<T>   &rs) const { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x *= rs.x, ls.y *= rs.y, NOOP        ); return ls; }
405
-  FI XYZval<T>  operator* (const XYval<T>   &rs)       { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x *= rs.x, ls.y *= rs.y, NOOP        ); return ls; }
406
-  FI XYZval<T>  operator/ (const XYval<T>   &rs) const { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x /= rs.x, ls.y /= rs.y, NOOP        ); return ls; }
407
-  FI XYZval<T>  operator/ (const XYval<T>   &rs)       { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x /= rs.x, ls.y /= rs.y, NOOP        ); return ls; }
408
-  FI XYZval<T>  operator+ (const XYZval<T>  &rs) const { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x += rs.x, ls.y += rs.y, ls.z += rs.z); return ls; }
409
-  FI XYZval<T>  operator+ (const XYZval<T>  &rs)       { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x += rs.x, ls.y += rs.y, ls.z += rs.z); return ls; }
410
-  FI XYZval<T>  operator- (const XYZval<T>  &rs) const { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x -= rs.x, ls.y -= rs.y, ls.z -= rs.z); return ls; }
411
-  FI XYZval<T>  operator- (const XYZval<T>  &rs)       { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x -= rs.x, ls.y -= rs.y, ls.z -= rs.z); return ls; }
412
-  FI XYZval<T>  operator* (const XYZval<T>  &rs) const { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x *= rs.x, ls.y *= rs.y, ls.z *= rs.z); return ls; }
413
-  FI XYZval<T>  operator* (const XYZval<T>  &rs)       { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x *= rs.x, ls.y *= rs.y, ls.z *= rs.z); return ls; }
414
-  FI XYZval<T>  operator/ (const XYZval<T>  &rs) const { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x /= rs.x, ls.y /= rs.y, ls.z /= rs.z); return ls; }
415
-  FI XYZval<T>  operator/ (const XYZval<T>  &rs)       { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x /= rs.x, ls.y /= rs.y, ls.z /= rs.z); return ls; }
416
-  FI XYZval<T>  operator+ (const XYZEval<T> &rs) const { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x += rs.x, ls.y += rs.y, ls.z += rs.z); return ls; }
417
-  FI XYZval<T>  operator+ (const XYZEval<T> &rs)       { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x += rs.x, ls.y += rs.y, ls.z += rs.z); return ls; }
418
-  FI XYZval<T>  operator- (const XYZEval<T> &rs) const { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x -= rs.x, ls.y -= rs.y, ls.z -= rs.z); return ls; }
419
-  FI XYZval<T>  operator- (const XYZEval<T> &rs)       { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x -= rs.x, ls.y -= rs.y, ls.z -= rs.z); return ls; }
420
-  FI XYZval<T>  operator* (const XYZEval<T> &rs) const { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x *= rs.x, ls.y *= rs.y, ls.z *= rs.z); return ls; }
421
-  FI XYZval<T>  operator* (const XYZEval<T> &rs)       { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x *= rs.x, ls.y *= rs.y, ls.z *= rs.z); return ls; }
422
-  FI XYZval<T>  operator/ (const XYZEval<T> &rs) const { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x /= rs.x, ls.y /= rs.y, ls.z /= rs.z); return ls; }
423
-  FI XYZval<T>  operator/ (const XYZEval<T> &rs)       { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x /= rs.x, ls.y /= rs.y, ls.z /= rs.z); return ls; }
424
-  FI XYZval<T>  operator* (const float &v)       const { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x *= v,    ls.y *= v,    ls.z *= v   ); return ls; }
425
-  FI XYZval<T>  operator* (const float &v)             { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x *= v,    ls.y *= v,    ls.z *= v   ); return ls; }
426
-  FI XYZval<T>  operator* (const int &v)         const { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x *= v,    ls.y *= v,    ls.z *= v   ); return ls; }
427
-  FI XYZval<T>  operator* (const int &v)               { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x *= v,    ls.y *= v,    ls.z *= v   ); return ls; }
428
-  FI XYZval<T>  operator/ (const float &v)       const { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x /= v,    ls.y /= v,    ls.z /= v   ); return ls; }
429
-  FI XYZval<T>  operator/ (const float &v)             { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x /= v,    ls.y /= v,    ls.z /= v   ); return ls; }
430
-  FI XYZval<T>  operator/ (const int &v)         const { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x /= v,    ls.y /= v,    ls.z /= v   ); return ls; }
431
-  FI XYZval<T>  operator/ (const int &v)               { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x /= v,    ls.y /= v,    ls.z /= v   ); return ls; }
432
-  FI XYZval<T>  operator>>(const int &v)         const { XYZval<T> ls = *this; LINEAR_AXIS_CODE(_RS(ls.x),    _RS(ls.y),    _RS(ls.z)   ); return ls; }
433
-  FI XYZval<T>  operator>>(const int &v)               { XYZval<T> ls = *this; LINEAR_AXIS_CODE(_RS(ls.x),    _RS(ls.y),    _RS(ls.z)   ); return ls; }
434
-  FI XYZval<T>  operator<<(const int &v)         const { XYZval<T> ls = *this; LINEAR_AXIS_CODE(_LS(ls.x),    _LS(ls.y),    _LS(ls.z)   ); return ls; }
435
-  FI XYZval<T>  operator<<(const int &v)               { XYZval<T> ls = *this; LINEAR_AXIS_CODE(_LS(ls.x),    _LS(ls.y),    _LS(ls.z)   ); return ls; }
436
-  FI XYZval<T>& operator+=(const XYval<T>   &rs)       { LINEAR_AXIS_CODE(x += rs.x, y += rs.y, NOOP      ); return *this; }
437
-  FI XYZval<T>& operator-=(const XYval<T>   &rs)       { LINEAR_AXIS_CODE(x -= rs.x, y -= rs.y, NOOP      ); return *this; }
438
-  FI XYZval<T>& operator*=(const XYval<T>   &rs)       { LINEAR_AXIS_CODE(x *= rs.x, y *= rs.y, NOOP      ); return *this; }
439
-  FI XYZval<T>& operator/=(const XYval<T>   &rs)       { LINEAR_AXIS_CODE(x /= rs.x, y /= rs.y, NOOP      ); return *this; }
440
-  FI XYZval<T>& operator+=(const XYZval<T>  &rs)       { LINEAR_AXIS_CODE(x += rs.x, y += rs.y, z += rs.z ); return *this; }
441
-  FI XYZval<T>& operator-=(const XYZval<T>  &rs)       { LINEAR_AXIS_CODE(x -= rs.x, y -= rs.y, z -= rs.z ); return *this; }
442
-  FI XYZval<T>& operator*=(const XYZval<T>  &rs)       { LINEAR_AXIS_CODE(x *= rs.x, y *= rs.y, z *= rs.z ); return *this; }
443
-  FI XYZval<T>& operator/=(const XYZval<T>  &rs)       { LINEAR_AXIS_CODE(x /= rs.x, y /= rs.y, z /= rs.z ); return *this; }
444
-  FI XYZval<T>& operator+=(const XYZEval<T> &rs)       { LINEAR_AXIS_CODE(x += rs.x, y += rs.y, z += rs.z ); return *this; }
445
-  FI XYZval<T>& operator-=(const XYZEval<T> &rs)       { LINEAR_AXIS_CODE(x -= rs.x, y -= rs.y, z -= rs.z ); return *this; }
446
-  FI XYZval<T>& operator*=(const XYZEval<T> &rs)       { LINEAR_AXIS_CODE(x *= rs.x, y *= rs.y, z *= rs.z ); return *this; }
447
-  FI XYZval<T>& operator/=(const XYZEval<T> &rs)       { LINEAR_AXIS_CODE(x /= rs.x, y /= rs.y, z /= rs.z ); return *this; }
448
-  FI XYZval<T>& operator*=(const float &v)             { LINEAR_AXIS_CODE(x *= v,    y *= v,    z *= v    ); return *this; }
449
-  FI XYZval<T>& operator*=(const int &v)               { LINEAR_AXIS_CODE(x *= v,    y *= v,    z *= v    ); return *this; }
450
-  FI XYZval<T>& operator>>=(const int &v)              { LINEAR_AXIS_CODE(_RS(x),    _RS(y),    _RS(z)    ); return *this; }
451
-  FI XYZval<T>& operator<<=(const int &v)              { LINEAR_AXIS_CODE(_LS(x),    _LS(y),    _LS(z)    ); return *this; }
452
-  FI bool       operator==(const XYZEval<T> &rs)       { return true LINEAR_AXIS_GANG(&& x == rs.x, && y == rs.y, && z == rs.z); }
453
-  FI bool       operator==(const XYZEval<T> &rs) const { return true LINEAR_AXIS_GANG(&& x == rs.x, && y == rs.y, && z == rs.z); }
458
+  FI XYZval<T>& operator= (const XYZEval<T> &rs)       { set(LINEAR_AXIS_ELEM(rs)); return *this; }
459
+
460
+  // Override other operators to get intuitive behaviors
461
+  FI XYZval<T>  operator+ (const XYval<T>   &rs) const { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x += rs.x, ls.y += rs.y, NOOP        , NOOP        , NOOP        , NOOP        ); return ls; }
462
+  FI XYZval<T>  operator+ (const XYval<T>   &rs)       { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x += rs.x, ls.y += rs.y, NOOP        , NOOP        , NOOP        , NOOP        ); return ls; }
463
+  FI XYZval<T>  operator- (const XYval<T>   &rs) const { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x -= rs.x, ls.y -= rs.y, NOOP        , NOOP        , NOOP        , NOOP        ); return ls; }
464
+  FI XYZval<T>  operator- (const XYval<T>   &rs)       { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x -= rs.x, ls.y -= rs.y, NOOP        , NOOP        , NOOP        , NOOP        ); return ls; }
465
+  FI XYZval<T>  operator* (const XYval<T>   &rs) const { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x *= rs.x, ls.y *= rs.y, NOOP        , NOOP        , NOOP        , NOOP        ); return ls; }
466
+  FI XYZval<T>  operator* (const XYval<T>   &rs)       { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x *= rs.x, ls.y *= rs.y, NOOP        , NOOP        , NOOP        , NOOP        ); return ls; }
467
+  FI XYZval<T>  operator/ (const XYval<T>   &rs) const { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x /= rs.x, ls.y /= rs.y, NOOP        , NOOP        , NOOP        , NOOP        ); return ls; }
468
+  FI XYZval<T>  operator/ (const XYval<T>   &rs)       { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x /= rs.x, ls.y /= rs.y, NOOP        , NOOP        , NOOP        , NOOP        ); return ls; }
469
+  FI XYZval<T>  operator+ (const XYZval<T>  &rs) const { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x += rs.x, ls.y += rs.y, ls.z += rs.z, ls.i += rs.i, ls.j += rs.j, ls.k += rs.k); return ls; }
470
+  FI XYZval<T>  operator+ (const XYZval<T>  &rs)       { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x += rs.x, ls.y += rs.y, ls.z += rs.z, ls.i += rs.i, ls.j += rs.j, ls.k += rs.k); return ls; }
471
+  FI XYZval<T>  operator- (const XYZval<T>  &rs) const { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x -= rs.x, ls.y -= rs.y, ls.z -= rs.z, ls.i -= rs.i, ls.j -= rs.j, ls.k -= rs.k); return ls; }
472
+  FI XYZval<T>  operator- (const XYZval<T>  &rs)       { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x -= rs.x, ls.y -= rs.y, ls.z -= rs.z, ls.i -= rs.i, ls.j -= rs.j, ls.k -= rs.k); return ls; }
473
+  FI XYZval<T>  operator* (const XYZval<T>  &rs) const { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x *= rs.x, ls.y *= rs.y, ls.z *= rs.z, ls.i *= rs.i, ls.j *= rs.j, ls.k *= rs.k); return ls; }
474
+  FI XYZval<T>  operator* (const XYZval<T>  &rs)       { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x *= rs.x, ls.y *= rs.y, ls.z *= rs.z, ls.i *= rs.i, ls.j *= rs.j, ls.k *= rs.k); return ls; }
475
+  FI XYZval<T>  operator/ (const XYZval<T>  &rs) const { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x /= rs.x, ls.y /= rs.y, ls.z /= rs.z, ls.i /= rs.i, ls.j /= rs.j, ls.k /= rs.k); return ls; }
476
+  FI XYZval<T>  operator/ (const XYZval<T>  &rs)       { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x /= rs.x, ls.y /= rs.y, ls.z /= rs.z, ls.i /= rs.i, ls.j /= rs.j, ls.k /= rs.k); return ls; }
477
+  FI XYZval<T>  operator+ (const XYZEval<T> &rs) const { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x += rs.x, ls.y += rs.y, ls.z += rs.z, ls.i += rs.i, ls.j += rs.j, ls.k += rs.k); return ls; }
478
+  FI XYZval<T>  operator+ (const XYZEval<T> &rs)       { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x += rs.x, ls.y += rs.y, ls.z += rs.z, ls.i += rs.i, ls.j += rs.j, ls.k += rs.k); return ls; }
479
+  FI XYZval<T>  operator- (const XYZEval<T> &rs) const { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x -= rs.x, ls.y -= rs.y, ls.z -= rs.z, ls.i -= rs.i, ls.j -= rs.j, ls.k -= rs.k); return ls; }
480
+  FI XYZval<T>  operator- (const XYZEval<T> &rs)       { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x -= rs.x, ls.y -= rs.y, ls.z -= rs.z, ls.i -= rs.i, ls.j -= rs.j, ls.k -= rs.k); return ls; }
481
+  FI XYZval<T>  operator* (const XYZEval<T> &rs) const { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x *= rs.x, ls.y *= rs.y, ls.z *= rs.z, ls.i *= rs.i, ls.j *= rs.j, ls.k *= rs.k); return ls; }
482
+  FI XYZval<T>  operator* (const XYZEval<T> &rs)       { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x *= rs.x, ls.y *= rs.y, ls.z *= rs.z, ls.i *= rs.i, ls.j *= rs.j, ls.k *= rs.k); return ls; }
483
+  FI XYZval<T>  operator/ (const XYZEval<T> &rs) const { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x /= rs.x, ls.y /= rs.y, ls.z /= rs.z, ls.i /= rs.i, ls.j /= rs.j, ls.k /= rs.k); return ls; }
484
+  FI XYZval<T>  operator/ (const XYZEval<T> &rs)       { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x /= rs.x, ls.y /= rs.y, ls.z /= rs.z, ls.i /= rs.i, ls.j /= rs.j, ls.k /= rs.k); return ls; }
485
+  FI XYZval<T>  operator* (const float &v)       const { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x *= v,    ls.y *= v,    ls.z *= v,    ls.i *= v,    ls.j *= v,    ls.k *= v   ); return ls; }
486
+  FI XYZval<T>  operator* (const float &v)             { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x *= v,    ls.y *= v,    ls.z *= v,    ls.i *= v,    ls.j *= v,    ls.k *= v   ); return ls; }
487
+  FI XYZval<T>  operator* (const int &v)         const { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x *= v,    ls.y *= v,    ls.z *= v,    ls.i *= v,    ls.j *= v,    ls.k *= v   ); return ls; }
488
+  FI XYZval<T>  operator* (const int &v)               { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x *= v,    ls.y *= v,    ls.z *= v,    ls.i *= v,    ls.j *= v,    ls.k *= v   ); return ls; }
489
+  FI XYZval<T>  operator/ (const float &v)       const { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x /= v,    ls.y /= v,    ls.z /= v,    ls.i /= v,    ls.j /= v,    ls.k /= v   ); return ls; }
490
+  FI XYZval<T>  operator/ (const float &v)             { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x /= v,    ls.y /= v,    ls.z /= v,    ls.i /= v,    ls.j /= v,    ls.k /= v   ); return ls; }
491
+  FI XYZval<T>  operator/ (const int &v)         const { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x /= v,    ls.y /= v,    ls.z /= v,    ls.i /= v,    ls.j /= v,    ls.k /= v   ); return ls; }
492
+  FI XYZval<T>  operator/ (const int &v)               { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x /= v,    ls.y /= v,    ls.z /= v,    ls.i /= v,    ls.j /= v,    ls.k /= v   ); return ls; }
493
+  FI XYZval<T>  operator>>(const int &v)         const { XYZval<T> ls = *this; LINEAR_AXIS_CODE(_RS(ls.x),    _RS(ls.y),    _RS(ls.z),    _RS(ls.i),    _RS(ls.j),    _RS(ls.k)   ); return ls; }
494
+  FI XYZval<T>  operator>>(const int &v)               { XYZval<T> ls = *this; LINEAR_AXIS_CODE(_RS(ls.x),    _RS(ls.y),    _RS(ls.z),    _RS(ls.i),    _RS(ls.j),    _RS(ls.k)   ); return ls; }
495
+  FI XYZval<T>  operator<<(const int &v)         const { XYZval<T> ls = *this; LINEAR_AXIS_CODE(_LS(ls.x),    _LS(ls.y),    _LS(ls.z),    _LS(ls.i),    _LS(ls.j),    _LS(ls.k)   ); return ls; }
496
+  FI XYZval<T>  operator<<(const int &v)               { XYZval<T> ls = *this; LINEAR_AXIS_CODE(_LS(ls.x),    _LS(ls.y),    _LS(ls.z),    _LS(ls.i),    _LS(ls.j),    _LS(ls.k)   ); return ls; }
497
+  FI const XYZval<T> operator-()                 const { XYZval<T> o = *this; LINEAR_AXIS_CODE(o.x = -x, o.y = -y, o.z = -z, o.i = -i, o.j = -j, o.k = -k); return o; }
498
+  FI XYZval<T>       operator-()                       { XYZval<T> o = *this; LINEAR_AXIS_CODE(o.x = -x, o.y = -y, o.z = -z, o.i = -i, o.j = -j, o.k = -k); return o; }
499
+
500
+  // Modifier operators
501
+  FI XYZval<T>& operator+=(const XYval<T>   &rs)       { LINEAR_AXIS_CODE(x += rs.x, y += rs.y, NOOP,      NOOP,      NOOP,      NOOP     ); return *this; }
502
+  FI XYZval<T>& operator-=(const XYval<T>   &rs)       { LINEAR_AXIS_CODE(x -= rs.x, y -= rs.y, NOOP,      NOOP,      NOOP,      NOOP     ); return *this; }
503
+  FI XYZval<T>& operator*=(const XYval<T>   &rs)       { LINEAR_AXIS_CODE(x *= rs.x, y *= rs.y, NOOP,      NOOP,      NOOP,      NOOP     ); return *this; }
504
+  FI XYZval<T>& operator/=(const XYval<T>   &rs)       { LINEAR_AXIS_CODE(x /= rs.x, y /= rs.y, NOOP,      NOOP,      NOOP,      NOOP     ); return *this; }
505
+  FI XYZval<T>& operator+=(const XYZval<T>  &rs)       { LINEAR_AXIS_CODE(x += rs.x, y += rs.y, z += rs.z, i += rs.i, j += rs.j, k += rs.k); return *this; }
506
+  FI XYZval<T>& operator-=(const XYZval<T>  &rs)       { LINEAR_AXIS_CODE(x -= rs.x, y -= rs.y, z -= rs.z, i -= rs.i, j -= rs.j, k -= rs.k); return *this; }
507
+  FI XYZval<T>& operator*=(const XYZval<T>  &rs)       { LINEAR_AXIS_CODE(x *= rs.x, y *= rs.y, z *= rs.z, i *= rs.i, j *= rs.j, k *= rs.k); return *this; }
508
+  FI XYZval<T>& operator/=(const XYZval<T>  &rs)       { LINEAR_AXIS_CODE(x /= rs.x, y /= rs.y, z /= rs.z, i /= rs.i, j /= rs.j, k /= rs.k); return *this; }
509
+  FI XYZval<T>& operator+=(const XYZEval<T> &rs)       { LINEAR_AXIS_CODE(x += rs.x, y += rs.y, z += rs.z, i += rs.i, j += rs.j, k += rs.k); return *this; }
510
+  FI XYZval<T>& operator-=(const XYZEval<T> &rs)       { LINEAR_AXIS_CODE(x -= rs.x, y -= rs.y, z -= rs.z, i -= rs.i, j -= rs.j, k -= rs.k); return *this; }
511
+  FI XYZval<T>& operator*=(const XYZEval<T> &rs)       { LINEAR_AXIS_CODE(x *= rs.x, y *= rs.y, z *= rs.z, i *= rs.i, j *= rs.j, k *= rs.k); return *this; }
512
+  FI XYZval<T>& operator/=(const XYZEval<T> &rs)       { LINEAR_AXIS_CODE(x /= rs.x, y /= rs.y, z /= rs.z, i /= rs.i, j /= rs.j, k /= rs.k); return *this; }
513
+  FI XYZval<T>& operator*=(const float &v)             { LINEAR_AXIS_CODE(x *= v,    y *= v,    z *= v,    i *= v,    j *= v,    k *= v);    return *this; }
514
+  FI XYZval<T>& operator*=(const int &v)               { LINEAR_AXIS_CODE(x *= v,    y *= v,    z *= v,    i *= v,    j *= v,    k *= v);    return *this; }
515
+  FI XYZval<T>& operator>>=(const int &v)              { LINEAR_AXIS_CODE(_RS(x),    _RS(y),    _RS(z),    _RS(i),    _RS(j),    _RS(k));    return *this; }
516
+  FI XYZval<T>& operator<<=(const int &v)              { LINEAR_AXIS_CODE(_LS(x),    _LS(y),    _LS(z),    _LS(i),    _LS(j),    _LS(k));    return *this; }
517
+
518
+  // Exact comparisons. For floats a "NEAR" operation may be better.
519
+  FI bool       operator==(const XYZEval<T> &rs)       { return true LINEAR_AXIS_GANG(&& x == rs.x, && y == rs.y, && z == rs.z, && i == rs.i, && j == rs.j, && k == rs.k); }
520
+  FI bool       operator==(const XYZEval<T> &rs) const { return true LINEAR_AXIS_GANG(&& x == rs.x, && y == rs.y, && z == rs.z, && i == rs.i, && j == rs.j, && k == rs.k); }
454 521
   FI bool       operator!=(const XYZEval<T> &rs)       { return !operator==(rs); }
455 522
   FI bool       operator!=(const XYZEval<T> &rs) const { return !operator==(rs); }
456
-  FI XYZval<T>       operator-()                       { XYZval<T> o = *this; LINEAR_AXIS_CODE(o.x = -x, o.y = -y, o.z = -z); return o; }
457
-  FI const XYZval<T> operator-()                 const { XYZval<T> o = *this; LINEAR_AXIS_CODE(o.x = -x, o.y = -y, o.z = -z); return o; }
458 523
 };
459 524
 
460 525
 //
@@ -463,109 +528,137 @@ struct XYZval {
463 528
 template<typename T>
464 529
 struct XYZEval {
465 530
   union {
466
-    struct{ T LOGICAL_AXIS_LIST(e, x, y, z); };
467
-    struct{ T LINEAR_AXIS_LIST(a, b, c); };
531
+    struct { T LOGICAL_AXIS_ARGS(); };
532
+    struct { T LOGICAL_AXIS_LIST(_e, a, b, c, u, v, w); };
468 533
     T pos[LOGICAL_AXES];
469 534
   };
470
-  FI void reset()                                             { LOGICAL_AXIS_GANG(e =, x =, y =, z =) 0; }
471
-  FI T magnitude()                                      const { return (T)sqrtf(LOGICAL_AXIS_GANG(+ e*e, + x*x, + y*y, + z*z)); }
472
-  FI operator T* ()                                           { return pos; }
473
-  FI operator bool()                                          { return false LOGICAL_AXIS_GANG(|| e, || x, || y, || z); }
474
-  FI void set(const T px)                                     { x = px;               }
475
-  FI void set(const T px, const T py)                         { x = px;    y = py;    }
476
-  FI void set(const XYval<T> pxy)                             { x = pxy.x; y = pxy.y; }
477
-  FI void set(const XYZval<T> pxyz)                           { set(LINEAR_AXIS_LIST(pxyz.x, pxyz.y, pxyz.z)); }
535
+  // Reset all to 0
536
+  FI void reset()                     { LOGICAL_AXIS_GANG(e =, x =, y =, z =, i =, j =, k =) 0; }
537
+
538
+  // Setters taking struct types and arrays
539
+  FI void set(const T px)             { x = px;               }
540
+  FI void set(const T px, const T py) { x = px;    y = py;    }
541
+  FI void set(const XYval<T> pxy)     { x = pxy.x; y = pxy.y; }
542
+  FI void set(const XYZval<T> pxyz)   { set(LINEAR_AXIS_ELEM(pxyz)); }
478 543
   #if HAS_Z_AXIS
479
-    FI void set(LINEAR_AXIS_LIST(const T px, const T py, const T pz)) {
480
-      LINEAR_AXIS_CODE(x = px, y = py, z = pz);
481
-    }
544
+    FI void set(LINEAR_AXIS_ARGS(const T))         { LINEAR_AXIS_CODE(a = x, b = y, c = z, u = i, v = j, w = k); }
482 545
   #endif
483 546
   #if LOGICAL_AXES > LINEAR_AXES
484
-    FI void set(LOGICAL_AXIS_LIST(const T pe, const T px, const T py, const T pz)) {
485
-      LOGICAL_AXIS_CODE(e = pe, x = px, y = py, z = pz);
486
-    }
487
-    FI void set(const XYval<T> pxy, const T pe)               { set(pxy); e = pe; }
488
-    FI void set(const XYZval<T> pxyz, const T pe)             { set(pxyz); e = pe; }
547
+    FI void set(const XYval<T> pxy, const T pe)    { set(pxy); e = pe; }
548
+    FI void set(const XYZval<T> pxyz, const T pe)  { set(pxyz); e = pe; }
549
+    FI void set(LOGICAL_AXIS_ARGS(const T))        { LOGICAL_AXIS_CODE(_e = e, a = x, b = y, c = z, u = i, v = j, w = k); }
489 550
   #endif
490
-  FI XYZEval<T>          copy()                         const { XYZEval<T> o = *this; return o; }
491
-  FI XYZEval<T>           ABS()                         const { return LOGICAL_AXIS_ARRAY(T(_ABS(e)), T(_ABS(x)), T(_ABS(y)), T(_ABS(z))); }
492
-  FI XYZEval<int16_t>   asInt()                               { return LOGICAL_AXIS_ARRAY(int16_t(e), int16_t(x), int16_t(y), int16_t(z)); }
493
-  FI XYZEval<int16_t>   asInt()                         const { return LOGICAL_AXIS_ARRAY(int16_t(e), int16_t(x), int16_t(y), int16_t(z)); }
494
-  FI XYZEval<int32_t>  asLong()                               { return LOGICAL_AXIS_ARRAY(int32_t(e), int32_t(x), int32_t(y), int32_t(z)); }
495
-  FI XYZEval<int32_t>  asLong()                         const { return LOGICAL_AXIS_ARRAY(int32_t(e), int32_t(x), int32_t(y), int32_t(z)); }
496
-  FI XYZEval<int32_t>  ROUNDL()                               { return LOGICAL_AXIS_ARRAY(int32_t(LROUND(e)), int32_t(LROUND(x)), int32_t(LROUND(y)), int32_t(LROUND(z))); }
497
-  FI XYZEval<int32_t>  ROUNDL()                         const { return LOGICAL_AXIS_ARRAY(int32_t(LROUND(e)), int32_t(LROUND(x)), int32_t(LROUND(y)), int32_t(LROUND(z))); }
498
-  FI XYZEval<float>   asFloat()                               { return LOGICAL_AXIS_ARRAY(static_cast<float>(e), static_cast<float>(x), static_cast<float>(y), static_cast<float>(z)); }
499
-  FI XYZEval<float>   asFloat()                         const { return LOGICAL_AXIS_ARRAY(static_cast<float>(e), static_cast<float>(x), static_cast<float>(y), static_cast<float>(z)); }
500
-  FI XYZEval<float> reciprocal()                        const { return LOGICAL_AXIS_ARRAY(_RECIP(e),  _RECIP(x),  _RECIP(y),  _RECIP(z)); }
501
-  FI XYZEval<float> asLogical()                         const { XYZEval<float> o = asFloat(); toLogical(o); return o; }
502
-  FI XYZEval<float>  asNative()                         const { XYZEval<float> o = asFloat(); toNative(o);  return o; }
503
-  FI operator       XYval<T>&()                               { return *(XYval<T>*)this; }
504
-  FI operator const XYval<T>&()                         const { return *(const XYval<T>*)this; }
505
-  FI operator       XYZval<T>&()                              { return *(XYZval<T>*)this; }
506
-  FI operator const XYZval<T>&()                        const { return *(const XYZval<T>*)this; }
507
-  FI       T&    operator[](const int n)                      { return pos[n]; }
508
-  FI const T&    operator[](const int n)                const { return pos[n]; }
509
-  FI XYZEval<T>& operator= (const T v)                        { set(LIST_N_1(LINEAR_AXES, v)); return *this; }
510
-  FI XYZEval<T>& operator= (const XYval<T>   &rs)             { set(rs.x, rs.y); return *this; }
511
-  FI XYZEval<T>& operator= (const XYZval<T>  &rs)             { set(LINEAR_AXIS_LIST(rs.x, rs.y, rs.z)); return *this; }
512
-  FI XYZEval<T>  operator+ (const XYval<T>   &rs)       const { XYZEval<T> ls = *this; ls.x += rs.x; ls.y += rs.y; return ls; }
513
-  FI XYZEval<T>  operator+ (const XYval<T>   &rs)             { XYZEval<T> ls = *this; ls.x += rs.x; ls.y += rs.y; return ls; }
514
-  FI XYZEval<T>  operator- (const XYval<T>   &rs)       const { XYZEval<T> ls = *this; ls.x -= rs.x; ls.y -= rs.y; return ls; }
515
-  FI XYZEval<T>  operator- (const XYval<T>   &rs)             { XYZEval<T> ls = *this; ls.x -= rs.x; ls.y -= rs.y; return ls; }
516
-  FI XYZEval<T>  operator* (const XYval<T>   &rs)       const { XYZEval<T> ls = *this; ls.x *= rs.x; ls.y *= rs.y; return ls; }
517
-  FI XYZEval<T>  operator* (const XYval<T>   &rs)             { XYZEval<T> ls = *this; ls.x *= rs.x; ls.y *= rs.y; return ls; }
518
-  FI XYZEval<T>  operator/ (const XYval<T>   &rs)       const { XYZEval<T> ls = *this; ls.x /= rs.x; ls.y /= rs.y; return ls; }
519
-  FI XYZEval<T>  operator/ (const XYval<T>   &rs)             { XYZEval<T> ls = *this; ls.x /= rs.x; ls.y /= rs.y; return ls; }
520
-  FI XYZEval<T>  operator+ (const XYZval<T>  &rs)       const { XYZval<T>  ls = *this; LINEAR_AXIS_CODE(ls.x += rs.x, ls.y += rs.y, ls.z += rs.z); return ls; }
521
-  FI XYZEval<T>  operator+ (const XYZval<T>  &rs)             { XYZval<T>  ls = *this; LINEAR_AXIS_CODE(ls.x += rs.x, ls.y += rs.y, ls.z += rs.z); return ls; }
522
-  FI XYZEval<T>  operator- (const XYZval<T>  &rs)       const { XYZval<T>  ls = *this; LINEAR_AXIS_CODE(ls.x -= rs.x, ls.y -= rs.y, ls.z -= rs.z); return ls; }
523
-  FI XYZEval<T>  operator- (const XYZval<T>  &rs)             { XYZval<T>  ls = *this; LINEAR_AXIS_CODE(ls.x -= rs.x, ls.y -= rs.y, ls.z -= rs.z); return ls; }
524
-  FI XYZEval<T>  operator* (const XYZval<T>  &rs)       const { XYZval<T>  ls = *this; LINEAR_AXIS_CODE(ls.x *= rs.x, ls.y *= rs.y, ls.z *= rs.z); return ls; }
525
-  FI XYZEval<T>  operator* (const XYZval<T>  &rs)             { XYZval<T>  ls = *this; LINEAR_AXIS_CODE(ls.x *= rs.x, ls.y *= rs.y, ls.z *= rs.z); return ls; }
526
-  FI XYZEval<T>  operator/ (const XYZval<T>  &rs)       const { XYZval<T>  ls = *this; LINEAR_AXIS_CODE(ls.x /= rs.x, ls.y /= rs.y, ls.z /= rs.z); return ls; }
527
-  FI XYZEval<T>  operator/ (const XYZval<T>  &rs)             { XYZval<T>  ls = *this; LINEAR_AXIS_CODE(ls.x /= rs.x, ls.y /= rs.y, ls.z /= rs.z); return ls; }
528
-  FI XYZEval<T>  operator+ (const XYZEval<T> &rs)       const { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(ls.e += rs.e, ls.x += rs.x, ls.y += rs.y, ls.z += rs.z ); return ls; }
529
-  FI XYZEval<T>  operator+ (const XYZEval<T> &rs)             { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(ls.e += rs.e, ls.x += rs.x, ls.y += rs.y, ls.z += rs.z ); return ls; }
530
-  FI XYZEval<T>  operator- (const XYZEval<T> &rs)       const { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(ls.e -= rs.e, ls.x -= rs.x, ls.y -= rs.y, ls.z -= rs.z ); return ls; }
531
-  FI XYZEval<T>  operator- (const XYZEval<T> &rs)             { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(ls.e -= rs.e, ls.x -= rs.x, ls.y -= rs.y, ls.z -= rs.z ); return ls; }
532
-  FI XYZEval<T>  operator* (const XYZEval<T> &rs)       const { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(ls.e *= rs.e, ls.x *= rs.x, ls.y *= rs.y, ls.z *= rs.z ); return ls; }
533
-  FI XYZEval<T>  operator* (const XYZEval<T> &rs)             { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(ls.e *= rs.e, ls.x *= rs.x, ls.y *= rs.y, ls.z *= rs.z ); return ls; }
534
-  FI XYZEval<T>  operator/ (const XYZEval<T> &rs)       const { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(ls.e /= rs.e, ls.x /= rs.x, ls.y /= rs.y, ls.z /= rs.z ); return ls; }
535
-  FI XYZEval<T>  operator/ (const XYZEval<T> &rs)             { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(ls.e /= rs.e, ls.x /= rs.x, ls.y /= rs.y, ls.z /= rs.z ); return ls; }
536
-  FI XYZEval<T>  operator* (const float &v)             const { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(ls.e *= v,    ls.x *= v,    ls.y *= v,    ls.z *= v    ); return ls; }
537
-  FI XYZEval<T>  operator* (const float &v)                   { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(ls.e *= v,    ls.x *= v,    ls.y *= v,    ls.z *= v    ); return ls; }
538
-  FI XYZEval<T>  operator* (const int &v)               const { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(ls.e *= v,    ls.x *= v,    ls.y *= v,    ls.z *= v    ); return ls; }
539
-  FI XYZEval<T>  operator* (const int &v)                     { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(ls.e *= v,    ls.x *= v,    ls.y *= v,    ls.z *= v    ); return ls; }
540
-  FI XYZEval<T>  operator/ (const float &v)             const { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(ls.e /= v,    ls.x /= v,    ls.y /= v,    ls.z /= v    ); return ls; }
541
-  FI XYZEval<T>  operator/ (const float &v)                   { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(ls.e /= v,    ls.x /= v,    ls.y /= v,    ls.z /= v    ); return ls; }
542
-  FI XYZEval<T>  operator/ (const int &v)               const { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(ls.e /= v,    ls.x /= v,    ls.y /= v,    ls.z /= v    ); return ls; }
543
-  FI XYZEval<T>  operator/ (const int &v)                     { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(ls.e /= v,    ls.x /= v,    ls.y /= v,    ls.z /= v    ); return ls; }
544
-  FI XYZEval<T>  operator>>(const int &v)               const { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(_RS(ls.e),    _RS(ls.x),    _RS(ls.y),    _RS(ls.z)    ); return ls; }
545
-  FI XYZEval<T>  operator>>(const int &v)                     { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(_RS(ls.e),    _RS(ls.x),    _RS(ls.y),    _RS(ls.z)    ); return ls; }
546
-  FI XYZEval<T>  operator<<(const int &v)               const { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(_LS(ls.e),    _LS(ls.x),    _LS(ls.y),    _LS(ls.z)    ); return ls; }
547
-  FI XYZEval<T>  operator<<(const int &v)                     { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(_LS(ls.e),    _LS(ls.x),    _LS(ls.y),    _LS(ls.z)    ); return ls; }
548
-  FI XYZEval<T>& operator+=(const XYval<T>   &rs)             { x += rs.x; y += rs.y; return *this; }
549
-  FI XYZEval<T>& operator-=(const XYval<T>   &rs)             { x -= rs.x; y -= rs.y; return *this; }
550
-  FI XYZEval<T>& operator*=(const XYval<T>   &rs)             { x *= rs.x; y *= rs.y; return *this; }
551
-  FI XYZEval<T>& operator/=(const XYval<T>   &rs)             { x /= rs.x; y /= rs.y; return *this; }
552
-  FI XYZEval<T>& operator+=(const XYZval<T>  &rs)             { LINEAR_AXIS_CODE(x += rs.x, y += rs.y, z += rs.z); return *this; }
553
-  FI XYZEval<T>& operator-=(const XYZval<T>  &rs)             { LINEAR_AXIS_CODE(x -= rs.x, y -= rs.y, z -= rs.z); return *this; }
554
-  FI XYZEval<T>& operator*=(const XYZval<T>  &rs)             { LINEAR_AXIS_CODE(x *= rs.x, y *= rs.y, z *= rs.z); return *this; }
555
-  FI XYZEval<T>& operator/=(const XYZval<T>  &rs)             { LINEAR_AXIS_CODE(x /= rs.x, y /= rs.y, z /= rs.z); return *this; }
556
-  FI XYZEval<T>& operator+=(const XYZEval<T> &rs)             { LOGICAL_AXIS_CODE(e += rs.e, x += rs.x, y += rs.y, z += rs.z); return *this; }
557
-  FI XYZEval<T>& operator-=(const XYZEval<T> &rs)             { LOGICAL_AXIS_CODE(e -= rs.e, x -= rs.x, y -= rs.y, z -= rs.z); return *this; }
558
-  FI XYZEval<T>& operator*=(const XYZEval<T> &rs)             { LOGICAL_AXIS_CODE(e *= rs.e, x *= rs.x, y *= rs.y, z *= rs.z); return *this; }
559
-  FI XYZEval<T>& operator/=(const XYZEval<T> &rs)             { LOGICAL_AXIS_CODE(e /= rs.e, x /= rs.x, y /= rs.y, z /= rs.z); return *this; }
560
-  FI XYZEval<T>& operator*=(const T &v)                       { LOGICAL_AXIS_CODE(e *= v,    x *= v,    y *= v,    z *= v);    return *this; }
561
-  FI XYZEval<T>& operator>>=(const int &v)                    { LOGICAL_AXIS_CODE(_RS(e),    _RS(x),    _RS(y),    _RS(z));    return *this; }
562
-  FI XYZEval<T>& operator<<=(const int &v)                    { LOGICAL_AXIS_CODE(_LS(e),    _LS(x),    _LS(y),    _LS(z));    return *this; }
563
-  FI bool        operator==(const XYZval<T>  &rs)             { return true LINEAR_AXIS_GANG(&& x == rs.x, && y == rs.y, && z == rs.z); }
564
-  FI bool        operator==(const XYZval<T>  &rs)       const { return true LINEAR_AXIS_GANG(&& x == rs.x, && y == rs.y, && z == rs.z); }
565
-  FI bool        operator!=(const XYZval<T>  &rs)             { return !operator==(rs); }
566
-  FI bool        operator!=(const XYZval<T>  &rs)       const { return !operator==(rs); }
567
-  FI       XYZEval<T> operator-()                             { return LOGICAL_AXIS_ARRAY(-e, -x, -y, -z); }
568
-  FI const XYZEval<T> operator-()                       const { return LOGICAL_AXIS_ARRAY(-e, -x, -y, -z); }
551
+  #if LINEAR_AXES >= 4
552
+    FI void set(const T px, const T py, const T pz)                         { x = px; y = py; z = pz; }
553
+  #endif
554
+  #if LINEAR_AXES >= 5
555
+    FI void set(const T px, const T py, const T pz, const T pi)             { x = px; y = py; z = pz; i = pi; }
556
+  #endif
557
+  #if LINEAR_AXES >= 6
558
+    FI void set(const T px, const T py, const T pz, const T pi, const T pj) { x = px; y = py; z = pz; i = pi; j = pj; }
559
+  #endif
560
+
561
+  // Length reduced to one dimension
562
+  FI T magnitude()                                 const { return (T)sqrtf(LOGICAL_AXIS_GANG(+ e*e, + x*x, + y*y, + z*z, + i*i, + j*j, + k*k)); }
563
+  // Pointer to the data as a simple array
564
+  FI operator T* ()                                      { return pos; }
565
+  // If any element is true then it's true
566
+  FI operator bool()                                     { return 0 LOGICAL_AXIS_GANG(|| e, || x, || y, || z, || i, || j, || k); }
567
+
568
+  // Explicit copy and copies with conversion
569
+  FI XYZEval<T>          copy()  const { XYZEval<T> o = *this; return o; }
570
+  FI XYZEval<T>           ABS()  const { return LOGICAL_AXIS_ARRAY(T(_ABS(e)), T(_ABS(x)), T(_ABS(y)), T(_ABS(z)), T(_ABS(i)), T(_ABS(j)), T(_ABS(k))); }
571
+  FI XYZEval<int16_t>   asInt()        { return LOGICAL_AXIS_ARRAY(int16_t(e), int16_t(x), int16_t(y), int16_t(z), int16_t(i), int16_t(j), int16_t(k)); }
572
+  FI XYZEval<int16_t>   asInt()  const { return LOGICAL_AXIS_ARRAY(int16_t(e), int16_t(x), int16_t(y), int16_t(z), int16_t(i), int16_t(j), int16_t(k)); }
573
+  FI XYZEval<int32_t>  asLong()        { return LOGICAL_AXIS_ARRAY(int32_t(e), int32_t(x), int32_t(y), int32_t(z), int32_t(i), int32_t(j), int32_t(k)); }
574
+  FI XYZEval<int32_t>  asLong()  const { return LOGICAL_AXIS_ARRAY(int32_t(e), int32_t(x), int32_t(y), int32_t(z), int32_t(i), int32_t(j), int32_t(k)); }
575
+  FI XYZEval<int32_t>  ROUNDL()        { return LOGICAL_AXIS_ARRAY(int32_t(LROUND(e)), int32_t(LROUND(x)), int32_t(LROUND(y)), int32_t(LROUND(z)), int32_t(LROUND(i)), int32_t(LROUND(j)), int32_t(LROUND(k))); }
576
+  FI XYZEval<int32_t>  ROUNDL()  const { return LOGICAL_AXIS_ARRAY(int32_t(LROUND(e)), int32_t(LROUND(x)), int32_t(LROUND(y)), int32_t(LROUND(z)), int32_t(LROUND(i)), int32_t(LROUND(j)), int32_t(LROUND(k))); }
577
+  FI XYZEval<float>   asFloat()        { return LOGICAL_AXIS_ARRAY(static_cast<float>(e), static_cast<float>(x), static_cast<float>(y), static_cast<float>(z), static_cast<float>(i), static_cast<float>(j), static_cast<float>(k)); }
578
+  FI XYZEval<float>   asFloat()  const { return LOGICAL_AXIS_ARRAY(static_cast<float>(e), static_cast<float>(x), static_cast<float>(y), static_cast<float>(z), static_cast<float>(i), static_cast<float>(j), static_cast<float>(k)); }
579
+  FI XYZEval<float> reciprocal() const { return LOGICAL_AXIS_ARRAY(_RECIP(e),  _RECIP(x),  _RECIP(y),  _RECIP(z),  _RECIP(i),  _RECIP(j),  _RECIP(k)); }
580
+
581
+  // Marlin workspace shifting is done with G92 and M206
582
+  FI XYZEval<float> asLogical()  const { XYZEval<float> o = asFloat(); toLogical(o); return o; }
583
+  FI XYZEval<float>  asNative()  const { XYZEval<float> o = asFloat(); toNative(o);  return o; }
584
+
585
+  // In-place cast to types having fewer fields
586
+  FI operator       XYval<T>&()        { return *(XYval<T>*)this; }
587
+  FI operator const XYval<T>&()  const { return *(const XYval<T>*)this; }
588
+  FI operator       XYZval<T>&()       { return *(XYZval<T>*)this; }
589
+  FI operator const XYZval<T>&() const { return *(const XYZval<T>*)this; }
590
+
591
+  // Accessor via an AxisEnum (or any integer) [index]
592
+  FI       T&    operator[](const int n)                  { return pos[n]; }
593
+  FI const T&    operator[](const int n)            const { return pos[n]; }
594
+
595
+  // Assignment operator overrides do the expected thing
596
+  FI XYZEval<T>& operator= (const T v)                    { set(LIST_N_1(LINEAR_AXES, v)); return *this; }
597
+  FI XYZEval<T>& operator= (const XYval<T>   &rs)         { set(rs.x, rs.y); return *this; }
598
+  FI XYZEval<T>& operator= (const XYZval<T>  &rs)         { set(LINEAR_AXIS_ELEM(rs)); return *this; }
599
+
600
+  // Override other operators to get intuitive behaviors
601
+  FI XYZEval<T>  operator+ (const XYval<T>   &rs)   const { XYZEval<T> ls = *this; ls.x += rs.x; ls.y += rs.y; return ls; }
602
+  FI XYZEval<T>  operator+ (const XYval<T>   &rs)         { XYZEval<T> ls = *this; ls.x += rs.x; ls.y += rs.y; return ls; }
603
+  FI XYZEval<T>  operator- (const XYval<T>   &rs)   const { XYZEval<T> ls = *this; ls.x -= rs.x; ls.y -= rs.y; return ls; }
604
+  FI XYZEval<T>  operator- (const XYval<T>   &rs)         { XYZEval<T> ls = *this; ls.x -= rs.x; ls.y -= rs.y; return ls; }
605
+  FI XYZEval<T>  operator* (const XYval<T>   &rs)   const { XYZEval<T> ls = *this; ls.x *= rs.x; ls.y *= rs.y; return ls; }
606
+  FI XYZEval<T>  operator* (const XYval<T>   &rs)         { XYZEval<T> ls = *this; ls.x *= rs.x; ls.y *= rs.y; return ls; }
607
+  FI XYZEval<T>  operator/ (const XYval<T>   &rs)   const { XYZEval<T> ls = *this; ls.x /= rs.x; ls.y /= rs.y; return ls; }
608
+  FI XYZEval<T>  operator/ (const XYval<T>   &rs)         { XYZEval<T> ls = *this; ls.x /= rs.x; ls.y /= rs.y; return ls; }
609
+  FI XYZEval<T>  operator+ (const XYZval<T>  &rs)   const { XYZval<T>  ls = *this; LINEAR_AXIS_CODE(ls.x += rs.x, ls.y += rs.y, ls.z += rs.z, ls.i += rs.i, ls.j += rs.j, ls.k += rs.k); return ls; }
610
+  FI XYZEval<T>  operator+ (const XYZval<T>  &rs)         { XYZval<T>  ls = *this; LINEAR_AXIS_CODE(ls.x += rs.x, ls.y += rs.y, ls.z += rs.z, ls.i += rs.i, ls.j += rs.j, ls.k += rs.k); return ls; }
611
+  FI XYZEval<T>  operator- (const XYZval<T>  &rs)   const { XYZval<T>  ls = *this; LINEAR_AXIS_CODE(ls.x -= rs.x, ls.y -= rs.y, ls.z -= rs.z, ls.i -= rs.i, ls.j -= rs.j, ls.k -= rs.k); return ls; }
612
+  FI XYZEval<T>  operator- (const XYZval<T>  &rs)         { XYZval<T>  ls = *this; LINEAR_AXIS_CODE(ls.x -= rs.x, ls.y -= rs.y, ls.z -= rs.z, ls.i -= rs.i, ls.j -= rs.j, ls.k -= rs.k); return ls; }
613
+  FI XYZEval<T>  operator* (const XYZval<T>  &rs)   const { XYZval<T>  ls = *this; LINEAR_AXIS_CODE(ls.x *= rs.x, ls.y *= rs.y, ls.z *= rs.z, ls.i *= rs.i, ls.j *= rs.j, ls.k *= rs.k); return ls; }
614
+  FI XYZEval<T>  operator* (const XYZval<T>  &rs)         { XYZval<T>  ls = *this; LINEAR_AXIS_CODE(ls.x *= rs.x, ls.y *= rs.y, ls.z *= rs.z, ls.i *= rs.i, ls.j *= rs.j, ls.k *= rs.k); return ls; }
615
+  FI XYZEval<T>  operator/ (const XYZval<T>  &rs)   const { XYZval<T>  ls = *this; LINEAR_AXIS_CODE(ls.x /= rs.x, ls.y /= rs.y, ls.z /= rs.z, ls.i /= rs.i, ls.j /= rs.j, ls.k /= rs.k); return ls; }
616
+  FI XYZEval<T>  operator/ (const XYZval<T>  &rs)         { XYZval<T>  ls = *this; LINEAR_AXIS_CODE(ls.x /= rs.x, ls.y /= rs.y, ls.z /= rs.z, ls.i /= rs.i, ls.j /= rs.j, ls.k /= rs.k); return ls; }
617
+  FI XYZEval<T>  operator+ (const XYZEval<T>  &rs)  const { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(ls.e += rs.e, ls.x += rs.x, ls.y += rs.y, ls.z += rs.z, ls.i += rs.i, ls.j += rs.j, ls.k += rs.k); return ls; }
618
+  FI XYZEval<T>  operator+ (const XYZEval<T>  &rs)        { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(ls.e += rs.e, ls.x += rs.x, ls.y += rs.y, ls.z += rs.z, ls.i += rs.i, ls.j += rs.j, ls.k += rs.k); return ls; }
619
+  FI XYZEval<T>  operator- (const XYZEval<T>  &rs)  const { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(ls.e -= rs.e, ls.x -= rs.x, ls.y -= rs.y, ls.z -= rs.z, ls.i -= rs.i, ls.j -= rs.j, ls.k -= rs.k); return ls; }
620
+  FI XYZEval<T>  operator- (const XYZEval<T>  &rs)        { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(ls.e -= rs.e, ls.x -= rs.x, ls.y -= rs.y, ls.z -= rs.z, ls.i -= rs.i, ls.j -= rs.j, ls.k -= rs.k); return ls; }
621
+  FI XYZEval<T>  operator* (const XYZEval<T>  &rs)  const { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(ls.e *= rs.e, ls.x *= rs.x, ls.y *= rs.y, ls.z *= rs.z, ls.i *= rs.i, ls.j *= rs.j, ls.k *= rs.k); return ls; }
622
+  FI XYZEval<T>  operator* (const XYZEval<T>  &rs)        { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(ls.e *= rs.e, ls.x *= rs.x, ls.y *= rs.y, ls.z *= rs.z, ls.i *= rs.i, ls.j *= rs.j, ls.k *= rs.k); return ls; }
623
+  FI XYZEval<T>  operator/ (const XYZEval<T>  &rs)  const { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(ls.e /= rs.e, ls.x /= rs.x, ls.y /= rs.y, ls.z /= rs.z, ls.i /= rs.i, ls.j /= rs.j, ls.k /= rs.k); return ls; }
624
+  FI XYZEval<T>  operator/ (const XYZEval<T>  &rs)        { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(ls.e /= rs.e, ls.x /= rs.x, ls.y /= rs.y, ls.z /= rs.z, ls.i /= rs.i, ls.j /= rs.j, ls.k /= rs.k); return ls; }
625
+  FI XYZEval<T>  operator* (const float &v)         const { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(ls.e *= v,    ls.x *= v,    ls.y *= v,    ls.z *= v,    ls.i *= v,    ls.j *= v,    ls.k *= v   ); return ls; }
626
+  FI XYZEval<T>  operator* (const float &v)               { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(ls.e *= v,    ls.x *= v,    ls.y *= v,    ls.z *= v,    ls.i *= v,    ls.j *= v,    ls.k *= v   ); return ls; }
627
+  FI XYZEval<T>  operator* (const int &v)           const { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(ls.e *= v,    ls.x *= v,    ls.y *= v,    ls.z *= v,    ls.i *= v,    ls.j *= v,    ls.k *= v   ); return ls; }
628
+  FI XYZEval<T>  operator* (const int &v)                 { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(ls.e *= v,    ls.x *= v,    ls.y *= v,    ls.z *= v,    ls.i *= v,    ls.j *= v,    ls.k *= v   ); return ls; }
629
+  FI XYZEval<T>  operator/ (const float &v)         const { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(ls.e /= v,    ls.x /= v,    ls.y /= v,    ls.z /= v,    ls.i /= v,    ls.j /= v,    ls.k /= v   ); return ls; }
630
+  FI XYZEval<T>  operator/ (const float &v)               { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(ls.e /= v,    ls.x /= v,    ls.y /= v,    ls.z /= v,    ls.i /= v,    ls.j /= v,    ls.k /= v   ); return ls; }
631
+  FI XYZEval<T>  operator/ (const int &v)           const { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(ls.e /= v,    ls.x /= v,    ls.y /= v,    ls.z /= v,    ls.i /= v,    ls.j /= v,    ls.k /= v   ); return ls; }
632
+  FI XYZEval<T>  operator/ (const int &v)                 { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(ls.e /= v,    ls.x /= v,    ls.y /= v,    ls.z /= v,    ls.i /= v,    ls.j /= v,    ls.k /= v   ); return ls; }
633
+  FI XYZEval<T>  operator>>(const int &v)           const { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(_RS(ls.e),    _RS(ls.x),    _RS(ls.y),    _RS(ls.z),    _RS(ls.i),    _RS(ls.j),    _RS(ls.k)   ); return ls; }
634
+  FI XYZEval<T>  operator>>(const int &v)                 { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(_RS(ls.e),    _RS(ls.x),    _RS(ls.y),    _RS(ls.z),    _RS(ls.i),    _RS(ls.j),    _RS(ls.k)   ); return ls; }
635
+  FI XYZEval<T>  operator<<(const int &v)           const { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(_LS(ls.e),    _LS(ls.x),    _LS(ls.y),    _LS(ls.z),    _LS(ls.i),    _LS(ls.j),    _LS(ls.k)   ); return ls; }
636
+  FI XYZEval<T>  operator<<(const int &v)                 { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(_LS(ls.e),    _LS(ls.x),    _LS(ls.y),    _LS(ls.z),    _LS(ls.i),    _LS(ls.j),    _LS(ls.k)   ); return ls; }
637
+  FI const XYZEval<T> operator-()                   const { return LOGICAL_AXIS_ARRAY(-e, -x, -y, -z, -i, -j, -k); }
638
+  FI       XYZEval<T> operator-()                         { return LOGICAL_AXIS_ARRAY(-e, -x, -y, -z, -i, -j, -k); }
639
+
640
+  // Modifier operators
641
+  FI XYZEval<T>& operator+=(const XYval<T>   &rs)         { x += rs.x; y += rs.y; return *this; }
642
+  FI XYZEval<T>& operator-=(const XYval<T>   &rs)         { x -= rs.x; y -= rs.y; return *this; }
643
+  FI XYZEval<T>& operator*=(const XYval<T>   &rs)         { x *= rs.x; y *= rs.y; return *this; }
644
+  FI XYZEval<T>& operator/=(const XYval<T>   &rs)         { x /= rs.x; y /= rs.y; return *this; }
645
+  FI XYZEval<T>& operator+=(const XYZval<T>  &rs)         { LINEAR_AXIS_CODE(x += rs.x, y += rs.y, z += rs.z, i += rs.i, j += rs.j, k += rs.k); return *this; }
646
+  FI XYZEval<T>& operator-=(const XYZval<T>  &rs)         { LINEAR_AXIS_CODE(x -= rs.x, y -= rs.y, z -= rs.z, i -= rs.i, j -= rs.j, k -= rs.k); return *this; }
647
+  FI XYZEval<T>& operator*=(const XYZval<T>  &rs)         { LINEAR_AXIS_CODE(x *= rs.x, y *= rs.y, z *= rs.z, i *= rs.i, j *= rs.j, k *= rs.k); return *this; }
648
+  FI XYZEval<T>& operator/=(const XYZval<T>  &rs)         { LINEAR_AXIS_CODE(x /= rs.x, y /= rs.y, z /= rs.z, i /= rs.i, j /= rs.j, k /= rs.k); return *this; }
649
+  FI XYZEval<T>& operator+=(const XYZEval<T> &rs)         { LOGICAL_AXIS_CODE(e += rs.e, x += rs.x, y += rs.y, z += rs.z, i += rs.i, j += rs.j, k += rs.k); return *this; }
650
+  FI XYZEval<T>& operator-=(const XYZEval<T> &rs)         { LOGICAL_AXIS_CODE(e -= rs.e, x -= rs.x, y -= rs.y, z -= rs.z, i -= rs.i, j -= rs.j, k -= rs.k); return *this; }
651
+  FI XYZEval<T>& operator*=(const XYZEval<T> &rs)         { LOGICAL_AXIS_CODE(e *= rs.e, x *= rs.x, y *= rs.y, z *= rs.z, i *= rs.i, j *= rs.j, k *= rs.k); return *this; }
652
+  FI XYZEval<T>& operator/=(const XYZEval<T> &rs)         { LOGICAL_AXIS_CODE(e /= rs.e, x /= rs.x, y /= rs.y, z /= rs.z, i /= rs.i, j /= rs.j, k /= rs.k); return *this; }
653
+  FI XYZEval<T>& operator*=(const T &v)                   { LOGICAL_AXIS_CODE(e *= v,    x *= v,    y *= v,    z *= v,    i *= v,    j *= v,    k *= v);    return *this; }
654
+  FI XYZEval<T>& operator>>=(const int &v)                { LOGICAL_AXIS_CODE(_RS(e),    _RS(x),    _RS(y),    _RS(z),    _RS(i),    _RS(j),    _RS(k));    return *this; }
655
+  FI XYZEval<T>& operator<<=(const int &v)                { LOGICAL_AXIS_CODE(_LS(e),    _LS(x),    _LS(y),    _LS(z),    _LS(i),    _LS(j),    _LS(k));    return *this; }
656
+
657
+  // Exact comparisons. For floats a "NEAR" operation may be better.
658
+  FI bool        operator==(const XYZval<T>  &rs)         { return true LINEAR_AXIS_GANG(&& x == rs.x, && y == rs.y, && z == rs.z, && i == rs.i, && j == rs.j, && k == rs.k); }
659
+  FI bool        operator==(const XYZval<T>  &rs)   const { return true LINEAR_AXIS_GANG(&& x == rs.x, && y == rs.y, && z == rs.z, && i == rs.i, && j == rs.j, && k == rs.k); }
660
+  FI bool        operator!=(const XYZval<T>  &rs)         { return !operator==(rs); }
661
+  FI bool        operator!=(const XYZval<T>  &rs)   const { return !operator==(rs); }
569 662
 };
570 663
 
571 664
 #undef _RECIP

+ 1
- 1
Marlin/src/core/utility.cpp View File

@@ -122,7 +122,7 @@ void safe_delay(millis_t ms) {
122 122
             SERIAL_ECHOLNPAIR("Z Fade: ", planner.z_fade_height);
123 123
         #endif
124 124
         #if ABL_PLANAR
125
-          SERIAL_ECHOPGM("ABL Adjustment X");
125
+          SERIAL_ECHOPGM("ABL Adjustment");
126 126
           LOOP_LINEAR_AXES(a) {
127 127
             const float v = planner.get_axis_position_mm(AxisEnum(a)) - current_position[a];
128 128
             SERIAL_CHAR(' ', AXIS_CHAR(a));

+ 1
- 1
Marlin/src/core/utility.h View File

@@ -77,7 +77,7 @@ public:
77 77
 // in the range 0-100 while avoiding rounding artifacts
78 78
 constexpr uint8_t ui8_to_percent(const uint8_t i) { return (int(i) * 100 + 127) / 255; }
79 79
 
80
-const xyze_char_t axis_codes LOGICAL_AXIS_ARRAY('E', 'X', 'Y', 'Z');
80
+const xyze_char_t axis_codes LOGICAL_AXIS_ARRAY('E', 'X', 'Y', 'Z', AXIS4_NAME, AXIS5_NAME, AXIS6_NAME);
81 81
 
82 82
 #if LINEAR_AXES <= XYZ
83 83
   #define AXIS_CHAR(A) ((char)('X' + A))

+ 69
- 57
Marlin/src/feature/bedlevel/ubl/ubl_motion.cpp View File

@@ -113,20 +113,22 @@
113 113
     const xy_float_t ad = sign * dist;
114 114
     const bool use_x_dist = ad.x > ad.y;
115 115
 
116
-    float on_axis_distance = use_x_dist ? dist.x : dist.y,
117
-          e_position = end.e - start.e,
118
-          z_position = end.z - start.z;
116
+    float on_axis_distance = use_x_dist ? dist.x : dist.y;
119 117
 
120
-    const float e_normalized_dist = e_position / on_axis_distance, // Allow divide by zero
121
-                z_normalized_dist = z_position / on_axis_distance;
118
+    const float z_normalized_dist = (end.z - start.z) / on_axis_distance; // Allow divide by zero
119
+    #if HAS_EXTRUDERS
120
+      const float e_normalized_dist = (end.e - start.e) / on_axis_distance;
121
+      const bool inf_normalized_flag = isinf(e_normalized_dist);
122
+    #endif
122 123
 
123 124
     xy_int8_t icell = istart;
124 125
 
125 126
     const float ratio = dist.y / dist.x,        // Allow divide by zero
126 127
                 c = start.y - ratio * start.x;
127 128
 
128
-    const bool inf_normalized_flag = isinf(e_normalized_dist),
129
-               inf_ratio_flag = isinf(ratio);
129
+    const bool inf_ratio_flag = isinf(ratio);
130
+
131
+    xyze_pos_t dest; // Stores XYZE for segmented moves
130 132
 
131 133
     /**
132 134
      * Handle vertical lines that stay within one column.
@@ -143,34 +145,36 @@
143 145
          * For others the next X is the same so this can continue.
144 146
          * Calculate X at the next Y mesh line.
145 147
          */
146
-        const float rx = inf_ratio_flag ? start.x : (next_mesh_line_y - c) / ratio;
148
+        dest.x = inf_ratio_flag ? start.x : (next_mesh_line_y - c) / ratio;
147 149
 
148
-        float z0 = z_correction_for_x_on_horizontal_mesh_line(rx, icell.x, icell.y)
150
+        float z0 = z_correction_for_x_on_horizontal_mesh_line(dest.x, icell.x, icell.y)
149 151
                    * planner.fade_scaling_factor_for_z(end.z);
150 152
 
151 153
         // Undefined parts of the Mesh in z_values[][] are NAN.
152 154
         // Replace NAN corrections with 0.0 to prevent NAN propagation.
153 155
         if (isnan(z0)) z0 = 0.0;
154 156
 
155
-        const float ry = mesh_index_to_ypos(icell.y);
157
+        dest.y = mesh_index_to_ypos(icell.y);
156 158
 
157 159
         /**
158 160
          * Without this check, it's possible to generate a zero length move, as in the case where
159 161
          * the line is heading down, starting exactly on a mesh line boundary. Since this is rare
160 162
          * it might be fine to remove this check and let planner.buffer_segment() filter it out.
161 163
          */
162
-        if (ry != start.y) {
164
+        if (dest.y != start.y) {
163 165
           if (!inf_normalized_flag) { // fall-through faster than branch
164
-            on_axis_distance = use_x_dist ? rx - start.x : ry - start.y;
165
-            e_position = start.e + on_axis_distance * e_normalized_dist;
166
-            z_position = start.z + on_axis_distance * z_normalized_dist;
166
+            on_axis_distance = use_x_dist ? dest.x - start.x : dest.y - start.y;
167
+            TERN_(HAS_EXTRUDERS, dest.e = start.e + on_axis_distance * e_normalized_dist);
168
+            dest.z = start.z + on_axis_distance * z_normalized_dist;
167 169
           }
168 170
           else {
169
-            e_position = end.e;
170
-            z_position = end.z;
171
+            TERN_(HAS_EXTRUDERS, dest.e = end.e);
172
+            dest.z = end.z;
171 173
           }
172 174
 
173
-          planner.buffer_segment(rx, ry, z_position + z0, e_position, scaled_fr_mm_s, extruder);
175
+          dest.z += z0;
176
+          planner.buffer_segment(dest, scaled_fr_mm_s, extruder);
177
+
174 178
         } //else printf("FIRST MOVE PRUNED  ");
175 179
       }
176 180
 
@@ -188,12 +192,13 @@
188 192
      */
189 193
     if (iadd.y == 0) {      // Horizontal line?
190 194
       icell.x += ineg.x;     // Heading left? Just go to the left edge of the cell for the first move.
195
+
191 196
       while (icell.x != iend.x + ineg.x) {
192 197
         icell.x += iadd.x;
193
-        const float rx = mesh_index_to_xpos(icell.x);
194
-        const float ry = ratio * rx + c;    // Calculate Y at the next X mesh line
198
+        dest.x = mesh_index_to_xpos(icell.x);
199
+        dest.y = ratio * dest.x + c;    // Calculate Y at the next X mesh line
195 200
 
196
-        float z0 = z_correction_for_y_on_vertical_mesh_line(ry, icell.x, icell.y)
201
+        float z0 = z_correction_for_y_on_vertical_mesh_line(dest.y, icell.x, icell.y)
197 202
                      * planner.fade_scaling_factor_for_z(end.z);
198 203
 
199 204
         // Undefined parts of the Mesh in z_values[][] are NAN.
@@ -205,19 +210,20 @@
205 210
          * the line is heading left, starting exactly on a mesh line boundary. Since this is rare
206 211
          * it might be fine to remove this check and let planner.buffer_segment() filter it out.
207 212
          */
208
-        if (rx != start.x) {
213
+        if (dest.x != start.x) {
209 214
           if (!inf_normalized_flag) {
210
-            on_axis_distance = use_x_dist ? rx - start.x : ry - start.y;
211
-            e_position = start.e + on_axis_distance * e_normalized_dist;  // is based on X or Y because this is a horizontal move
212
-            z_position = start.z + on_axis_distance * z_normalized_dist;
215
+            on_axis_distance = use_x_dist ? dest.x - start.x : dest.y - start.y;
216
+            TERN_(HAS_EXTRUDERS, dest.e = start.e + on_axis_distance * e_normalized_dist); // Based on X or Y because the move is horizontal
217
+            dest.z = start.z + on_axis_distance * z_normalized_dist;
213 218
           }
214 219
           else {
215
-            e_position = end.e;
216
-            z_position = end.z;
220
+            TERN_(HAS_EXTRUDERS, dest.e = end.e);
221
+            dest.z = end.z;
217 222
           }
218 223
 
219
-          if (!planner.buffer_segment(rx, ry, z_position + z0, e_position, scaled_fr_mm_s, extruder))
220
-            break;
224
+          dest.z += z0;
225
+          if (!planner.buffer_segment(dest, scaled_fr_mm_s, extruder)) break;
226
+
221 227
         } //else printf("FIRST MOVE PRUNED  ");
222 228
       }
223 229
 
@@ -239,57 +245,65 @@
239 245
     while (cnt) {
240 246
 
241 247
       const float next_mesh_line_x = mesh_index_to_xpos(icell.x + iadd.x),
242
-                  next_mesh_line_y = mesh_index_to_ypos(icell.y + iadd.y),
243
-                  ry = ratio * next_mesh_line_x + c,    // Calculate Y at the next X mesh line
244
-                  rx = (next_mesh_line_y - c) / ratio;  // Calculate X at the next Y mesh line
245
-                                                        // (No need to worry about ratio == 0.
246
-                                                        //  In that case, it was already detected
247
-                                                        //  as a vertical line move above.)
248
-
249
-      if (neg.x == (rx > next_mesh_line_x)) { // Check if we hit the Y line first
248
+                  next_mesh_line_y = mesh_index_to_ypos(icell.y + iadd.y);
249
+
250
+      dest.y = ratio * next_mesh_line_x + c;    // Calculate Y at the next X mesh line
251
+      dest.x = (next_mesh_line_y - c) / ratio;  // Calculate X at the next Y mesh line
252
+                                                // (No need to worry about ratio == 0.
253
+                                                //  In that case, it was already detected
254
+                                                //  as a vertical line move above.)
255
+
256
+      if (neg.x == (dest.x > next_mesh_line_x)) { // Check if we hit the Y line first
250 257
         // Yes!  Crossing a Y Mesh Line next
251
-        float z0 = z_correction_for_x_on_horizontal_mesh_line(rx, icell.x - ineg.x, icell.y + iadd.y)
258
+        float z0 = z_correction_for_x_on_horizontal_mesh_line(dest.x, icell.x - ineg.x, icell.y + iadd.y)
252 259
                    * planner.fade_scaling_factor_for_z(end.z);
253 260
 
254 261
         // Undefined parts of the Mesh in z_values[][] are NAN.
255 262
         // Replace NAN corrections with 0.0 to prevent NAN propagation.
256 263
         if (isnan(z0)) z0 = 0.0;
257 264
 
265
+        dest.y = next_mesh_line_y;
266
+
258 267
         if (!inf_normalized_flag) {
259
-          on_axis_distance = use_x_dist ? rx - start.x : next_mesh_line_y - start.y;
260
-          e_position = start.e + on_axis_distance * e_normalized_dist;
261
-          z_position = start.z + on_axis_distance * z_normalized_dist;
268
+          on_axis_distance = use_x_dist ? dest.x - start.x : dest.y - start.y;
269
+          TERN_(HAS_EXTRUDERS, dest.e = start.e + on_axis_distance * e_normalized_dist);
270
+          dest.z = start.z + on_axis_distance * z_normalized_dist;
262 271
         }
263 272
         else {
264
-          e_position = end.e;
265
-          z_position = end.z;
273
+          TERN_(HAS_EXTRUDERS, dest.e = end.e);
274
+          dest.z = end.z;
266 275
         }
267
-        if (!planner.buffer_segment(rx, next_mesh_line_y, z_position + z0, e_position, scaled_fr_mm_s, extruder))
268
-          break;
276
+
277
+        dest.z += z0;
278
+        if (!planner.buffer_segment(dest, scaled_fr_mm_s, extruder)) break;
279
+
269 280
         icell.y += iadd.y;
270 281
         cnt.y--;
271 282
       }
272 283
       else {
273 284
         // Yes!  Crossing a X Mesh Line next
274
-        float z0 = z_correction_for_y_on_vertical_mesh_line(ry, icell.x + iadd.x, icell.y - ineg.y)
285
+        float z0 = z_correction_for_y_on_vertical_mesh_line(dest.y, icell.x + iadd.x, icell.y - ineg.y)
275 286
                    * planner.fade_scaling_factor_for_z(end.z);
276 287
 
277 288
         // Undefined parts of the Mesh in z_values[][] are NAN.
278 289
         // Replace NAN corrections with 0.0 to prevent NAN propagation.
279 290
         if (isnan(z0)) z0 = 0.0;
280 291
 
292
+        dest.x = next_mesh_line_x;
293
+
281 294
         if (!inf_normalized_flag) {
282
-          on_axis_distance = use_x_dist ? next_mesh_line_x - start.x : ry - start.y;
283
-          e_position = start.e + on_axis_distance * e_normalized_dist;
284
-          z_position = start.z + on_axis_distance * z_normalized_dist;
295
+          on_axis_distance = use_x_dist ? dest.x - start.x : dest.y - start.y;
296
+          TERN_(HAS_EXTRUDERS, dest.e = start.e + on_axis_distance * e_normalized_dist);
297
+          dest.z = start.z + on_axis_distance * z_normalized_dist;
285 298
         }
286 299
         else {
287
-          e_position = end.e;
288
-          z_position = end.z;
300
+          TERN_(HAS_EXTRUDERS, dest.e = end.e);
301
+          dest.z = end.z;
289 302
         }
290 303
 
291
-        if (!planner.buffer_segment(next_mesh_line_x, ry, z_position + z0, e_position, scaled_fr_mm_s, extruder))
292
-          break;
304
+        dest.z += z0;
305
+        if (!planner.buffer_segment(dest, scaled_fr_mm_s, extruder)) break;
306
+
293 307
         icell.x += iadd.x;
294 308
         cnt.x--;
295 309
       }
@@ -438,11 +452,9 @@
438 452
           #endif
439 453
         ;
440 454
 
441
-        planner.buffer_line(raw.x, raw.y, raw.z + z_cxcy, raw.e, scaled_fr_mm_s, active_extruder, segment_xyz_mm
442
-          #if ENABLED(SCARA_FEEDRATE_SCALING)
443
-            , inv_duration
444
-          #endif
445
-        );
455
+        const float oldz = raw.z; raw.z += z_cxcy;
456
+        planner.buffer_line(raw, scaled_fr_mm_s, active_extruder, segment_xyz_mm OPTARG(SCARA_FEEDRATE_SCALING, inv_duration) );
457
+        raw.z = oldz;
446 458
 
447 459
         if (segments == 0)                        // done with last segment
448 460
           return false;                           // didn't set current from destination

+ 159
- 118
Marlin/src/feature/tmc_util.cpp View File

@@ -417,6 +417,21 @@
417 417
       }
418 418
       #endif
419 419
 
420
+      #if AXIS_IS_TMC(I)
421
+        if (monitor_tmc_driver(stepperI, need_update_error_counters, need_debug_reporting))
422
+          step_current_down(stepperI);
423
+      #endif
424
+
425
+      #if AXIS_IS_TMC(J)
426
+        if (monitor_tmc_driver(stepperJ, need_update_error_counters, need_debug_reporting))
427
+          step_current_down(stepperJ);
428
+      #endif
429
+
430
+      #if AXIS_IS_TMC(K)
431
+        if (monitor_tmc_driver(stepperK, need_update_error_counters, need_debug_reporting))
432
+          step_current_down(stepperK);
433
+      #endif
434
+
420 435
       #if AXIS_IS_TMC(E0)
421 436
         (void)monitor_tmc_driver(stepperE0, need_update_error_counters, need_debug_reporting);
422 437
       #endif
@@ -757,138 +772,148 @@
757 772
     }
758 773
   }
759 774
 
760
-  static void tmc_debug_loop(
761
-    const TMC_debug_enum i,
762
-    LOGICAL_AXIS_LIST(const bool print_e, const bool print_x, const bool print_y, const bool print_z)
763
-  ) {
764
-    if (print_x) {
775
+  static void tmc_debug_loop(const TMC_debug_enum n, LOGICAL_AXIS_ARGS(const bool)) {
776
+    if (x) {
765 777
       #if AXIS_IS_TMC(X)
766
-        tmc_status(stepperX, i);
778
+        tmc_status(stepperX, n);
767 779
       #endif
768 780
       #if AXIS_IS_TMC(X2)
769
-        tmc_status(stepperX2, i);
781
+        tmc_status(stepperX2, n);
770 782
       #endif
771 783
     }
772 784
 
773
-    #if LINEAR_AXES >= XY
774
-      if (print_y) {
775
-        #if AXIS_IS_TMC(Y)
776
-          tmc_status(stepperY, i);
777
-        #endif
778
-        #if AXIS_IS_TMC(Y2)
779
-          tmc_status(stepperY2, i);
780
-        #endif
781
-      }
782
-    #endif
785
+    if (TERN0(HAS_Y_AXIS, y)) {
786
+      #if AXIS_IS_TMC(Y)
787
+        tmc_status(stepperY, n);
788
+      #endif
789
+      #if AXIS_IS_TMC(Y2)
790
+        tmc_status(stepperY2, n);
791
+      #endif
792
+    }
783 793
 
784
-    if (TERN0(HAS_Z_AXIS, print_z)) {
794
+    if (TERN0(HAS_Z_AXIS, z)) {
785 795
       #if AXIS_IS_TMC(Z)
786
-        tmc_status(stepperZ, i);
796
+        tmc_status(stepperZ, n);
787 797
       #endif
788 798
       #if AXIS_IS_TMC(Z2)
789
-        tmc_status(stepperZ2, i);
799
+        tmc_status(stepperZ2, n);
790 800
       #endif
791 801
       #if AXIS_IS_TMC(Z3)
792
-        tmc_status(stepperZ3, i);
802
+        tmc_status(stepperZ3, n);
793 803
       #endif
794 804
       #if AXIS_IS_TMC(Z4)
795
-        tmc_status(stepperZ4, i);
805
+        tmc_status(stepperZ4, n);
796 806
       #endif
797 807
     }
798 808
 
799
-    if (TERN0(HAS_EXTRUDERS, print_e)) {
809
+    #if AXIS_IS_TMC(I)
810
+      if (i) tmc_status(stepperI, n);
811
+    #endif
812
+    #if AXIS_IS_TMC(J)
813
+      if (j) tmc_status(stepperJ, n);
814
+    #endif
815
+    #if AXIS_IS_TMC(K)
816
+      if (k) tmc_status(stepperK, n);
817
+    #endif
818
+
819
+    if (TERN0(HAS_EXTRUDERS, e)) {
800 820
       #if AXIS_IS_TMC(E0)
801
-        tmc_status(stepperE0, i);
821
+        tmc_status(stepperE0, n);
802 822
       #endif
803 823
       #if AXIS_IS_TMC(E1)
804
-        tmc_status(stepperE1, i);
824
+        tmc_status(stepperE1, n);
805 825
       #endif
806 826
       #if AXIS_IS_TMC(E2)
807
-        tmc_status(stepperE2, i);
827
+        tmc_status(stepperE2, n);
808 828
       #endif
809 829
       #if AXIS_IS_TMC(E3)
810
-        tmc_status(stepperE3, i);
830
+        tmc_status(stepperE3, n);
811 831
       #endif
812 832
       #if AXIS_IS_TMC(E4)
813
-        tmc_status(stepperE4, i);
833
+        tmc_status(stepperE4, n);
814 834
       #endif
815 835
       #if AXIS_IS_TMC(E5)
816
-        tmc_status(stepperE5, i);
836
+        tmc_status(stepperE5, n);
817 837
       #endif
818 838
       #if AXIS_IS_TMC(E6)
819
-        tmc_status(stepperE6, i);
839
+        tmc_status(stepperE6, n);
820 840
       #endif
821 841
       #if AXIS_IS_TMC(E7)
822
-        tmc_status(stepperE7, i);
842
+        tmc_status(stepperE7, n);
823 843
       #endif
824 844
     }
825 845
 
826 846
     SERIAL_EOL();
827 847
   }
828 848
 
829
-  static void drv_status_loop(
830
-    const TMC_drv_status_enum i,
831
-    LOGICAL_AXIS_LIST(const bool print_e, const bool print_x, const bool print_y, const bool print_z)
832
-  ) {
833
-    if (print_x) {
849
+  static void drv_status_loop(const TMC_drv_status_enum n, LOGICAL_AXIS_ARGS(const bool)) {
850
+    if (x) {
834 851
       #if AXIS_IS_TMC(X)
835
-        tmc_parse_drv_status(stepperX, i);
852
+        tmc_parse_drv_status(stepperX, n);
836 853
       #endif
837 854
       #if AXIS_IS_TMC(X2)
838
-        tmc_parse_drv_status(stepperX2, i);
855
+        tmc_parse_drv_status(stepperX2, n);
839 856
       #endif
840 857
     }
841 858
 
842
-    #if LINEAR_AXES >= XY
843
-      if (print_y) {
844
-        #if AXIS_IS_TMC(Y)
845
-          tmc_parse_drv_status(stepperY, i);
846
-        #endif
847
-        #if AXIS_IS_TMC(Y2)
848
-          tmc_parse_drv_status(stepperY2, i);
849
-        #endif
850
-      }
851
-    #endif
859
+    if (TERN0(HAS_Y_AXIS, y)) {
860
+      #if AXIS_IS_TMC(Y)
861
+        tmc_parse_drv_status(stepperY, n);
862
+      #endif
863
+      #if AXIS_IS_TMC(Y2)
864
+        tmc_parse_drv_status(stepperY2, n);
865
+      #endif
866
+    }
852 867
 
853
-    if (TERN0(HAS_Z_AXIS, print_z)) {
868
+    if (TERN0(HAS_Z_AXIS, z)) {
854 869
       #if AXIS_IS_TMC(Z)
855
-        tmc_parse_drv_status(stepperZ, i);
870
+        tmc_parse_drv_status(stepperZ, n);
856 871
       #endif
857 872
       #if AXIS_IS_TMC(Z2)
858
-        tmc_parse_drv_status(stepperZ2, i);
873
+        tmc_parse_drv_status(stepperZ2, n);
859 874
       #endif
860 875
       #if AXIS_IS_TMC(Z3)
861
-        tmc_parse_drv_status(stepperZ3, i);
876
+        tmc_parse_drv_status(stepperZ3, n);
862 877
       #endif
863 878
       #if AXIS_IS_TMC(Z4)
864
-        tmc_parse_drv_status(stepperZ4, i);
879
+        tmc_parse_drv_status(stepperZ4, n);
865 880
       #endif
866 881
     }
867 882
 
868
-    if (TERN0(HAS_EXTRUDERS, print_e)) {
883
+    #if AXIS_IS_TMC(I)
884
+      if (i) tmc_parse_drv_status(stepperI, n);
885
+    #endif
886
+    #if AXIS_IS_TMC(J)
887
+      if (j) tmc_parse_drv_status(stepperJ, n);
888
+    #endif
889
+    #if AXIS_IS_TMC(K)
890
+      if (k) tmc_parse_drv_status(stepperK, n);
891
+    #endif
892
+
893
+    if (TERN0(HAS_EXTRUDERS, e)) {
869 894
       #if AXIS_IS_TMC(E0)
870
-        tmc_parse_drv_status(stepperE0, i);
895
+        tmc_parse_drv_status(stepperE0, n);
871 896
       #endif
872 897
       #if AXIS_IS_TMC(E1)
873
-        tmc_parse_drv_status(stepperE1, i);
898
+        tmc_parse_drv_status(stepperE1, n);
874 899
       #endif
875 900
       #if AXIS_IS_TMC(E2)
876
-        tmc_parse_drv_status(stepperE2, i);
901
+        tmc_parse_drv_status(stepperE2, n);
877 902
       #endif
878 903
       #if AXIS_IS_TMC(E3)
879
-        tmc_parse_drv_status(stepperE3, i);
904
+        tmc_parse_drv_status(stepperE3, n);
880 905
       #endif
881 906
       #if AXIS_IS_TMC(E4)
882
-        tmc_parse_drv_status(stepperE4, i);
907
+        tmc_parse_drv_status(stepperE4, n);
883 908
       #endif
884 909
       #if AXIS_IS_TMC(E5)
885
-        tmc_parse_drv_status(stepperE5, i);
910
+        tmc_parse_drv_status(stepperE5, n);
886 911
       #endif
887 912
       #if AXIS_IS_TMC(E6)
888
-        tmc_parse_drv_status(stepperE6, i);
913
+        tmc_parse_drv_status(stepperE6, n);
889 914
       #endif
890 915
       #if AXIS_IS_TMC(E7)
891
-        tmc_parse_drv_status(stepperE7, i);
916
+        tmc_parse_drv_status(stepperE7, n);
892 917
       #endif
893 918
     }
894 919
 
@@ -899,11 +924,9 @@
899 924
    * M122 report functions
900 925
    */
901 926
 
902
-  void tmc_report_all(
903
-    LOGICAL_AXIS_LIST(const bool print_e/*=true*/, const bool print_x/*=true*/, const bool print_y/*=true*/, const bool print_z/*=true*/)
904
-  ) {
905
-    #define TMC_REPORT(LABEL, ITEM) do{ SERIAL_ECHOPGM(LABEL);  tmc_debug_loop(ITEM, LOGICAL_AXIS_LIST(print_e, print_x, print_y, print_z)); }while(0)
906
-    #define DRV_REPORT(LABEL, ITEM) do{ SERIAL_ECHOPGM(LABEL); drv_status_loop(ITEM, LOGICAL_AXIS_LIST(print_e, print_x, print_y, print_z)); }while(0)
927
+  void tmc_report_all(LOGICAL_AXIS_ARGS(const bool)) {
928
+    #define TMC_REPORT(LABEL, ITEM) do{ SERIAL_ECHOPGM(LABEL); tmc_debug_loop(ITEM, LOGICAL_AXIS_ARGS()); }while(0)
929
+    #define DRV_REPORT(LABEL, ITEM) do{ SERIAL_ECHOPGM(LABEL); drv_status_loop(ITEM, LOGICAL_AXIS_ARGS()); }while(0)
907 930
 
908 931
     TMC_REPORT("\t",                 TMC_CODES);
909 932
     #if HAS_DRIVER(TMC2209)
@@ -1028,79 +1051,82 @@
1028 1051
     }
1029 1052
   #endif
1030 1053
 
1031
-  static void tmc_get_registers(
1032
-    TMC_get_registers_enum i,
1033
-    LOGICAL_AXIS_LIST(const bool print_e, const bool print_x, const bool print_y, const bool print_z)
1034
-  ) {
1035
-    if (print_x) {
1054
+  static void tmc_get_registers(TMC_get_registers_enum n, LOGICAL_AXIS_ARGS(const bool)) {
1055
+    if (x) {
1036 1056
       #if AXIS_IS_TMC(X)
1037
-        tmc_get_registers(stepperX, i);
1057
+        tmc_get_registers(stepperX, n);
1038 1058
       #endif
1039 1059
       #if AXIS_IS_TMC(X2)
1040
-        tmc_get_registers(stepperX2, i);
1060
+        tmc_get_registers(stepperX2, n);
1041 1061
       #endif
1042 1062
     }
1043 1063
 
1044
-    #if LINEAR_AXES >= XY
1045
-      if (print_y) {
1046
-        #if AXIS_IS_TMC(Y)
1047
-          tmc_get_registers(stepperY, i);
1048
-        #endif
1049
-        #if AXIS_IS_TMC(Y2)
1050
-          tmc_get_registers(stepperY2, i);
1051
-        #endif
1052
-      }
1053
-    #endif
1064
+    if (TERN0(HAS_Y_AXIS, y)) {
1065
+      #if AXIS_IS_TMC(Y)
1066
+        tmc_get_registers(stepperY, n);
1067
+      #endif
1068
+      #if AXIS_IS_TMC(Y2)
1069
+        tmc_get_registers(stepperY2, n);
1070
+      #endif
1071
+    }
1054 1072
 
1055
-    if (TERN0(HAS_Z_AXIS, print_z)) {
1073
+    if (TERN0(HAS_Z_AXIS, z)) {
1056 1074
       #if AXIS_IS_TMC(Z)
1057
-        tmc_get_registers(stepperZ, i);
1075
+        tmc_get_registers(stepperZ, n);
1058 1076
       #endif
1059 1077
       #if AXIS_IS_TMC(Z2)
1060
-        tmc_get_registers(stepperZ2, i);
1078
+        tmc_get_registers(stepperZ2, n);
1061 1079
       #endif
1062 1080
       #if AXIS_IS_TMC(Z3)
1063
-        tmc_get_registers(stepperZ3, i);
1081
+        tmc_get_registers(stepperZ3, n);
1064 1082
       #endif
1065 1083
       #if AXIS_IS_TMC(Z4)
1066
-        tmc_get_registers(stepperZ4, i);
1084
+        tmc_get_registers(stepperZ4, n);
1067 1085
       #endif
1068 1086
     }
1069 1087
 
1070
-    if (TERN0(HAS_EXTRUDERS, print_e)) {
1088
+    #if AXIS_IS_TMC(I)
1089
+      if (i) tmc_get_registers(stepperI, n);
1090
+    #endif
1091
+    #if AXIS_IS_TMC(J)
1092
+      if (j) tmc_get_registers(stepperJ, n);
1093
+    #endif
1094
+    #if AXIS_IS_TMC(K)
1095
+      if (k) tmc_get_registers(stepperK, n);
1096
+    #endif
1097
+
1098
+    if (TERN0(HAS_EXTRUDERS, e)) {
1071 1099
       #if AXIS_IS_TMC(E0)
1072
-        tmc_get_registers(stepperE0, i);
1100
+        tmc_get_registers(stepperE0, n);
1073 1101
       #endif
1074 1102
       #if AXIS_IS_TMC(E1)
1075
-        tmc_get_registers(stepperE1, i);
1103
+        tmc_get_registers(stepperE1, n);
1076 1104
       #endif
1077 1105
       #if AXIS_IS_TMC(E2)
1078
-        tmc_get_registers(stepperE2, i);
1106
+        tmc_get_registers(stepperE2, n);
1079 1107
       #endif
1080 1108
       #if AXIS_IS_TMC(E3)
1081
-        tmc_get_registers(stepperE3, i);
1109
+        tmc_get_registers(stepperE3, n);
1082 1110
       #endif
1083 1111
       #if AXIS_IS_TMC(E4)
1084
-        tmc_get_registers(stepperE4, i);
1112
+        tmc_get_registers(stepperE4, n);
1085 1113
       #endif
1086 1114
       #if AXIS_IS_TMC(E5)
1087
-        tmc_get_registers(stepperE5, i);
1115
+        tmc_get_registers(stepperE5, n);
1088 1116
       #endif
1089 1117
       #if AXIS_IS_TMC(E6)
1090
-        tmc_get_registers(stepperE6, i);
1118
+        tmc_get_registers(stepperE6, n);
1091 1119
       #endif
1092 1120
       #if AXIS_IS_TMC(E7)
1093
-        tmc_get_registers(stepperE7, i);
1121
+        tmc_get_registers(stepperE7, n);
1094 1122
       #endif
1095 1123
     }
1096 1124
 
1097 1125
     SERIAL_EOL();
1098 1126
   }
1099 1127
 
1100
-  void tmc_get_registers(
1101
-    LOGICAL_AXIS_LIST(bool print_e, bool print_x, bool print_y, bool print_z)
1102
-  ) {
1103
-    #define _TMC_GET_REG(LABEL, ITEM) do{ SERIAL_ECHOPGM(LABEL); tmc_get_registers(ITEM, LOGICAL_AXIS_LIST(print_e, print_x, print_y, print_z)); }while(0)
1128
+  void tmc_get_registers(LOGICAL_AXIS_ARGS(bool)) {
1129
+    #define _TMC_GET_REG(LABEL, ITEM) do{ SERIAL_ECHOPGM(LABEL); tmc_get_registers(ITEM, LOGICAL_AXIS_ARGS()); }while(0)
1104 1130
     #define TMC_GET_REG(NAME, TABS) _TMC_GET_REG(STRINGIFY(NAME) TABS, TMC_GET_##NAME)
1105 1131
     _TMC_GET_REG("\t", TMC_AXIS_CODES);
1106 1132
     TMC_GET_REG(GCONF, "\t\t");
@@ -1185,6 +1211,15 @@
1185 1211
     #if AXIS_HAS_SPI(Z4)
1186 1212
       SET_CS_PIN(Z4);
1187 1213
     #endif
1214
+    #if AXIS_HAS_SPI(I)
1215
+      SET_CS_PIN(I);
1216
+    #endif
1217
+    #if AXIS_HAS_SPI(J)
1218
+      SET_CS_PIN(J);
1219
+    #endif
1220
+    #if AXIS_HAS_SPI(K)
1221
+      SET_CS_PIN(K);
1222
+    #endif
1188 1223
     #if AXIS_HAS_SPI(E0)
1189 1224
       SET_CS_PIN(E0);
1190 1225
     #endif
@@ -1234,12 +1269,10 @@ static bool test_connection(TMC &st) {
1234 1269
   return test_result;
1235 1270
 }
1236 1271
 
1237
-void test_tmc_connection(
1238
-  LOGICAL_AXIS_LIST(const bool test_e/*=true*/, const bool test_x/*=true*/, const bool test_y/*=true*/, const bool test_z/*=true*/)
1239
-) {
1272
+void test_tmc_connection(LOGICAL_AXIS_ARGS(const bool)) {
1240 1273
   uint8_t axis_connection = 0;
1241 1274
 
1242
-  if (test_x) {
1275
+  if (x) {
1243 1276
     #if AXIS_IS_TMC(X)
1244 1277
       axis_connection += test_connection(stepperX);
1245 1278
     #endif
@@ -1248,18 +1281,16 @@ void test_tmc_connection(
1248 1281
     #endif
1249 1282
   }
1250 1283
 
1251
-  #if LINEAR_AXES >= XY
1252
-    if (test_y) {
1253
-      #if AXIS_IS_TMC(Y)
1254
-        axis_connection += test_connection(stepperY);
1255
-      #endif
1256
-      #if AXIS_IS_TMC(Y2)
1257
-        axis_connection += test_connection(stepperY2);
1258
-      #endif
1259
-    }
1260
-  #endif
1284
+  if (TERN0(HAS_Y_AXIS, y)) {
1285
+    #if AXIS_IS_TMC(Y)
1286
+      axis_connection += test_connection(stepperY);
1287
+    #endif
1288
+    #if AXIS_IS_TMC(Y2)
1289
+      axis_connection += test_connection(stepperY2);
1290
+    #endif
1291
+  }
1261 1292
 
1262
-  if (TERN0(HAS_Z_AXIS, test_z)) {
1293
+  if (TERN0(HAS_Z_AXIS, z)) {
1263 1294
     #if AXIS_IS_TMC(Z)
1264 1295
       axis_connection += test_connection(stepperZ);
1265 1296
     #endif
@@ -1274,7 +1305,17 @@ void test_tmc_connection(
1274 1305
     #endif
1275 1306
   }
1276 1307
 
1277
-  if (TERN0(HAS_EXTRUDERS, test_e)) {
1308
+  #if AXIS_IS_TMC(I)
1309
+    if (i) axis_connection += test_connection(stepperI);
1310
+  #endif
1311
+  #if AXIS_IS_TMC(J)
1312
+    if (j) axis_connection += test_connection(stepperJ);
1313
+  #endif
1314
+  #if AXIS_IS_TMC(K)
1315
+    if (k) axis_connection += test_connection(stepperK);
1316
+  #endif
1317
+
1318
+  if (TERN0(HAS_EXTRUDERS, e)) {
1278 1319
     #if AXIS_IS_TMC(E0)
1279 1320
       axis_connection += test_connection(stepperE0);
1280 1321
     #endif

+ 4
- 10
Marlin/src/feature/tmc_util.h View File

@@ -335,20 +335,14 @@ void tmc_print_current(TMC &st) {
335 335
 #endif
336 336
 
337 337
 void monitor_tmc_drivers();
338
-void test_tmc_connection(
339
-  LOGICAL_AXIS_LIST(const bool test_e=true, const bool test_x=true, const bool test_y=true, const bool test_z=true)
340
-);
338
+void test_tmc_connection(LOGICAL_AXIS_DECL(const bool, true));
341 339
 
342 340
 #if ENABLED(TMC_DEBUG)
343 341
   #if ENABLED(MONITOR_DRIVER_STATUS)
344 342
     void tmc_set_report_interval(const uint16_t update_interval);
345 343
   #endif
346
-  void tmc_report_all(
347
-    LOGICAL_AXIS_LIST(const bool print_e=true, const bool print_x=true, const bool print_y=true, const bool print_z=true)
348
-  );
349
-  void tmc_get_registers(
350
-    LOGICAL_AXIS_LIST(const bool print_e, const bool print_x, const bool print_y, const bool print_z)
351
-  );
344
+  void tmc_report_all(LOGICAL_AXIS_DECL(const bool, true));
345
+  void tmc_get_registers(LOGICAL_AXIS_ARGS(const bool));
352 346
 #endif
353 347
 
354 348
 /**
@@ -361,7 +355,7 @@ void test_tmc_connection(
361 355
 #if USE_SENSORLESS
362 356
 
363 357
   // Track enabled status of stealthChop and only re-enable where applicable
364
-  struct sensorless_t { bool LINEAR_AXIS_LIST(x, y, z), x2, y2, z2, z3, z4; };
358
+  struct sensorless_t { bool LINEAR_AXIS_ARGS(), x2, y2, z2, z3, z4; };
365 359
 
366 360
   #if ENABLED(IMPROVE_HOMING_RELIABILITY)
367 361
     extern millis_t sg_guard_period;

+ 2
- 2
Marlin/src/gcode/bedlevel/abl/G29.cpp View File

@@ -689,7 +689,7 @@ G29_TYPE GcodeSuite::G29() {
689 689
         TERN_(HAS_STATUS_MESSAGE, ui.status_printf_P(0, PSTR(S_FMT " %i/3"), GET_TEXT(MSG_PROBING_MESH), int(i + 1)));
690 690
 
691 691
         // Retain the last probe position
692
-        abl.probePos = points[i];
692
+        abl.probePos = xy_pos_t(points[i]);
693 693
         abl.measured_z = faux ? 0.001 * random(-100, 101) : probe.probe_at_point(abl.probePos, raise_after, abl.verbose_level);
694 694
         if (isnan(abl.measured_z)) {
695 695
           set_bed_leveling_enabled(abl.reenable);
@@ -795,7 +795,7 @@ G29_TYPE GcodeSuite::G29() {
795 795
               const int ind = abl.indexIntoAB[xx][yy];
796 796
               xyz_float_t tmp = { abl.eqnAMatrix[ind + 0 * abl.abl_points],
797 797
                                   abl.eqnAMatrix[ind + 1 * abl.abl_points], 0 };
798
-              planner.bed_level_matrix.apply_rotation_xyz(tmp);
798
+              planner.bed_level_matrix.apply_rotation_xyz(tmp.x, tmp.y, tmp.z);
799 799
               if (get_min) NOMORE(min_diff, abl.eqnBVector[ind] - tmp.z);
800 800
               const float subval = get_min ? abl.mean : tmp.z + min_diff,
801 801
                             diff = abl.eqnBVector[ind] - subval;

+ 48
- 25
Marlin/src/gcode/calibrate/G28.cpp View File

@@ -323,42 +323,44 @@ void GcodeSuite::G28() {
323 323
 
324 324
     #define _UNSAFE(A) (homeZ && TERN0(Z_SAFE_HOMING, axes_should_home(_BV(A##_AXIS))))
325 325
 
326
-    const bool homeZ = parser.seen_test('Z'),
327
-               LINEAR_AXIS_LIST( // Other axes should be homed before Z safe-homing
328
-                 needX = _UNSAFE(X), needY = _UNSAFE(Y), needZ = false // UNUSED
326
+    const bool homeZ = TERN0(HAS_Z_AXIS, parser.seen_test('Z')),
327
+               LINEAR_AXIS_LIST(              // Other axes should be homed before Z safe-homing
328
+                 needX = _UNSAFE(X), needY = _UNSAFE(Y), needZ = false, // UNUSED
329
+                 needI = _UNSAFE(I), needJ = _UNSAFE(J), needK = _UNSAFE(K)
329 330
                ),
330
-               LINEAR_AXIS_LIST( // Home each axis if needed or flagged
331
+               LINEAR_AXIS_LIST(              // Home each axis if needed or flagged
331 332
                  homeX = needX || parser.seen_test('X'),
332 333
                  homeY = needY || parser.seen_test('Y'),
333
-                 homeZZ = homeZ // UNUSED
334
+                 homeZZ = homeZ,
335
+                 homeI = needI || parser.seen_test(AXIS4_NAME), homeJ = needJ || parser.seen_test(AXIS5_NAME), homeK = needK || parser.seen_test(AXIS6_NAME),
334 336
                ),
335
-               // Home-all if all or none are flagged
336
-               home_all = true LINEAR_AXIS_GANG(&& homeX == homeX, && homeX == homeY, && homeX == homeZ),
337
-               LINEAR_AXIS_LIST(doX = home_all || homeX, doY = home_all || homeY, doZ = home_all || homeZ);
338
-
339
-   UNUSED(needZ);
340
-   UNUSED(homeZZ);
341
-
342
-    #if ENABLED(HOME_Z_FIRST)
343
-
344
-      if (doZ) homeaxis(Z_AXIS);
337
+               home_all = LINEAR_AXIS_GANG(   // Home-all if all or none are flagged
338
+                    homeX == homeX, && homeY == homeX, && homeZ == homeX,
339
+                 && homeI == homeX, && homeJ == homeX, && homeK == homeX
340
+               ),
341
+               LINEAR_AXIS_LIST(
342
+                 doX = home_all || homeX, doY = home_all || homeY, doZ = home_all || homeZ,
343
+                 doI = home_all || homeI, doJ = home_all || homeJ, doK = home_all || homeK
344
+               );
345 345
 
346
+    #if HAS_Z_AXIS
347
+      UNUSED(needZ); UNUSED(homeZZ);
348
+    #else
349
+      constexpr bool doZ = false;
346 350
     #endif
347 351
 
352
+    TERN_(HOME_Z_FIRST, if (doZ) homeaxis(Z_AXIS));
353
+
348 354
     const float z_homing_height = parser.seenval('R') ? parser.value_linear_units() : Z_HOMING_HEIGHT;
349 355
 
350
-    if (z_homing_height && (0 LINEAR_AXIS_GANG(|| doX, || doY, || TERN0(Z_SAFE_HOMING, doZ)))) {
356
+    if (z_homing_height && (0 LINEAR_AXIS_GANG(|| doX, || doY, || TERN0(Z_SAFE_HOMING, doZ), || doI, || doJ, || doK))) {
351 357
       // Raise Z before homing any other axes and z is not already high enough (never lower z)
352 358
       if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("Raise Z (before homing) by ", z_homing_height);
353 359
       do_z_clearance(z_homing_height);
354 360
       TERN_(BLTOUCH, bltouch.init());
355 361
     }
356 362
 
357
-    #if ENABLED(QUICK_HOME)
358
-
359
-      if (doX && doY) quick_home_xy();
360
-
361
-    #endif
363
+    TERN_(QUICK_HOME, if (doX && doY) quick_home_xy());
362 364
 
363 365
     // Home Y (before X)
364 366
     if (ENABLED(HOME_Y_BEFORE_X) && (doY || TERN0(CODEPENDENT_XY_HOMING, doX)))
@@ -397,7 +399,7 @@ void GcodeSuite::G28() {
397 399
     TERN_(IMPROVE_HOMING_RELIABILITY, end_slow_homing(slow_homing));
398 400
 
399 401
     // Home Z last if homing towards the bed
400
-    #if DISABLED(HOME_Z_FIRST)
402
+    #if HAS_Z_AXIS && DISABLED(HOME_Z_FIRST)
401 403
       if (doZ) {
402 404
         #if EITHER(Z_MULTI_ENDSTOPS, Z_STEPPER_AUTO_ALIGN)
403 405
           stepper.set_all_z_lock(false);
@@ -409,6 +411,16 @@ void GcodeSuite::G28() {
409 411
       }
410 412
     #endif
411 413
 
414
+    #if LINEAR_AXES >= 4
415
+      if (doI) homeaxis(I_AXIS);
416
+    #endif
417
+    #if LINEAR_AXES >= 5
418
+      if (doJ) homeaxis(J_AXIS);
419
+    #endif
420
+    #if LINEAR_AXES >= 6
421
+      if (doK) homeaxis(K_AXIS);
422
+    #endif
423
+
412 424
     sync_plan_position();
413 425
 
414 426
   #endif
@@ -480,6 +492,15 @@ void GcodeSuite::G28() {
480 492
     #if HAS_CURRENT_HOME(Y2)
481 493
       stepperY2.rms_current(tmc_save_current_Y2);
482 494
     #endif
495
+    #if HAS_CURRENT_HOME(I)
496
+      stepperI.rms_current(tmc_save_current_I);
497
+    #endif
498
+    #if HAS_CURRENT_HOME(J)
499
+      stepperJ.rms_current(tmc_save_current_J);
500
+    #endif
501
+    #if HAS_CURRENT_HOME(K)
502
+      stepperK.rms_current(tmc_save_current_K);
503
+    #endif
483 504
   #endif // HAS_HOMING_CURRENT
484 505
 
485 506
   ui.refresh();
@@ -498,11 +519,13 @@ void GcodeSuite::G28() {
498 519
     // Set L6470 absolute position registers to counts
499 520
     // constexpr *might* move this to PROGMEM.
500 521
     // If not, this will need a PROGMEM directive and an accessor.
522
+    #define _EN_ITEM(N) , E_AXIS
501 523
     static constexpr AxisEnum L64XX_axis_xref[MAX_L64XX] = {
502
-      X_AXIS, Y_AXIS, Z_AXIS,
503
-      X_AXIS, Y_AXIS, Z_AXIS, Z_AXIS,
504
-      E_AXIS, E_AXIS, E_AXIS, E_AXIS, E_AXIS, E_AXIS, E_AXIS, E_AXIS
524
+      LINEAR_AXIS_LIST(X_AXIS, Y_AXIS, Z_AXIS, I_AXIS, J_AXIS, K_AXIS),
525
+      X_AXIS, Y_AXIS, Z_AXIS, Z_AXIS, Z_AXIS
526
+      REPEAT(E_STEPPERS, _EN_ITEM)
505 527
     };
528
+    #undef _EN_ITEM
506 529
     for (uint8_t j = 1; j <= L64XX::chain[0]; j++) {
507 530
       const uint8_t cv = L64XX::chain[j];
508 531
       L64xxManager.set_param((L64XX_axis_t)cv, L6470_ABS_POS, stepper.position(L64XX_axis_xref[cv]));

+ 175
- 46
Marlin/src/gcode/calibrate/G425.cpp View File

@@ -73,11 +73,23 @@
73 73
 #if BOTH(CALIBRATION_MEASURE_LEFT, CALIBRATION_MEASURE_RIGHT)
74 74
   #define HAS_X_CENTER 1
75 75
 #endif
76
-#if BOTH(CALIBRATION_MEASURE_FRONT, CALIBRATION_MEASURE_BACK)
76
+#if HAS_Y_AXIS && BOTH(CALIBRATION_MEASURE_FRONT, CALIBRATION_MEASURE_BACK)
77 77
   #define HAS_Y_CENTER 1
78 78
 #endif
79
+#if LINEAR_AXES >= 4 && BOTH(CALIBRATION_MEASURE_IMIN, CALIBRATION_MEASURE_IMAX)
80
+  #define HAS_I_CENTER 1
81
+#endif
82
+#if LINEAR_AXES >= 5 && BOTH(CALIBRATION_MEASURE_JMIN, CALIBRATION_MEASURE_JMAX)
83
+  #define HAS_J_CENTER 1
84
+#endif
85
+#if LINEAR_AXES >= 6 && BOTH(CALIBRATION_MEASURE_KMIN, CALIBRATION_MEASURE_KMAX)
86
+  #define HAS_K_CENTER 1
87
+#endif
79 88
 
80
-enum side_t : uint8_t { TOP, RIGHT, FRONT, LEFT, BACK, NUM_SIDES };
89
+enum side_t : uint8_t {
90
+  TOP, RIGHT, FRONT, LEFT, BACK, NUM_SIDES,
91
+  LIST_N(DOUBLE(SUB3(LINEAR_AXES)), IMINIMUM, IMAXIMUM, JMINIMUM, JMAXIMUM, KMINIMUM, KMAXIMUM)
92
+};
81 93
 
82 94
 static constexpr xyz_pos_t true_center CALIBRATION_OBJECT_CENTER;
83 95
 static constexpr xyz_float_t dimensions CALIBRATION_OBJECT_DIMENSIONS;
@@ -105,7 +117,7 @@ struct measurements_t {
105 117
 #endif
106 118
 
107 119
 inline void calibration_move() {
108
-  do_blocking_move_to(current_position, MMM_TO_MMS(CALIBRATION_FEEDRATE_TRAVEL));
120
+  do_blocking_move_to((xyz_pos_t)current_position, MMM_TO_MMS(CALIBRATION_FEEDRATE_TRAVEL));
109 121
 }
110 122
 
111 123
 /**
@@ -174,7 +186,7 @@ float measuring_movement(const AxisEnum axis, const int dir, const bool stop_sta
174 186
   destination = current_position;
175 187
   for (float travel = 0; travel < limit; travel += step) {
176 188
     destination[axis] += dir * step;
177
-    do_blocking_move_to(destination, mms);
189
+    do_blocking_move_to((xyz_pos_t)destination, mms);
178 190
     planner.synchronize();
179 191
     if (read_calibration_pin() == stop_state) break;
180 192
   }
@@ -209,7 +221,7 @@ inline float measure(const AxisEnum axis, const int dir, const bool stop_state,
209 221
   // Move back to the starting position
210 222
   destination = current_position;
211 223
   destination[axis] = start_pos;
212
-  do_blocking_move_to(destination, MMM_TO_MMS(CALIBRATION_FEEDRATE_TRAVEL));
224
+  do_blocking_move_to((xyz_pos_t)destination, MMM_TO_MMS(CALIBRATION_FEEDRATE_TRAVEL));
213 225
   return measured_pos;
214 226
 }
215 227
 
@@ -230,7 +242,15 @@ inline void probe_side(measurements_t &m, const float uncertainty, const side_t
230 242
   park_above_object(m, uncertainty);
231 243
 
232 244
   switch (side) {
233
-    #if AXIS_CAN_CALIBRATE(Z)
245
+    #if AXIS_CAN_CALIBRATE(X)
246
+      case RIGHT: dir = -1;
247
+      case LEFT:  axis = X_AXIS; break;
248
+    #endif
249
+    #if LINEAR_AXES >= 2 && AXIS_CAN_CALIBRATE(Y)
250
+      case BACK:  dir = -1;
251
+      case FRONT: axis = Y_AXIS; break;
252
+    #endif
253
+    #if HAS_Z_AXIS && AXIS_CAN_CALIBRATE(Z)
234 254
       case TOP: {
235 255
         const float measurement = measure(Z_AXIS, -1, true, &m.backlash[TOP], uncertainty);
236 256
         m.obj_center.z = measurement - dimensions.z / 2;
@@ -238,13 +258,17 @@ inline void probe_side(measurements_t &m, const float uncertainty, const side_t
238 258
         return;
239 259
       }
240 260
     #endif
241
-    #if AXIS_CAN_CALIBRATE(X)
242
-      case RIGHT: dir = -1;
243
-      case LEFT:  axis = X_AXIS; break;
261
+    #if LINEAR_AXES >= 4 && AXIS_CAN_CALIBRATE(I)
262
+      case IMINIMUM: dir = -1;
263
+      case IMAXIMUM: axis = I_AXIS; break;
244 264
     #endif
245
-    #if AXIS_CAN_CALIBRATE(Y)
246
-      case BACK:  dir = -1;
247
-      case FRONT: axis = Y_AXIS; break;
265
+    #if LINEAR_AXES >= 5 && AXIS_CAN_CALIBRATE(J)
266
+      case JMINIMUM: dir = -1;
267
+      case JMAXIMUM: axis = J_AXIS; break;
268
+    #endif
269
+    #if LINEAR_AXES >= 6 && AXIS_CAN_CALIBRATE(K)
270
+      case KMINIMUM: dir = -1;
271
+      case KMAXIMUM: axis = K_AXIS; break;
248 272
     #endif
249 273
     default: return;
250 274
   }
@@ -289,14 +313,23 @@ inline void probe_sides(measurements_t &m, const float uncertainty) {
289 313
     probe_side(m, uncertainty, TOP);
290 314
   #endif
291 315
 
292
-  TERN_(CALIBRATION_MEASURE_RIGHT, probe_side(m, uncertainty, RIGHT, probe_top_at_edge));
293
-  TERN_(CALIBRATION_MEASURE_FRONT, probe_side(m, uncertainty, FRONT, probe_top_at_edge));
294
-  TERN_(CALIBRATION_MEASURE_LEFT,  probe_side(m, uncertainty, LEFT,  probe_top_at_edge));
295
-  TERN_(CALIBRATION_MEASURE_BACK,  probe_side(m, uncertainty, BACK,  probe_top_at_edge));
316
+  TERN_(CALIBRATION_MEASURE_RIGHT, probe_side(m, uncertainty, RIGHT,    probe_top_at_edge));
317
+  TERN_(CALIBRATION_MEASURE_FRONT, probe_side(m, uncertainty, FRONT,    probe_top_at_edge));
318
+  TERN_(CALIBRATION_MEASURE_LEFT,  probe_side(m, uncertainty, LEFT,     probe_top_at_edge));
319
+  TERN_(CALIBRATION_MEASURE_BACK,  probe_side(m, uncertainty, BACK,     probe_top_at_edge));
320
+  TERN_(CALIBRATION_MEASURE_IMIN,  probe_side(m, uncertainty, IMINIMUM, probe_top_at_edge));
321
+  TERN_(CALIBRATION_MEASURE_IMAX,  probe_side(m, uncertainty, IMAXIMUM, probe_top_at_edge));
322
+  TERN_(CALIBRATION_MEASURE_JMIN,  probe_side(m, uncertainty, JMINIMUM, probe_top_at_edge));
323
+  TERN_(CALIBRATION_MEASURE_JMAX,  probe_side(m, uncertainty, JMAXIMUM, probe_top_at_edge));
324
+  TERN_(CALIBRATION_MEASURE_KMIN,  probe_side(m, uncertainty, KMINIMUM, probe_top_at_edge));
325
+  TERN_(CALIBRATION_MEASURE_KMAX,  probe_side(m, uncertainty, KMAXIMUM, probe_top_at_edge));
296 326
 
297 327
   // Compute the measured center of the calibration object.
298
-  TERN_(HAS_X_CENTER, m.obj_center.x = (m.obj_side[LEFT] + m.obj_side[RIGHT]) / 2);
299
-  TERN_(HAS_Y_CENTER, m.obj_center.y = (m.obj_side[FRONT] + m.obj_side[BACK]) / 2);
328
+  TERN_(HAS_X_CENTER, m.obj_center.x = (m.obj_side[LEFT]     + m.obj_side[RIGHT])    / 2);
329
+  TERN_(HAS_Y_CENTER, m.obj_center.y = (m.obj_side[FRONT]    + m.obj_side[BACK])     / 2);
330
+  TERN_(HAS_I_CENTER, m.obj_center.i = (m.obj_side[IMINIMUM] + m.obj_side[IMAXIMUM]) / 2);
331
+  TERN_(HAS_J_CENTER, m.obj_center.j = (m.obj_side[JMINIMUM] + m.obj_side[JMAXIMUM]) / 2);
332
+  TERN_(HAS_K_CENTER, m.obj_center.k = (m.obj_side[KMINIMUM] + m.obj_side[KMAXIMUM]) / 2);
300 333
 
301 334
   // Compute the outside diameter of the nozzle at the height
302 335
   // at which it makes contact with the calibration object
@@ -310,14 +343,17 @@ inline void probe_sides(measurements_t &m, const float uncertainty) {
310 343
   LINEAR_AXIS_CODE(
311 344
     m.pos_error.x = TERN0(HAS_X_CENTER, true_center.x - m.obj_center.x),
312 345
     m.pos_error.y = TERN0(HAS_Y_CENTER, true_center.y - m.obj_center.y),
313
-    m.pos_error.z = true_center.z - m.obj_center.z
346
+    m.pos_error.z = true_center.z - m.obj_center.z,
347
+    m.pos_error.i = TERN0(HAS_I_CENTER, true_center.i - m.obj_center.i),
348
+    m.pos_error.j = TERN0(HAS_J_CENTER, true_center.j - m.obj_center.j),
349
+    m.pos_error.k = TERN0(HAS_K_CENTER, true_center.k - m.obj_center.k)
314 350
   );
315 351
 }
316 352
 
317 353
 #if ENABLED(CALIBRATION_REPORTING)
318 354
   inline void report_measured_faces(const measurements_t &m) {
319 355
     SERIAL_ECHOLNPGM("Sides:");
320
-    #if AXIS_CAN_CALIBRATE(Z)
356
+    #if HAS_Z_AXIS && AXIS_CAN_CALIBRATE(Z)
321 357
       SERIAL_ECHOLNPAIR("  Top: ", m.obj_side[TOP]);
322 358
     #endif
323 359
     #if ENABLED(CALIBRATION_MEASURE_LEFT)
@@ -326,11 +362,37 @@ inline void probe_sides(measurements_t &m, const float uncertainty) {
326 362
     #if ENABLED(CALIBRATION_MEASURE_RIGHT)
327 363
       SERIAL_ECHOLNPAIR("  Right: ", m.obj_side[RIGHT]);
328 364
     #endif
329
-    #if ENABLED(CALIBRATION_MEASURE_FRONT)
330
-      SERIAL_ECHOLNPAIR("  Front: ", m.obj_side[FRONT]);
365
+    #if HAS_Y_AXIS
366
+      #if ENABLED(CALIBRATION_MEASURE_FRONT)
367
+        SERIAL_ECHOLNPAIR("  Front: ", m.obj_side[FRONT]);
368
+      #endif
369
+      #if ENABLED(CALIBRATION_MEASURE_BACK)
370
+        SERIAL_ECHOLNPAIR("  Back: ", m.obj_side[BACK]);
371
+      #endif
331 372
     #endif
332
-    #if ENABLED(CALIBRATION_MEASURE_BACK)
333
-      SERIAL_ECHOLNPAIR("  Back: ", m.obj_side[BACK]);
373
+    #if LINEAR_AXES >= 4
374
+      #if ENABLED(CALIBRATION_MEASURE_IMIN)
375
+        SERIAL_ECHOLNPAIR("  " STR_I_MIN ": ", m.obj_side[IMINIMUM]);
376
+      #endif
377
+      #if ENABLED(CALIBRATION_MEASURE_IMAX)
378
+        SERIAL_ECHOLNPAIR("  " STR_I_MAX ": ", m.obj_side[IMAXIMUM]);
379
+      #endif
380
+    #endif
381
+    #if LINEAR_AXES >= 5
382
+      #if ENABLED(CALIBRATION_MEASURE_JMIN)
383
+        SERIAL_ECHOLNPAIR("  " STR_J_MIN ": ", m.obj_side[JMINIMUM]);
384
+      #endif
385
+      #if ENABLED(CALIBRATION_MEASURE_JMAX)
386
+        SERIAL_ECHOLNPAIR("  " STR_J_MAX ": ", m.obj_side[JMAXIMUM]);
387
+      #endif
388
+    #endif
389
+    #if LINEAR_AXES >= 6
390
+      #if ENABLED(CALIBRATION_MEASURE_KMIN)
391
+        SERIAL_ECHOLNPAIR("  " STR_K_MIN ": ", m.obj_side[KMINIMUM]);
392
+      #endif
393
+      #if ENABLED(CALIBRATION_MEASURE_KMAX)
394
+        SERIAL_ECHOLNPAIR("  " STR_K_MAX ": ", m.obj_side[KMAXIMUM]);
395
+      #endif
334 396
     #endif
335 397
     SERIAL_EOL();
336 398
   }
@@ -344,6 +406,15 @@ inline void probe_sides(measurements_t &m, const float uncertainty) {
344 406
       SERIAL_ECHOLNPAIR_P(SP_Y_STR, m.obj_center.y);
345 407
     #endif
346 408
     SERIAL_ECHOLNPAIR_P(SP_Z_STR, m.obj_center.z);
409
+    #if HAS_I_CENTER
410
+      SERIAL_ECHOLNPAIR_P(SP_I_STR, m.obj_center.i);
411
+    #endif
412
+    #if HAS_J_CENTER
413
+      SERIAL_ECHOLNPAIR_P(SP_J_STR, m.obj_center.j);
414
+    #endif
415
+    #if HAS_K_CENTER
416
+      SERIAL_ECHOLNPAIR_P(SP_K_STR, m.obj_center.k);
417
+    #endif
347 418
     SERIAL_EOL();
348 419
   }
349 420
 
@@ -357,7 +428,7 @@ inline void probe_sides(measurements_t &m, const float uncertainty) {
357 428
         SERIAL_ECHOLNPAIR("  Right: ", m.backlash[RIGHT]);
358 429
       #endif
359 430
     #endif
360
-    #if AXIS_CAN_CALIBRATE(Y)
431
+    #if HAS_Y_AXIS && AXIS_CAN_CALIBRATE(Y)
361 432
       #if ENABLED(CALIBRATION_MEASURE_FRONT)
362 433
         SERIAL_ECHOLNPAIR("  Front: ", m.backlash[FRONT]);
363 434
       #endif
@@ -365,9 +436,33 @@ inline void probe_sides(measurements_t &m, const float uncertainty) {
365 436
         SERIAL_ECHOLNPAIR("  Back: ", m.backlash[BACK]);
366 437
       #endif
367 438
     #endif
368
-    #if AXIS_CAN_CALIBRATE(Z)
439
+    #if HAS_Z_AXIS && AXIS_CAN_CALIBRATE(Z)
369 440
       SERIAL_ECHOLNPAIR("  Top: ", m.backlash[TOP]);
370 441
     #endif
442
+    #if LINEAR_AXES >= 4 AXIS_CAN_CALIBRATE(I)
443
+      #if ENABLED(CALIBRATION_MEASURE_IMIN)
444
+        SERIAL_ECHOLNPAIR("  " STR_I_MIN ": ", m.backlash[IMINIMUM]);
445
+      #endif
446
+      #if ENABLED(CALIBRATION_MEASURE_IMAX)
447
+        SERIAL_ECHOLNPAIR("  " STR_I_MAX ": ", m.backlash[IMAXIMUM]);
448
+      #endif
449
+    #endif
450
+    #if LINEAR_AXES >= 5 AXIS_CAN_CALIBRATE(J)
451
+      #if ENABLED(CALIBRATION_MEASURE_JMIN)
452
+        SERIAL_ECHOLNPAIR("  " STR_J_MIN ": ", m.backlash[JMINIMUM]);
453
+      #endif
454
+      #if ENABLED(CALIBRATION_MEASURE_JMAX)
455
+        SERIAL_ECHOLNPAIR("  " STR_J_MAX ": ", m.backlash[JMAXIMUM]);
456
+      #endif
457
+    #endif
458
+    #if LINEAR_AXES >= 6 AXIS_CAN_CALIBRATE(K)
459
+      #if ENABLED(CALIBRATION_MEASURE_KMIN)
460
+        SERIAL_ECHOLNPAIR("  " STR_K_MIN ": ", m.backlash[KMINIMUM]);
461
+      #endif
462
+      #if ENABLED(CALIBRATION_MEASURE_KMAX)
463
+        SERIAL_ECHOLNPAIR("  " STR_K_MAX ": ", m.backlash[KMAXIMUM]);
464
+      #endif
465
+    #endif
371 466
     SERIAL_EOL();
372 467
   }
373 468
 
@@ -375,29 +470,37 @@ inline void probe_sides(measurements_t &m, const float uncertainty) {
375 470
     SERIAL_CHAR('T');
376 471
     SERIAL_ECHO(active_extruder);
377 472
     SERIAL_ECHOLNPGM(" Positional Error:");
378
-    #if HAS_X_CENTER
473
+    #if HAS_X_CENTER && AXIS_CAN_CALIBRATE(X)
379 474
       SERIAL_ECHOLNPAIR_P(SP_X_STR, m.pos_error.x);
380 475
     #endif
381
-    #if HAS_Y_CENTER
476
+    #if HAS_Y_CENTER && AXIS_CAN_CALIBRATE(Y)
382 477
       SERIAL_ECHOLNPAIR_P(SP_Y_STR, m.pos_error.y);
383 478
     #endif
384
-    if (AXIS_CAN_CALIBRATE(Z)) SERIAL_ECHOLNPAIR_P(SP_Z_STR, m.pos_error.z);
479
+    #if HAS_Z_AXIS && AXIS_CAN_CALIBRATE(Z)
480
+      SERIAL_ECHOLNPAIR_P(SP_Z_STR, m.pos_error.z);
481
+    #endif
482
+    #if HAS_I_CENTER && AXIS_CAN_CALIBRATE(I)
483
+      SERIAL_ECHOLNPAIR_P(SP_I_STR, m.pos_error.i);
484
+    #endif
485
+    #if HAS_J_CENTER && AXIS_CAN_CALIBRATE(J)
486
+      SERIAL_ECHOLNPAIR_P(SP_J_STR, m.pos_error.j);
487
+    #endif
488
+    #if HAS_K_CENTER && AXIS_CAN_CALIBRATE(K)
489
+      SERIAL_ECHOLNPAIR_P(SP_Z_STR, m.pos_error.z);
490
+    #endif
385 491
     SERIAL_EOL();
386 492
   }
387 493
 
388 494
   inline void report_measured_nozzle_dimensions(const measurements_t &m) {
389 495
     SERIAL_ECHOLNPGM("Nozzle Tip Outer Dimensions:");
390
-    #if HAS_X_CENTER || HAS_Y_CENTER
391
-      #if HAS_X_CENTER
392
-        SERIAL_ECHOLNPAIR_P(SP_X_STR, m.nozzle_outer_dimension.x);
393
-      #endif
394
-      #if HAS_Y_CENTER
395
-        SERIAL_ECHOLNPAIR_P(SP_Y_STR, m.nozzle_outer_dimension.y);
396
-      #endif
397
-    #else
398
-      UNUSED(m);
496
+    #if HAS_X_CENTER
497
+      SERIAL_ECHOLNPAIR_P(SP_X_STR, m.nozzle_outer_dimension.x);
498
+    #endif
499
+    #if HAS_Y_CENTER
500
+      SERIAL_ECHOLNPAIR_P(SP_Y_STR, m.nozzle_outer_dimension.y);
399 501
     #endif
400 502
     SERIAL_EOL();
503
+    UNUSED(m);
401 504
   }
402 505
 
403 506
   #if HAS_HOTEND_OFFSET
@@ -446,8 +549,33 @@ inline void calibrate_backlash(measurements_t &m, const float uncertainty) {
446 549
         backlash.distance_mm.y = m.backlash[BACK];
447 550
       #endif
448 551
 
449
-      if (AXIS_CAN_CALIBRATE(Z)) backlash.distance_mm.z = m.backlash[TOP];
450
-    #endif
552
+      TERN_(HAS_Z_AXIS, if (AXIS_CAN_CALIBRATE(Z)) backlash.distance_mm.z = m.backlash[TOP]);
553
+
554
+      #if HAS_I_CENTER
555
+        backlash.distance_mm.i = (m.backlash[IMINIMUM] + m.backlash[IMAXIMUM]) / 2;
556
+      #elif ENABLED(CALIBRATION_MEASURE_IMIN)
557
+        backlash.distance_mm.i = m.backlash[IMINIMUM];
558
+      #elif ENABLED(CALIBRATION_MEASURE_IMAX)
559
+        backlash.distance_mm.i = m.backlash[IMAXIMUM];
560
+      #endif
561
+
562
+      #if HAS_J_CENTER
563
+        backlash.distance_mm.j = (m.backlash[JMINIMUM] + m.backlash[JMAXIMUM]) / 2;
564
+      #elif ENABLED(CALIBRATION_MEASURE_JMIN)
565
+        backlash.distance_mm.j = m.backlash[JMINIMUM];
566
+      #elif ENABLED(CALIBRATION_MEASURE_JMAX)
567
+        backlash.distance_mm.j = m.backlash[JMAXIMUM];
568
+      #endif
569
+
570
+      #if HAS_K_CENTER
571
+        backlash.distance_mm.k = (m.backlash[KMINIMUM] + m.backlash[KMAXIMUM]) / 2;
572
+      #elif ENABLED(CALIBRATION_MEASURE_KMIN)
573
+        backlash.distance_mm.k = m.backlash[KMINIMUM];
574
+      #elif ENABLED(CALIBRATION_MEASURE_KMAX)
575
+        backlash.distance_mm.k = m.backlash[KMAXIMUM];
576
+      #endif
577
+
578
+    #endif // BACKLASH_GCODE
451 579
   }
452 580
 
453 581
   #if ENABLED(BACKLASH_GCODE)
@@ -458,7 +586,8 @@ inline void calibrate_backlash(measurements_t &m, const float uncertainty) {
458 586
       TEMPORARY_BACKLASH_CORRECTION(all_on);
459 587
       TEMPORARY_BACKLASH_SMOOTHING(0.0f);
460 588
       const xyz_float_t move = LINEAR_AXIS_ARRAY(
461
-        AXIS_CAN_CALIBRATE(X) * 3, AXIS_CAN_CALIBRATE(Y) * 3, AXIS_CAN_CALIBRATE(Z) * 3
589
+        AXIS_CAN_CALIBRATE(X) * 3, AXIS_CAN_CALIBRATE(Y) * 3, AXIS_CAN_CALIBRATE(Z) * 3,
590
+        AXIS_CAN_CALIBRATE(I) * 3, AXIS_CAN_CALIBRATE(J) * 3, AXIS_CAN_CALIBRATE(K) * 3
462 591
       );
463 592
       current_position += move; calibration_move();
464 593
       current_position -= move; calibration_move();
@@ -487,11 +616,7 @@ inline void calibrate_toolhead(measurements_t &m, const float uncertainty, const
487 616
   TEMPORARY_BACKLASH_CORRECTION(all_on);
488 617
   TEMPORARY_BACKLASH_SMOOTHING(0.0f);
489 618
 
490
-  #if HAS_MULTI_HOTEND
491
-    set_nozzle(m, extruder);
492
-  #else
493
-    UNUSED(extruder);
494
-  #endif
619
+  TERN(HAS_MULTI_HOTEND, set_nozzle(m, extruder), UNUSED(extruder));
495 620
 
496 621
   probe_sides(m, uncertainty);
497 622
 
@@ -510,6 +635,10 @@ inline void calibrate_toolhead(measurements_t &m, const float uncertainty, const
510 635
   if (ENABLED(HAS_Y_CENTER) && AXIS_CAN_CALIBRATE(Y)) update_measurements(m, Y_AXIS);
511 636
                            if (AXIS_CAN_CALIBRATE(Z)) update_measurements(m, Z_AXIS);
512 637
 
638
+  TERN_(HAS_I_CENTER, update_measurements(m, I_AXIS));
639
+  TERN_(HAS_J_CENTER, update_measurements(m, J_AXIS));
640
+  TERN_(HAS_K_CENTER, update_measurements(m, K_AXIS));
641
+
513 642
   sync_plan_position();
514 643
 }
515 644
 

+ 4
- 1
Marlin/src/gcode/calibrate/M425.cpp View File

@@ -52,7 +52,10 @@ void GcodeSuite::M425() {
52 52
       LINEAR_AXIS_CODE(
53 53
         case X_AXIS: return AXIS_CAN_CALIBRATE(X),
54 54
         case Y_AXIS: return AXIS_CAN_CALIBRATE(Y),
55
-        case Z_AXIS: return AXIS_CAN_CALIBRATE(Z)
55
+        case Z_AXIS: return AXIS_CAN_CALIBRATE(Z),
56
+        case I_AXIS: return AXIS_CAN_CALIBRATE(I),
57
+        case J_AXIS: return AXIS_CAN_CALIBRATE(J),
58
+        case K_AXIS: return AXIS_CAN_CALIBRATE(K),
56 59
       );
57 60
     }
58 61
   };

+ 7
- 1
Marlin/src/gcode/config/M200-M205.cpp View File

@@ -154,6 +154,9 @@ void GcodeSuite::M205() {
154 154
   if (parser.seenval('S')) planner.settings.min_feedrate_mm_s = parser.value_linear_units();
155 155
   if (parser.seenval('T')) planner.settings.min_travel_feedrate_mm_s = parser.value_linear_units();
156 156
   #if HAS_JUNCTION_DEVIATION
157
+    #if HAS_CLASSIC_JERK && (AXIS4_NAME == 'J' || AXIS5_NAME == 'J' || AXIS6_NAME == 'J')
158
+      #error "Can't set_max_jerk for 'J' axis because 'J' is used for Junction Deviation."
159
+    #endif
157 160
     if (parser.seenval('J')) {
158 161
       const float junc_dev = parser.value_linear_units();
159 162
       if (WITHIN(junc_dev, 0.01f, 0.3f)) {
@@ -170,7 +173,10 @@ void GcodeSuite::M205() {
170 173
       if (parser.seenval('E')) planner.set_max_jerk(E_AXIS, parser.value_linear_units()),
171 174
       if (parser.seenval('X')) planner.set_max_jerk(X_AXIS, parser.value_linear_units()),
172 175
       if (parser.seenval('Y')) planner.set_max_jerk(Y_AXIS, parser.value_linear_units()),
173
-      if ((seenZ = parser.seenval('Z'))) planner.set_max_jerk(Z_AXIS, parser.value_linear_units())
176
+      if ((seenZ = parser.seenval('Z'))) planner.set_max_jerk(Z_AXIS, parser.value_linear_units()),
177
+      if (parser.seenval(AXIS4_NAME)) planner.set_max_jerk(I_AXIS, parser.value_linear_units()),
178
+      if (parser.seenval(AXIS5_NAME)) planner.set_max_jerk(J_AXIS, parser.value_linear_units()),
179
+      if (parser.seenval(AXIS6_NAME)) planner.set_max_jerk(K_AXIS, parser.value_linear_units())
174 180
     );
175 181
     #if HAS_MESH && DISABLED(LIMITED_JERK_EDITING)
176 182
       if (seenZ && planner.max_jerk.z <= 0.1f)

+ 6
- 3
Marlin/src/gcode/config/M92.cpp View File

@@ -28,8 +28,11 @@ void report_M92(const bool echo=true, const int8_t e=-1) {
28 28
   SERIAL_ECHOPAIR_P(LIST_N(DOUBLE(LINEAR_AXES),
29 29
     PSTR(" M92 X"), LINEAR_UNIT(planner.settings.axis_steps_per_mm[X_AXIS]),
30 30
     SP_Y_STR, LINEAR_UNIT(planner.settings.axis_steps_per_mm[Y_AXIS]),
31
-    SP_Z_STR, LINEAR_UNIT(planner.settings.axis_steps_per_mm[Z_AXIS])
32
-  ));
31
+    SP_Z_STR, LINEAR_UNIT(planner.settings.axis_steps_per_mm[Z_AXIS]),
32
+    SP_I_STR, LINEAR_UNIT(planner.settings.axis_steps_per_mm[I_AXIS]),
33
+    SP_J_STR, LINEAR_UNIT(planner.settings.axis_steps_per_mm[J_AXIS]),
34
+    SP_K_STR, LINEAR_UNIT(planner.settings.axis_steps_per_mm[K_AXIS]))
35
+  );
33 36
   #if HAS_EXTRUDERS && DISABLED(DISTINCT_E_FACTORS)
34 37
     SERIAL_ECHOPAIR_P(SP_E_STR, VOLUMETRIC_UNIT(planner.settings.axis_steps_per_mm[E_AXIS]));
35 38
   #endif
@@ -67,7 +70,7 @@ void GcodeSuite::M92() {
67 70
 
68 71
   // No arguments? Show M92 report.
69 72
   if (!parser.seen(
70
-    LOGICAL_AXIS_GANG("E", "X", "Y", "Z")
73
+    LOGICAL_AXIS_GANG("E", "X", "Y", "Z", AXIS4_STR, AXIS5_STR, AXIS6_STR)
71 74
     TERN_(MAGIC_NUMBERS_GCODE, "HL")
72 75
   )) return report_M92(true, target_extruder);
73 76
 

+ 10
- 4
Marlin/src/gcode/control/M17_M18_M84.cpp View File

@@ -33,12 +33,15 @@
33 33
  * M17: Enable stepper motors
34 34
  */
35 35
 void GcodeSuite::M17() {
36
-  if (parser.seen(LOGICAL_AXIS_GANG("E", "X", "Y", "Z"))) {
36
+  if (parser.seen(LOGICAL_AXIS_GANG("E", "X", "Y", "Z", AXIS4_STR, AXIS5_STR, AXIS6_STR))) {
37 37
     LOGICAL_AXIS_CODE(
38 38
       if (TERN0(HAS_E_STEPPER_ENABLE, parser.seen_test('E'))) enable_e_steppers(),
39 39
       if (parser.seen_test('X'))        ENABLE_AXIS_X(),
40 40
       if (parser.seen_test('Y'))        ENABLE_AXIS_Y(),
41
-      if (parser.seen_test('Z'))        ENABLE_AXIS_Z()
41
+      if (parser.seen_test('Z'))        ENABLE_AXIS_Z(),
42
+      if (parser.seen_test(AXIS4_NAME)) ENABLE_AXIS_I(),
43
+      if (parser.seen_test(AXIS5_NAME)) ENABLE_AXIS_J(),
44
+      if (parser.seen_test(AXIS6_NAME)) ENABLE_AXIS_K()
42 45
     );
43 46
   }
44 47
   else {
@@ -56,13 +59,16 @@ void GcodeSuite::M18_M84() {
56 59
     stepper_inactive_time = parser.value_millis_from_seconds();
57 60
   }
58 61
   else {
59
-    if (parser.seen(LOGICAL_AXIS_GANG("E", "X", "Y", "Z"))) {
62
+    if (parser.seen(LOGICAL_AXIS_GANG("E", "X", "Y", "Z", AXIS4_STR, AXIS5_STR, AXIS6_STR))) {
60 63
       planner.synchronize();
61 64
       LOGICAL_AXIS_CODE(
62 65
         if (TERN0(HAS_E_STEPPER_ENABLE, parser.seen_test('E'))) disable_e_steppers(),
63 66
         if (parser.seen_test('X'))        DISABLE_AXIS_X(),
64 67
         if (parser.seen_test('Y'))        DISABLE_AXIS_Y(),
65
-        if (parser.seen_test('Z'))        DISABLE_AXIS_Z()
68
+        if (parser.seen_test('Z'))        DISABLE_AXIS_Z(),
69
+        if (parser.seen_test(AXIS4_NAME)) DISABLE_AXIS_I(),
70
+        if (parser.seen_test(AXIS5_NAME)) DISABLE_AXIS_J(),
71
+        if (parser.seen_test(AXIS6_NAME)) DISABLE_AXIS_K()
66 72
       );
67 73
     }
68 74
     else

+ 21
- 16
Marlin/src/gcode/control/M605.cpp View File

@@ -70,26 +70,12 @@
70 70
       dual_x_carriage_mode = (DualXMode)parser.value_byte();
71 71
       idex_set_mirrored_mode(false);
72 72
 
73
-      if (dual_x_carriage_mode == DXC_MIRRORED_MODE) {
74
-        if (previous_mode != DXC_DUPLICATION_MODE) {
75
-          SERIAL_ECHOLNPGM("Printer must be in DXC_DUPLICATION_MODE prior to ");
76
-          SERIAL_ECHOLNPGM("specifying DXC_MIRRORED_MODE.");
77
-          dual_x_carriage_mode = DEFAULT_DUAL_X_CARRIAGE_MODE;
78
-          return;
79
-        }
80
-        idex_set_mirrored_mode(true);
81
-        float x_jog = current_position.x - .1;
82
-        for (uint8_t i = 2; --i;) {
83
-          planner.buffer_line(x_jog, current_position.y, current_position.z, current_position.e, feedrate_mm_s, 0);
84
-          x_jog += .1;
85
-        }
86
-        return;
87
-      }
88
-
89 73
       switch (dual_x_carriage_mode) {
74
+
90 75
         case DXC_FULL_CONTROL_MODE:
91 76
         case DXC_AUTO_PARK_MODE:
92 77
           break;
78
+
93 79
         case DXC_DUPLICATION_MODE:
94 80
           // Set the X offset, but no less than the safety gap
95 81
           if (parser.seen('X')) duplicate_extruder_x_offset = _MAX(parser.value_linear_units(), (X2_MIN_POS) - (X1_MIN_POS));
@@ -97,10 +83,29 @@
97 83
           // Always switch back to tool 0
98 84
           if (active_extruder != 0) tool_change(0);
99 85
           break;
86
+
87
+        case DXC_MIRRORED_MODE: {
88
+          if (previous_mode != DXC_DUPLICATION_MODE) {
89
+            SERIAL_ECHOLNPGM("Printer must be in DXC_DUPLICATION_MODE prior to ");
90
+            SERIAL_ECHOLNPGM("specifying DXC_MIRRORED_MODE.");
91
+            dual_x_carriage_mode = DEFAULT_DUAL_X_CARRIAGE_MODE;
92
+            return;
93
+          }
94
+          idex_set_mirrored_mode(true);
95
+
96
+          // Do a small 'jog' motion in the X axis
97
+          xyze_pos_t dest = current_position; dest.x -= 0.1f;
98
+          for (uint8_t i = 2; --i;) {
99
+            planner.buffer_line(dest, feedrate_mm_s, 0);
100
+            dest.x += 0.1f;
101
+          }
102
+        } return;
103
+
100 104
         default:
101 105
           dual_x_carriage_mode = DEFAULT_DUAL_X_CARRIAGE_MODE;
102 106
           break;
103 107
       }
108
+
104 109
       idex_set_parked(false);
105 110
       set_duplication_enabled(false);
106 111
 

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

@@ -253,7 +253,7 @@ void GcodeSuite::M906() {
253 253
         #endif
254 254
         break;
255 255
 
256
-      #if LINEAR_AXES >= XY
256
+      #if HAS_Y_AXIS
257 257
         case Y_AXIS:
258 258
           #if AXIS_IS_L64XX(Y)
259 259
             if (index == 0) L6470_SET_KVAL_HOLD(Y);

+ 6
- 5
Marlin/src/gcode/feature/pause/G60.cpp View File

@@ -47,12 +47,13 @@ void GcodeSuite::G60() {
47 47
   SBI(saved_slots[slot >> 3], slot & 0x07);
48 48
 
49 49
   #if ENABLED(SAVED_POSITIONS_DEBUG)
50
-    const xyze_pos_t &pos = stored_position[slot];
51 50
     DEBUG_ECHOPAIR(STR_SAVED_POS " S", slot);
52
-    DEBUG_ECHOPAIR_F(" : X", pos.x);
53
-    DEBUG_ECHOPAIR_F_P(SP_Y_STR, pos.y);
54
-    DEBUG_ECHOPAIR_F_P(SP_Z_STR, pos.z);
55
-    DEBUG_ECHOLNPAIR_F_P(SP_E_STR, pos.e);
51
+    const xyze_pos_t &pos = stored_position[slot];
52
+    DEBUG_ECHOLNPAIR_F_P(
53
+      LIST_N(DOUBLE(LOGICAL_AXES), SP_E_STR, pos.e,
54
+      PSTR(" : X"), pos.x, SP_Y_STR, pos.y, SP_Z_STR, pos.z,
55
+      SP_I_STR, pos.i, SP_J_STR, pos.j, SP_K_STR, pos.k)
56
+    );
56 57
   #endif
57 58
 }
58 59
 

+ 2
- 2
Marlin/src/gcode/feature/pause/G61.cpp View File

@@ -45,7 +45,7 @@ void GcodeSuite::G61(void) {
45 45
 
46 46
   const uint8_t slot = parser.byteval('S');
47 47
 
48
-  #define SYNC_E(POINT) planner.set_e_position_mm((destination.e = current_position.e = (POINT)))
48
+  #define SYNC_E(POINT) TERN_(HAS_EXTRUDERS, planner.set_e_position_mm((destination.e = current_position.e = (POINT))))
49 49
 
50 50
   #if SAVED_POSITIONS < 256
51 51
     if (slot >= SAVED_POSITIONS) {
@@ -68,7 +68,7 @@ void GcodeSuite::G61(void) {
68 68
     SYNC_E(stored_position[slot].e);
69 69
   }
70 70
   else {
71
-    if (parser.seen(LINEAR_AXIS_GANG("X", "Y", "Z"))) {
71
+    if (parser.seen(LINEAR_AXIS_GANG("X", "Y", "Z", AXIS4_STR, AXIS5_STR, AXIS6_STR))) {
72 72
       DEBUG_ECHOPAIR(STR_RESTORING_POS " S", slot);
73 73
       LOOP_LINEAR_AXES(i) {
74 74
         destination[i] = parser.seen(AXIS_CHAR(i))

+ 6
- 14
Marlin/src/gcode/feature/trinamic/M122.cpp View File

@@ -35,7 +35,7 @@ void GcodeSuite::M122() {
35 35
   xyze_bool_t print_axis = ARRAY_N_1(LOGICAL_AXES, false);
36 36
 
37 37
   bool print_all = true;
38
-  LOOP_LOGICAL_AXES(i) if (parser.seen(axis_codes[i])) { print_axis[i] = true; print_all = false; }
38
+  LOOP_LOGICAL_AXES(i) if (parser.seen_test(axis_codes[i])) { print_axis[i] = true; print_all = false; }
39 39
 
40 40
   if (print_all) LOOP_LOGICAL_AXES(i) print_axis[i] = true;
41 41
 
@@ -49,21 +49,13 @@ void GcodeSuite::M122() {
49 49
       tmc_set_report_interval(interval);
50 50
     #endif
51 51
 
52
-    if (parser.seen_test('V')) {
53
-      tmc_get_registers(
54
-        LOGICAL_AXIS_LIST(print_axis.e, print_axis.x, print_axis.y, print_axis.z)
55
-      );
56
-    }
57
-    else {
58
-      tmc_report_all(
59
-        LOGICAL_AXIS_LIST(print_axis.e, print_axis.x, print_axis.y, print_axis.z)
60
-      );
61
-    }
52
+    if (parser.seen_test('V'))
53
+      tmc_get_registers(LOGICAL_AXIS_ELEM(print_axis));
54
+    else
55
+      tmc_report_all(LOGICAL_AXIS_ELEM(print_axis));
62 56
   #endif
63 57
 
64
-  test_tmc_connection(
65
-    LOGICAL_AXIS_LIST(print_axis.e, print_axis.x, print_axis.y, print_axis.z)
66
-  );
58
+  test_tmc_connection(LOGICAL_AXIS_ELEM(print_axis));
67 59
 }
68 60
 
69 61
 #endif // HAS_TRINAMIC_CONFIG

+ 49
- 104
Marlin/src/gcode/feature/trinamic/M569.cpp View File

@@ -43,81 +43,56 @@ void tmc_set_stealthChop(TMC &st, const bool enable) {
43 43
 static void set_stealth_status(const bool enable, const int8_t target_extruder) {
44 44
   #define TMC_SET_STEALTH(Q) tmc_set_stealthChop(stepper##Q, enable)
45 45
 
46
-  #if    AXIS_HAS_STEALTHCHOP(X)  || AXIS_HAS_STEALTHCHOP(X2) \
47
-      || AXIS_HAS_STEALTHCHOP(Y)  || AXIS_HAS_STEALTHCHOP(Y2) \
48
-      || AXIS_HAS_STEALTHCHOP(Z)  || AXIS_HAS_STEALTHCHOP(Z2) \
49
-      || AXIS_HAS_STEALTHCHOP(Z3) || AXIS_HAS_STEALTHCHOP(Z4)
46
+  #if    X_HAS_STEALTHCHOP  || Y_HAS_STEALTHCHOP  || Z_HAS_STEALTHCHOP \
47
+      || I_HAS_STEALTHCHOP  || J_HAS_STEALTHCHOP  || K_HAS_STEALTHCHOP \
48
+      || X2_HAS_STEALTHCHOP || Y2_HAS_STEALTHCHOP || Z2_HAS_STEALTHCHOP || Z3_HAS_STEALTHCHOP || Z4_HAS_STEALTHCHOP
50 49
     const uint8_t index = parser.byteval('I');
51 50
   #endif
52 51
 
53 52
   LOOP_LOGICAL_AXES(i) if (parser.seen(axis_codes[i])) {
54 53
     switch (i) {
55 54
       case X_AXIS:
56
-        #if AXIS_HAS_STEALTHCHOP(X)
57
-          if (index == 0) TMC_SET_STEALTH(X);
58
-        #endif
59
-        #if AXIS_HAS_STEALTHCHOP(X2)
60
-          if (index == 1) TMC_SET_STEALTH(X2);
61
-        #endif
55
+        TERN_(X_HAS_STEALTHCHOP,  if (index == 0) TMC_SET_STEALTH(X));
56
+        TERN_(X2_HAS_STEALTHCHOP, if (index == 1) TMC_SET_STEALTH(X2));
62 57
         break;
63 58
 
64
-      #if LINEAR_AXES >= XY
59
+      #if HAS_Y_AXIS
65 60
         case Y_AXIS:
66
-          #if AXIS_HAS_STEALTHCHOP(Y)
67
-            if (index == 0) TMC_SET_STEALTH(Y);
68
-          #endif
69
-          #if AXIS_HAS_STEALTHCHOP(Y2)
70
-            if (index == 1) TMC_SET_STEALTH(Y2);
71
-          #endif
61
+          TERN_(Y_HAS_STEALTHCHOP,  if (index == 0) TMC_SET_STEALTH(Y));
62
+          TERN_(Y2_HAS_STEALTHCHOP, if (index == 1) TMC_SET_STEALTH(Y2));
72 63
           break;
73 64
       #endif
74 65
 
75 66
       #if HAS_Z_AXIS
76 67
         case Z_AXIS:
77
-          #if AXIS_HAS_STEALTHCHOP(Z)
78
-            if (index == 0) TMC_SET_STEALTH(Z);
79
-          #endif
80
-          #if AXIS_HAS_STEALTHCHOP(Z2)
81
-            if (index == 1) TMC_SET_STEALTH(Z2);
82
-          #endif
83
-          #if AXIS_HAS_STEALTHCHOP(Z3)
84
-            if (index == 2) TMC_SET_STEALTH(Z3);
85
-          #endif
86
-          #if AXIS_HAS_STEALTHCHOP(Z4)
87
-            if (index == 3) TMC_SET_STEALTH(Z4);
88
-          #endif
68
+          TERN_(Z_HAS_STEALTHCHOP,  if (index == 0) TMC_SET_STEALTH(Z));
69
+          TERN_(Z2_HAS_STEALTHCHOP, if (index == 1) TMC_SET_STEALTH(Z2));
70
+          TERN_(Z3_HAS_STEALTHCHOP, if (index == 2) TMC_SET_STEALTH(Z3));
71
+          TERN_(Z4_HAS_STEALTHCHOP, if (index == 3) TMC_SET_STEALTH(Z4));
89 72
           break;
90 73
       #endif
91 74
 
75
+      #if I_HAS_STEALTHCHOP
76
+        case I_AXIS: TMC_SET_STEALTH(I); break;
77
+      #endif
78
+      #if J_HAS_STEALTHCHOP
79
+        case J_AXIS: TMC_SET_STEALTH(J); break;
80
+      #endif
81
+      #if K_HAS_STEALTHCHOP
82
+        case K_AXIS: TMC_SET_STEALTH(K); break;
83
+      #endif
84
+
92 85
       #if HAS_EXTRUDERS
93 86
         case E_AXIS: {
94 87
           if (target_extruder < 0) return;
95
-          switch (target_extruder) {
96
-            #if AXIS_HAS_STEALTHCHOP(E0)
97
-              case 0: TMC_SET_STEALTH(E0); break;
98
-            #endif
99
-            #if AXIS_HAS_STEALTHCHOP(E1)
100
-              case 1: TMC_SET_STEALTH(E1); break;
101
-            #endif
102
-            #if AXIS_HAS_STEALTHCHOP(E2)
103
-              case 2: TMC_SET_STEALTH(E2); break;
104
-            #endif
105
-            #if AXIS_HAS_STEALTHCHOP(E3)
106
-              case 3: TMC_SET_STEALTH(E3); break;
107
-            #endif
108
-            #if AXIS_HAS_STEALTHCHOP(E4)
109
-              case 4: TMC_SET_STEALTH(E4); break;
110
-            #endif
111
-            #if AXIS_HAS_STEALTHCHOP(E5)
112
-              case 5: TMC_SET_STEALTH(E5); break;
113
-            #endif
114
-            #if AXIS_HAS_STEALTHCHOP(E6)
115
-              case 6: TMC_SET_STEALTH(E6); break;
116
-            #endif
117
-            #if AXIS_HAS_STEALTHCHOP(E7)
118
-              case 7: TMC_SET_STEALTH(E7); break;
119
-            #endif
120
-          }
88
+          OPTCODE(E0_HAS_STEALTHCHOP, else if (target_extruder == 0) TMC_SET_STEALTH(E0))
89
+          OPTCODE(E1_HAS_STEALTHCHOP, else if (target_extruder == 1) TMC_SET_STEALTH(E1))
90
+          OPTCODE(E2_HAS_STEALTHCHOP, else if (target_extruder == 2) TMC_SET_STEALTH(E2))
91
+          OPTCODE(E3_HAS_STEALTHCHOP, else if (target_extruder == 3) TMC_SET_STEALTH(E3))
92
+          OPTCODE(E4_HAS_STEALTHCHOP, else if (target_extruder == 4) TMC_SET_STEALTH(E4))
93
+          OPTCODE(E5_HAS_STEALTHCHOP, else if (target_extruder == 5) TMC_SET_STEALTH(E5))
94
+          OPTCODE(E6_HAS_STEALTHCHOP, else if (target_extruder == 6) TMC_SET_STEALTH(E6))
95
+          OPTCODE(E7_HAS_STEALTHCHOP, else if (target_extruder == 7) TMC_SET_STEALTH(E7))
121 96
         } break;
122 97
       #endif
123 98
     }
@@ -126,55 +101,25 @@ static void set_stealth_status(const bool enable, const int8_t target_extruder)
126 101
 
127 102
 static void say_stealth_status() {
128 103
   #define TMC_SAY_STEALTH_STATUS(Q) tmc_say_stealth_status(stepper##Q)
129
-
130
-  #if AXIS_HAS_STEALTHCHOP(X)
131
-    TMC_SAY_STEALTH_STATUS(X);
132
-  #endif
133
-  #if AXIS_HAS_STEALTHCHOP(X2)
134
-    TMC_SAY_STEALTH_STATUS(X2);
135
-  #endif
136
-  #if AXIS_HAS_STEALTHCHOP(Y)
137
-    TMC_SAY_STEALTH_STATUS(Y);
138
-  #endif
139
-  #if AXIS_HAS_STEALTHCHOP(Y2)
140
-    TMC_SAY_STEALTH_STATUS(Y2);
141
-  #endif
142
-  #if AXIS_HAS_STEALTHCHOP(Z)
143
-    TMC_SAY_STEALTH_STATUS(Z);
144
-  #endif
145
-  #if AXIS_HAS_STEALTHCHOP(Z2)
146
-    TMC_SAY_STEALTH_STATUS(Z2);
147
-  #endif
148
-  #if AXIS_HAS_STEALTHCHOP(Z3)
149
-    TMC_SAY_STEALTH_STATUS(Z3);
150
-  #endif
151
-  #if AXIS_HAS_STEALTHCHOP(Z4)
152
-    TMC_SAY_STEALTH_STATUS(Z4);
153
-  #endif
154
-  #if AXIS_HAS_STEALTHCHOP(E0)
155
-    TMC_SAY_STEALTH_STATUS(E0);
156
-  #endif
157
-  #if AXIS_HAS_STEALTHCHOP(E1)
158
-    TMC_SAY_STEALTH_STATUS(E1);
159
-  #endif
160
-  #if AXIS_HAS_STEALTHCHOP(E2)
161
-    TMC_SAY_STEALTH_STATUS(E2);
162
-  #endif
163
-  #if AXIS_HAS_STEALTHCHOP(E3)
164
-    TMC_SAY_STEALTH_STATUS(E3);
165
-  #endif
166
-  #if AXIS_HAS_STEALTHCHOP(E4)
167
-    TMC_SAY_STEALTH_STATUS(E4);
168
-  #endif
169
-  #if AXIS_HAS_STEALTHCHOP(E5)
170
-    TMC_SAY_STEALTH_STATUS(E5);
171
-  #endif
172
-  #if AXIS_HAS_STEALTHCHOP(E6)
173
-    TMC_SAY_STEALTH_STATUS(E6);
174
-  #endif
175
-  #if AXIS_HAS_STEALTHCHOP(E7)
176
-    TMC_SAY_STEALTH_STATUS(E7);
177
-  #endif
104
+  OPTCODE( X_HAS_STEALTHCHOP, TMC_SAY_STEALTH_STATUS(X))
105
+  OPTCODE(X2_HAS_STEALTHCHOP, TMC_SAY_STEALTH_STATUS(X2))
106
+  OPTCODE( Y_HAS_STEALTHCHOP, TMC_SAY_STEALTH_STATUS(Y))
107
+  OPTCODE(Y2_HAS_STEALTHCHOP, TMC_SAY_STEALTH_STATUS(Y2))
108
+  OPTCODE( Z_HAS_STEALTHCHOP, TMC_SAY_STEALTH_STATUS(Z))
109
+  OPTCODE(Z2_HAS_STEALTHCHOP, TMC_SAY_STEALTH_STATUS(Z2))
110
+  OPTCODE(Z3_HAS_STEALTHCHOP, TMC_SAY_STEALTH_STATUS(Z3))
111
+  OPTCODE(Z4_HAS_STEALTHCHOP, TMC_SAY_STEALTH_STATUS(Z4))
112
+  OPTCODE( I_HAS_STEALTHCHOP, TMC_SAY_STEALTH_STATUS(I))
113
+  OPTCODE( J_HAS_STEALTHCHOP, TMC_SAY_STEALTH_STATUS(J))
114
+  OPTCODE( K_HAS_STEALTHCHOP, TMC_SAY_STEALTH_STATUS(K))
115
+  OPTCODE(E0_HAS_STEALTHCHOP, TMC_SAY_STEALTH_STATUS(E0))
116
+  OPTCODE(E1_HAS_STEALTHCHOP, TMC_SAY_STEALTH_STATUS(E1))
117
+  OPTCODE(E2_HAS_STEALTHCHOP, TMC_SAY_STEALTH_STATUS(E2))
118
+  OPTCODE(E3_HAS_STEALTHCHOP, TMC_SAY_STEALTH_STATUS(E3))
119
+  OPTCODE(E4_HAS_STEALTHCHOP, TMC_SAY_STEALTH_STATUS(E4))
120
+  OPTCODE(E5_HAS_STEALTHCHOP, TMC_SAY_STEALTH_STATUS(E5))
121
+  OPTCODE(E6_HAS_STEALTHCHOP, TMC_SAY_STEALTH_STATUS(E6))
122
+  OPTCODE(E7_HAS_STEALTHCHOP, TMC_SAY_STEALTH_STATUS(E7))
178 123
 }
179 124
 
180 125
 /**

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

@@ -48,7 +48,7 @@ void GcodeSuite::M906() {
48 48
 
49 49
   bool report = true;
50 50
 
51
-  #if AXIS_IS_TMC(X) || AXIS_IS_TMC(X2) || AXIS_IS_TMC(Y) || AXIS_IS_TMC(Y2) || AXIS_IS_TMC(Z) || AXIS_IS_TMC(Z2) || AXIS_IS_TMC(Z3) || AXIS_IS_TMC(Z4)
51
+  #if AXIS_IS_TMC(X) || AXIS_IS_TMC(X2) || AXIS_IS_TMC(Y) || AXIS_IS_TMC(Y2) || AXIS_IS_TMC(Z) || AXIS_IS_TMC(Z2) || AXIS_IS_TMC(Z3) || AXIS_IS_TMC(Z4) || AXIS_IS_TMC(I) || AXIS_IS_TMC(J) || AXIS_IS_TMC(K)
52 52
     const uint8_t index = parser.byteval('I');
53 53
   #endif
54 54
 
@@ -64,7 +64,7 @@ void GcodeSuite::M906() {
64 64
         #endif
65 65
         break;
66 66
 
67
-      #if LINEAR_AXES >= XY
67
+      #if HAS_Y_AXIS
68 68
         case Y_AXIS:
69 69
           #if AXIS_IS_TMC(Y)
70 70
             if (index == 0) TMC_SET_CURRENT(Y);
@@ -92,6 +92,16 @@ void GcodeSuite::M906() {
92 92
           break;
93 93
       #endif
94 94
 
95
+      #if AXIS_IS_TMC(I)
96
+        case I_AXIS: TMC_SET_CURRENT(I); break;
97
+      #endif
98
+      #if AXIS_IS_TMC(J)
99
+        case J_AXIS: TMC_SET_CURRENT(J); break;
100
+      #endif
101
+      #if AXIS_IS_TMC(K)
102
+        case K_AXIS: TMC_SET_CURRENT(K); break;
103
+      #endif
104
+
95 105
       #if HAS_EXTRUDERS
96 106
         case E_AXIS: {
97 107
           const int8_t target_extruder = get_target_extruder_from_command();
@@ -152,6 +162,15 @@ void GcodeSuite::M906() {
152 162
     #if AXIS_IS_TMC(Z4)
153 163
       TMC_SAY_CURRENT(Z4);
154 164
     #endif
165
+    #if AXIS_IS_TMC(I)
166
+      TMC_SAY_CURRENT(I);
167
+    #endif
168
+    #if AXIS_IS_TMC(J)
169
+      TMC_SAY_CURRENT(J);
170
+    #endif
171
+    #if AXIS_IS_TMC(K)
172
+      TMC_SAY_CURRENT(K);
173
+    #endif
155 174
     #if AXIS_IS_TMC(E0)
156 175
       TMC_SAY_CURRENT(E0);
157 176
     #endif

+ 99
- 103
Marlin/src/gcode/feature/trinamic/M911-M914.cpp View File

@@ -38,18 +38,27 @@
38 38
   #if M91x_USE(X) || M91x_USE(X2)
39 39
     #define M91x_SOME_X 1
40 40
   #endif
41
-  #if M91x_USE(Y) || M91x_USE(Y2)
41
+  #if LINEAR_AXES >= 2 && (M91x_USE(Y) || M91x_USE(Y2))
42 42
     #define M91x_SOME_Y 1
43 43
   #endif
44
-  #if M91x_USE(Z) || M91x_USE(Z2) || M91x_USE(Z3) || M91x_USE(Z4)
44
+  #if HAS_Z_AXIS && (M91x_USE(Z) || M91x_USE(Z2) || M91x_USE(Z3) || M91x_USE(Z4))
45 45
     #define M91x_SOME_Z 1
46 46
   #endif
47
+  #if LINEAR_AXES >= 4 && M91x_USE(I)
48
+    #define M91x_USE_I 1
49
+  #endif
50
+  #if LINEAR_AXES >= 5 && M91x_USE(J)
51
+    #define M91x_USE_J 1
52
+  #endif
53
+  #if LINEAR_AXES >= 6 && M91x_USE(K)
54
+    #define M91x_USE_K 1
55
+  #endif
47 56
 
48 57
   #if M91x_USE_E(0) || M91x_USE_E(1) || M91x_USE_E(2) || M91x_USE_E(3) || M91x_USE_E(4) || M91x_USE_E(5) || M91x_USE_E(6) || M91x_USE_E(7)
49 58
     #define M91x_SOME_E 1
50 59
   #endif
51 60
 
52
-  #if !M91x_SOME_X && !M91x_SOME_Y && !M91x_SOME_Z && !M91x_SOME_E
61
+  #if !M91x_SOME_X && !M91x_SOME_Y && !M91x_SOME_Z && !M91x_USE_I && !M91x_USE_J && !M91x_USE_K && !M91x_SOME_E
53 62
     #error "MONITOR_DRIVER_STATUS requires at least one TMC2130, 2160, 2208, 2209, 2660, 5130, or 5160."
54 63
   #endif
55 64
 
@@ -82,6 +91,9 @@
82 91
     #if M91x_USE(Z4)
83 92
       tmc_report_otpw(stepperZ4);
84 93
     #endif
94
+    TERN_(M91x_USE_I, tmc_report_otpw(stepperI));
95
+    TERN_(M91x_USE_J, tmc_report_otpw(stepperJ));
96
+    TERN_(M91x_USE_K, tmc_report_otpw(stepperK));
85 97
     #if M91x_USE_E(0)
86 98
       tmc_report_otpw(stepperE0);
87 99
     #endif
@@ -124,9 +136,12 @@
124 136
     const bool hasX = TERN0(M91x_SOME_X, parser.seen(axis_codes.x)),
125 137
                hasY = TERN0(M91x_SOME_Y, parser.seen(axis_codes.y)),
126 138
                hasZ = TERN0(M91x_SOME_Z, parser.seen(axis_codes.z)),
139
+               hasI = TERN0(M91x_USE_I,  parser.seen(axis_codes.i)),
140
+               hasJ = TERN0(M91x_USE_J,  parser.seen(axis_codes.j)),
141
+               hasK = TERN0(M91x_USE_K,  parser.seen(axis_codes.k)),
127 142
                hasE = TERN0(M91x_SOME_E, parser.seen(axis_codes.e));
128 143
 
129
-    const bool hasNone = !hasE && !hasX && !hasY && !hasZ;
144
+    const bool hasNone = !hasE && !hasX && !hasY && !hasZ && !hasI && !hasJ && !hasK;
130 145
 
131 146
     #if M91x_SOME_X
132 147
       const int8_t xval = int8_t(parser.byteval(axis_codes.x, 0xFF));
@@ -164,6 +179,19 @@
164 179
       #endif
165 180
     #endif
166 181
 
182
+    #if M91x_USE_I
183
+      const int8_t ival = int8_t(parser.byteval(axis_codes.i, 0xFF));
184
+      if (hasNone || ival == 1 || (hasI && ival < 0)) tmc_clear_otpw(stepperI);
185
+    #endif
186
+    #if M91x_USE_J
187
+      const int8_t jval = int8_t(parser.byteval(axis_codes.j, 0xFF));
188
+      if (hasNone || jval == 1 || (hasJ && jval < 0)) tmc_clear_otpw(stepperJ);
189
+    #endif
190
+    #if M91x_USE_K
191
+      const int8_t kval = int8_t(parser.byteval(axis_codes.k, 0xFF));
192
+      if (hasNone || kval == 1 || (hasK && kval < 0)) tmc_clear_otpw(stepperK);
193
+    #endif
194
+
167 195
     #if M91x_SOME_E
168 196
       const int8_t eval = int8_t(parser.byteval(axis_codes.e, 0xFF));
169 197
       #if M91x_USE_E(0)
@@ -206,126 +234,76 @@
206 234
     #define TMC_SET_PWMTHRS_E(E) stepperE##E.set_pwm_thrs(value)
207 235
 
208 236
     bool report = true;
209
-    #if AXIS_IS_TMC(X) || AXIS_IS_TMC(X2) || AXIS_IS_TMC(Y) || AXIS_IS_TMC(Y2) || AXIS_IS_TMC(Z) || AXIS_IS_TMC(Z2) || AXIS_IS_TMC(Z3) || AXIS_IS_TMC(Z4)
237
+    #if AXIS_IS_TMC(X) || AXIS_IS_TMC(X2) || AXIS_IS_TMC(Y) || AXIS_IS_TMC(Y2) || AXIS_IS_TMC(Z) || AXIS_IS_TMC(Z2) || AXIS_IS_TMC(Z3) || AXIS_IS_TMC(Z4) || AXIS_IS_TMC(I) || AXIS_IS_TMC(J) || AXIS_IS_TMC(K)
210 238
       const uint8_t index = parser.byteval('I');
211 239
     #endif
212 240
     LOOP_LOGICAL_AXES(i) if (int32_t value = parser.longval(axis_codes[i])) {
213 241
       report = false;
214 242
       switch (i) {
215 243
         case X_AXIS:
216
-          #if AXIS_HAS_STEALTHCHOP(X)
217
-            if (index < 2) TMC_SET_PWMTHRS(X,X);
218
-          #endif
219
-          #if AXIS_HAS_STEALTHCHOP(X2)
220
-            if (!(index & 1)) TMC_SET_PWMTHRS(X,X2);
221
-          #endif
244
+          TERN_(X_HAS_STEALTHCHOP,  if (index < 2) TMC_SET_PWMTHRS(X,X));
245
+          TERN_(X2_HAS_STEALTHCHOP, if (!(index & 1)) TMC_SET_PWMTHRS(X,X2));
222 246
           break;
223 247
         case Y_AXIS:
224
-          #if AXIS_HAS_STEALTHCHOP(Y)
225
-            if (index < 2) TMC_SET_PWMTHRS(Y,Y);
226
-          #endif
227
-          #if AXIS_HAS_STEALTHCHOP(Y2)
228
-            if (!(index & 1)) TMC_SET_PWMTHRS(Y,Y2);
229
-          #endif
248
+          TERN_(Y_HAS_STEALTHCHOP,  if (index < 2) TMC_SET_PWMTHRS(Y,Y));
249
+          TERN_(Y2_HAS_STEALTHCHOP, if (!(index & 1)) TMC_SET_PWMTHRS(Y,Y2));
230 250
           break;
251
+
252
+        #if I_HAS_STEALTHCHOP
253
+          case I_AXIS: TMC_SET_PWMTHRS(I,I); break;
254
+        #endif
255
+        #if J_HAS_STEALTHCHOP
256
+          case J_AXIS: TMC_SET_PWMTHRS(J,J); break;
257
+        #endif
258
+        #if K_HAS_STEALTHCHOP
259
+          case K_AXIS: TMC_SET_PWMTHRS(K,K); break;
260
+        #endif
261
+
231 262
         case Z_AXIS:
232
-          #if AXIS_HAS_STEALTHCHOP(Z)
233
-            if (index < 2) TMC_SET_PWMTHRS(Z,Z);
234
-          #endif
235
-          #if AXIS_HAS_STEALTHCHOP(Z2)
236
-            if (index == 0 || index == 2) TMC_SET_PWMTHRS(Z,Z2);
237
-          #endif
238
-          #if AXIS_HAS_STEALTHCHOP(Z3)
239
-            if (index == 0 || index == 3) TMC_SET_PWMTHRS(Z,Z3);
240
-          #endif
241
-          #if AXIS_HAS_STEALTHCHOP(Z4)
242
-            if (index == 0 || index == 4) TMC_SET_PWMTHRS(Z,Z4);
243
-          #endif
263
+          TERN_(Z_HAS_STEALTCHOP, if (index < 2) TMC_SET_PWMTHRS(Z,Z));
264
+          TERN_(Z2_HAS_STEALTCHOP, if (index == 0 || index == 2) TMC_SET_PWMTHRS(Z,Z2));
265
+          TERN_(Z3_HAS_STEALTCHOP, if (index == 0 || index == 3) TMC_SET_PWMTHRS(Z,Z3));
266
+          TERN_(Z4_HAS_STEALTCHOP, if (index == 0 || index == 4) TMC_SET_PWMTHRS(Z,Z4));
244 267
           break;
245 268
         case E_AXIS: {
246 269
           #if E_STEPPERS
247 270
             const int8_t target_extruder = get_target_extruder_from_command();
248 271
             if (target_extruder < 0) return;
249
-            switch (target_extruder) {
250
-              #if AXIS_HAS_STEALTHCHOP(E0)
251
-                case 0: TMC_SET_PWMTHRS_E(0); break;
252
-              #endif
253
-              #if E_STEPPERS > 1 && AXIS_HAS_STEALTHCHOP(E1)
254
-                case 1: TMC_SET_PWMTHRS_E(1); break;
255
-              #endif
256
-              #if E_STEPPERS > 2 && AXIS_HAS_STEALTHCHOP(E2)
257
-                case 2: TMC_SET_PWMTHRS_E(2); break;
258
-              #endif
259
-              #if E_STEPPERS > 3 && AXIS_HAS_STEALTHCHOP(E3)
260
-                case 3: TMC_SET_PWMTHRS_E(3); break;
261
-              #endif
262
-              #if E_STEPPERS > 4 && AXIS_HAS_STEALTHCHOP(E4)
263
-                case 4: TMC_SET_PWMTHRS_E(4); break;
264
-              #endif
265
-              #if E_STEPPERS > 5 && AXIS_HAS_STEALTHCHOP(E5)
266
-                case 5: TMC_SET_PWMTHRS_E(5); break;
267
-              #endif
268
-              #if E_STEPPERS > 6 && AXIS_HAS_STEALTHCHOP(E6)
269
-                case 6: TMC_SET_PWMTHRS_E(6); break;
270
-              #endif
271
-              #if E_STEPPERS > 7 && AXIS_HAS_STEALTHCHOP(E7)
272
-                case 7: TMC_SET_PWMTHRS_E(7); break;
273
-              #endif
274
-            }
272
+            TERN_(E0_HAS_STEALTHCHOP, else if (target_extruder == 0) TMC_SET_PWMTHRS_E(0));
273
+            TERN_(E1_HAS_STEALTHCHOP, else if (target_extruder == 1) TMC_SET_PWMTHRS_E(1));
274
+            TERN_(E2_HAS_STEALTHCHOP, else if (target_extruder == 2) TMC_SET_PWMTHRS_E(2));
275
+            TERN_(E3_HAS_STEALTHCHOP, else if (target_extruder == 3) TMC_SET_PWMTHRS_E(3));
276
+            TERN_(E4_HAS_STEALTHCHOP, else if (target_extruder == 4) TMC_SET_PWMTHRS_E(4));
277
+            TERN_(E5_HAS_STEALTHCHOP, else if (target_extruder == 5) TMC_SET_PWMTHRS_E(5));
278
+            TERN_(E6_HAS_STEALTHCHOP, else if (target_extruder == 6) TMC_SET_PWMTHRS_E(6));
279
+            TERN_(E7_HAS_STEALTHCHOP, else if (target_extruder == 7) TMC_SET_PWMTHRS_E(7));
275 280
           #endif // E_STEPPERS
276 281
         } break;
277 282
       }
278 283
     }
279 284
 
280 285
     if (report) {
281
-      #if AXIS_HAS_STEALTHCHOP(X)
282
-        TMC_SAY_PWMTHRS(X,X);
283
-      #endif
284
-      #if AXIS_HAS_STEALTHCHOP(X2)
285
-        TMC_SAY_PWMTHRS(X,X2);
286
-      #endif
287
-      #if AXIS_HAS_STEALTHCHOP(Y)
288
-        TMC_SAY_PWMTHRS(Y,Y);
289
-      #endif
290
-      #if AXIS_HAS_STEALTHCHOP(Y2)
291
-        TMC_SAY_PWMTHRS(Y,Y2);
292
-      #endif
293
-      #if AXIS_HAS_STEALTHCHOP(Z)
294
-        TMC_SAY_PWMTHRS(Z,Z);
295
-      #endif
296
-      #if AXIS_HAS_STEALTHCHOP(Z2)
297
-        TMC_SAY_PWMTHRS(Z,Z2);
298
-      #endif
299
-      #if AXIS_HAS_STEALTHCHOP(Z3)
300
-        TMC_SAY_PWMTHRS(Z,Z3);
301
-      #endif
302
-      #if AXIS_HAS_STEALTHCHOP(Z4)
303
-        TMC_SAY_PWMTHRS(Z,Z4);
304
-      #endif
305
-      #if E_STEPPERS && AXIS_HAS_STEALTHCHOP(E0)
306
-        TMC_SAY_PWMTHRS_E(0);
307
-      #endif
308
-      #if E_STEPPERS > 1 && AXIS_HAS_STEALTHCHOP(E1)
309
-        TMC_SAY_PWMTHRS_E(1);
310
-      #endif
311
-      #if E_STEPPERS > 2 && AXIS_HAS_STEALTHCHOP(E2)
312
-        TMC_SAY_PWMTHRS_E(2);
313
-      #endif
314
-      #if E_STEPPERS > 3 && AXIS_HAS_STEALTHCHOP(E3)
315
-        TMC_SAY_PWMTHRS_E(3);
316
-      #endif
317
-      #if E_STEPPERS > 4 && AXIS_HAS_STEALTHCHOP(E4)
318
-        TMC_SAY_PWMTHRS_E(4);
319
-      #endif
320
-      #if E_STEPPERS > 5 && AXIS_HAS_STEALTHCHOP(E5)
321
-        TMC_SAY_PWMTHRS_E(5);
322
-      #endif
323
-      #if E_STEPPERS > 6 && AXIS_HAS_STEALTHCHOP(E6)
324
-        TMC_SAY_PWMTHRS_E(6);
325
-      #endif
326
-      #if E_STEPPERS > 7 && AXIS_HAS_STEALTHCHOP(E7)
327
-        TMC_SAY_PWMTHRS_E(7);
328
-      #endif
286
+      TERN_( X_HAS_STEALTHCHOP, TMC_SAY_PWMTHRS(X,X));
287
+      TERN_(X2_HAS_STEALTHCHOP, TMC_SAY_PWMTHRS(X,X2));
288
+      TERN_( Y_HAS_STEALTHCHOP, TMC_SAY_PWMTHRS(Y,Y));
289
+      TERN_(Y2_HAS_STEALTHCHOP, TMC_SAY_PWMTHRS(Y,Y2));
290
+      TERN_( Z_HAS_STEALTHCHOP, TMC_SAY_PWMTHRS(Z,Z));
291
+      TERN_(Z2_HAS_STEALTHCHOP, TMC_SAY_PWMTHRS(Z,Z2));
292
+      TERN_(Z3_HAS_STEALTHCHOP, TMC_SAY_PWMTHRS(Z,Z3));
293
+      TERN_(Z4_HAS_STEALTHCHOP, TMC_SAY_PWMTHRS(Z,Z4));
294
+
295
+      TERN_( I_HAS_STEALTHCHOP, TMC_SAY_PWMTHRS(I,I));
296
+      TERN_( J_HAS_STEALTHCHOP, TMC_SAY_PWMTHRS(J,J));
297
+      TERN_( K_HAS_STEALTHCHOP, TMC_SAY_PWMTHRS(K,K));
298
+
299
+      TERN_(E0_HAS_STEALTHCHOP, TMC_SAY_PWMTHRS_E(0));
300
+      TERN_(E1_HAS_STEALTHCHOP, TMC_SAY_PWMTHRS_E(1));
301
+      TERN_(E2_HAS_STEALTHCHOP, TMC_SAY_PWMTHRS_E(2));
302
+      TERN_(E3_HAS_STEALTHCHOP, TMC_SAY_PWMTHRS_E(3));
303
+      TERN_(E4_HAS_STEALTHCHOP, TMC_SAY_PWMTHRS_E(4));
304
+      TERN_(E5_HAS_STEALTHCHOP, TMC_SAY_PWMTHRS_E(5));
305
+      TERN_(E6_HAS_STEALTHCHOP, TMC_SAY_PWMTHRS_E(6));
306
+      TERN_(E7_HAS_STEALTHCHOP, TMC_SAY_PWMTHRS_E(7));
329 307
     }
330 308
   }
331 309
 #endif // HYBRID_THRESHOLD
@@ -378,6 +356,15 @@
378 356
             #endif
379 357
             break;
380 358
         #endif
359
+        #if I_SENSORLESS && AXIS_HAS_STALLGUARD(I)
360
+          case I_AXIS: stepperI.homing_threshold(value); break;
361
+        #endif
362
+        #if J_SENSORLESS && AXIS_HAS_STALLGUARD(J)
363
+          case J_AXIS: stepperJ.homing_threshold(value); break;
364
+        #endif
365
+        #if K_SENSORLESS && AXIS_HAS_STALLGUARD(K)
366
+          case K_AXIS: stepperK.homing_threshold(value); break;
367
+        #endif
381 368
       }
382 369
     }
383 370
 
@@ -412,6 +399,15 @@
412 399
           tmc_print_sgt(stepperZ4);
413 400
         #endif
414 401
       #endif
402
+      #if I_SENSORLESS && AXIS_HAS_STALLGUARD(I)
403
+        tmc_print_sgt(stepperI);
404
+      #endif
405
+      #if J_SENSORLESS && AXIS_HAS_STALLGUARD(J)
406
+        tmc_print_sgt(stepperJ);
407
+      #endif
408
+      #if K_SENSORLESS && AXIS_HAS_STALLGUARD(K)
409
+        tmc_print_sgt(stepperK);
410
+      #endif
415 411
     }
416 412
   }
417 413
 #endif // USE_SENSORLESS

+ 4
- 1
Marlin/src/gcode/gcode.cpp View File

@@ -78,7 +78,10 @@ uint8_t GcodeSuite::axis_relative = 0 LOGICAL_AXIS_GANG(
78 78
   | (ar_init.e << REL_E),
79 79
   | (ar_init.x << REL_X),
80 80
   | (ar_init.y << REL_Y),
81
-  | (ar_init.z << REL_Z)
81
+  | (ar_init.z << REL_Z),
82
+  | (ar_init.i << REL_I),
83
+  | (ar_init.j << REL_J),
84
+  | (ar_init.k << REL_K)
82 85
 );
83 86
 
84 87
 #if EITHER(HAS_AUTO_REPORTING, HOST_KEEPALIVE_FEATURE)

+ 6
- 2
Marlin/src/gcode/gcode.h View File

@@ -315,7 +315,7 @@
315 315
 #endif
316 316
 
317 317
 enum AxisRelative : uint8_t {
318
-  LOGICAL_AXIS_LIST(REL_E, REL_X, REL_Y, REL_Z)
318
+  LOGICAL_AXIS_LIST(REL_E, REL_X, REL_Y, REL_Z, REL_I, REL_J, REL_K)
319 319
   #if HAS_EXTRUDERS
320 320
     , E_MODE_ABS, E_MODE_REL
321 321
   #endif
@@ -338,7 +338,11 @@ public:
338 338
     return TEST(axis_relative, a);
339 339
   }
340 340
   static inline void set_relative_mode(const bool rel) {
341
-    axis_relative = rel ? (0 LOGICAL_AXIS_GANG(| _BV(REL_E), | _BV(REL_X), | _BV(REL_Y), | _BV(REL_Z))) : 0;
341
+    axis_relative = rel ? (0 LOGICAL_AXIS_GANG(
342
+      | _BV(REL_E),
343
+      | _BV(REL_X), | _BV(REL_Y), | _BV(REL_Z),
344
+      | _BV(REL_I), | _BV(REL_J), | _BV(REL_K)
345
+    )) : 0;
342 346
   }
343 347
   #if HAS_EXTRUDERS
344 348
     static inline void set_e_relative() {

+ 11
- 2
Marlin/src/gcode/geometry/M206_M428.cpp View File

@@ -31,7 +31,16 @@
31 31
 #include "../../MarlinCore.h"
32 32
 
33 33
 void M206_report() {
34
-  SERIAL_ECHOLNPAIR_P(PSTR("M206 X"), home_offset.x, SP_Y_STR, home_offset.y, SP_Z_STR, home_offset.z);
34
+  SERIAL_ECHOLNPAIR_P(
35
+    LIST_N(DOUBLE(LINEAR_AXES),
36
+      PSTR("M206 X"), home_offset.x,
37
+      SP_Y_STR, home_offset.y,
38
+      SP_Z_STR, home_offset.z,
39
+      SP_I_STR, home_offset.i,
40
+      SP_J_STR, home_offset.j,
41
+      SP_K_STR, home_offset.k,
42
+    )
43
+  );
35 44
 }
36 45
 
37 46
 /**
@@ -51,7 +60,7 @@ void GcodeSuite::M206() {
51 60
     if (parser.seen('P')) set_home_offset(B_AXIS, parser.value_float()); // Psi
52 61
   #endif
53 62
 
54
-  if (!parser.seen("XYZ"))
63
+  if (!parser.seen(LINEAR_AXIS_GANG("X", "Y", "Z", "I", "J", "K")))
55 64
     M206_report();
56 65
   else
57 66
     report_current_position();

+ 16
- 1
Marlin/src/gcode/host/M114.cpp View File

@@ -125,6 +125,15 @@
125 125
       #if AXIS_IS_L64XX(Z4)
126 126
         REPORT_ABSOLUTE_POS(Z4);
127 127
       #endif
128
+      #if AXIS_IS_L64XX(I)
129
+        REPORT_ABSOLUTE_POS(I);
130
+      #endif
131
+      #if AXIS_IS_L64XX(J)
132
+        REPORT_ABSOLUTE_POS(J);
133
+      #endif
134
+      #if AXIS_IS_L64XX(K)
135
+        REPORT_ABSOLUTE_POS(K);
136
+      #endif
128 137
       #if AXIS_IS_L64XX(E0)
129 138
         REPORT_ABSOLUTE_POS(E0);
130 139
       #endif
@@ -170,7 +179,13 @@
170 179
 
171 180
     SERIAL_ECHOPGM("FromStp:");
172 181
     get_cartesian_from_steppers();  // writes 'cartes' (with forward kinematics)
173
-    xyze_pos_t from_steppers = LOGICAL_AXIS_ARRAY(planner.get_axis_position_mm(E_AXIS), cartes.x, cartes.y, cartes.z);
182
+    xyze_pos_t from_steppers = LOGICAL_AXIS_ARRAY(
183
+      planner.get_axis_position_mm(E_AXIS),
184
+      cartes.x, cartes.y, cartes.z,
185
+      planner.get_axis_position_mm(I_AXIS),
186
+      planner.get_axis_position_mm(J_AXIS),
187
+      planner.get_axis_position_mm(K_AXIS)
188
+    );
174 189
     report_all_axis_pos(from_steppers);
175 190
 
176 191
     const xyze_float_t diff = from_steppers - leveled;

+ 7
- 2
Marlin/src/gcode/motion/G0_G1.cpp View File

@@ -52,7 +52,10 @@ void GcodeSuite::G0_G1(TERN_(HAS_FAST_MOVES, const bool fast_move/*=false*/)) {
52 52
         LINEAR_AXIS_GANG(
53 53
             (parser.seen_test('X') ? _BV(X_AXIS) : 0),
54 54
           | (parser.seen_test('Y') ? _BV(Y_AXIS) : 0),
55
-          | (parser.seen_test('Z') ? _BV(Z_AXIS) : 0))
55
+          | (parser.seen_test('Z') ? _BV(Z_AXIS) : 0),
56
+          | (parser.seen_test(AXIS4_NAME) ? _BV(I_AXIS) : 0),
57
+          | (parser.seen_test(AXIS5_NAME) ? _BV(J_AXIS) : 0),
58
+          | (parser.seen_test(AXIS6_NAME) ? _BV(K_AXIS) : 0))
56 59
       )
57 60
     #endif
58 61
   ) {
@@ -85,7 +88,9 @@ void GcodeSuite::G0_G1(TERN_(HAS_FAST_MOVES, const bool fast_move/*=false*/)) {
85 88
 
86 89
       if (MIN_AUTORETRACT <= MAX_AUTORETRACT) {
87 90
         // When M209 Autoretract is enabled, convert E-only moves to firmware retract/recover moves
88
-        if (fwretract.autoretract_enabled && parser.seen_test('E') && !parser.seen(LINEAR_AXIS_GANG("X", "Y", "Z"))) {
91
+        if (fwretract.autoretract_enabled && parser.seen_test('E')
92
+          && !parser.seen(LINEAR_AXIS_GANG("X", "Y", "Z", AXIS4_STR, AXIS5_STR, AXIS6_STR))
93
+        ) {
89 94
           const float echange = destination.e - current_position.e;
90 95
           // Is this a retract or recover move?
91 96
           if (WITHIN(ABS(echange), MIN_AUTORETRACT, MAX_AUTORETRACT) && fwretract.retracted[active_extruder] == (echange > 0.0)) {

+ 22
- 22
Marlin/src/gcode/motion/G2_G3.cpp View File

@@ -63,7 +63,7 @@ void plan_arc(
63 63
       case GcodeSuite::PLANE_ZX: p_axis = Z_AXIS; q_axis = X_AXIS; l_axis = Y_AXIS; break;
64 64
     }
65 65
   #else
66
-    constexpr AxisEnum p_axis = X_AXIS, q_axis = Y_AXIS, l_axis = Z_AXIS;
66
+    constexpr AxisEnum p_axis = X_AXIS, q_axis = Y_AXIS OPTARG(HAS_Z_AXIS, l_axis = Z_AXIS);
67 67
   #endif
68 68
 
69 69
   // Radius vector from center to current location
@@ -73,8 +73,8 @@ void plan_arc(
73 73
               center_P = current_position[p_axis] - rvec.a,
74 74
               center_Q = current_position[q_axis] - rvec.b,
75 75
               rt_X = cart[p_axis] - center_P,
76
-              rt_Y = cart[q_axis] - center_Q,
77
-              start_L = current_position[l_axis];
76
+              rt_Y = cart[q_axis] - center_Q
77
+              OPTARG(HAS_Z_AXIS, start_L = current_position[l_axis]);
78 78
 
79 79
   #ifdef MIN_ARC_SEGMENTS
80 80
     uint16_t min_segments = MIN_ARC_SEGMENTS;
@@ -109,8 +109,9 @@ void plan_arc(
109 109
     #endif
110 110
   }
111 111
 
112
-  float linear_travel = cart[l_axis] - start_L;
113
-
112
+  #if HAS_Z_AXIS
113
+    float linear_travel = cart[l_axis] - start_L;
114
+  #endif
114 115
   #if HAS_EXTRUDERS
115 116
     float extruder_travel = cart.e - current_position.e;
116 117
   #endif
@@ -118,9 +119,11 @@ void plan_arc(
118 119
   // If circling around...
119 120
   if (ENABLED(ARC_P_CIRCLES) && circles) {
120 121
     const float total_angular = angular_travel + circles * RADIANS(360),  // Total rotation with all circles and remainder
121
-              part_per_circle = RADIANS(360) / total_angular,             // Each circle's part of the total
122
-                 l_per_circle = linear_travel * part_per_circle;          // L movement per circle
122
+              part_per_circle = RADIANS(360) / total_angular;             // Each circle's part of the total
123 123
 
124
+    #if HAS_Z_AXIS
125
+      const float l_per_circle = linear_travel * part_per_circle;         // L movement per circle
126
+    #endif
124 127
     #if HAS_EXTRUDERS
125 128
       const float e_per_circle = extruder_travel * part_per_circle;       // E movement per circle
126 129
     #endif
@@ -128,17 +131,15 @@ void plan_arc(
128 131
     xyze_pos_t temp_position = current_position;                          // for plan_arc to compare to current_position
129 132
     for (uint16_t n = circles; n--;) {
130 133
       TERN_(HAS_EXTRUDERS, temp_position.e += e_per_circle);              // Destination E axis
131
-      temp_position[l_axis] += l_per_circle;                              // Destination L axis
134
+      TERN_(HAS_Z_AXIS, temp_position[l_axis] += l_per_circle);           // Destination L axis
132 135
       plan_arc(temp_position, offset, clockwise, 0);                      // Plan a single whole circle
133 136
     }
134
-    linear_travel = cart[l_axis] - current_position[l_axis];
135
-    #if HAS_EXTRUDERS
136
-      extruder_travel = cart.e - current_position.e;
137
-    #endif
137
+    TERN_(HAS_Z_AXIS, linear_travel = cart[l_axis] - current_position[l_axis]);
138
+    TERN_(HAS_EXTRUDERS, extruder_travel = cart.e - current_position.e);
138 139
   }
139 140
 
140 141
   const float flat_mm = radius * angular_travel,
141
-              mm_of_travel = linear_travel ? HYPOT(flat_mm, linear_travel) : ABS(flat_mm);
142
+              mm_of_travel = TERN_(HAS_Z_AXIS, linear_travel ? HYPOT(flat_mm, linear_travel) :) ABS(flat_mm);
142 143
   if (mm_of_travel < 0.001f) return;
143 144
 
144 145
   const feedRate_t scaled_fr_mm_s = MMS_SCALED(feedrate_mm_s);
@@ -187,17 +188,19 @@ void plan_arc(
187 188
   // Vector rotation matrix values
188 189
   xyze_pos_t raw;
189 190
   const float theta_per_segment = angular_travel / segments,
190
-              linear_per_segment = linear_travel / segments,
191 191
               sq_theta_per_segment = sq(theta_per_segment),
192 192
               sin_T = theta_per_segment - sq_theta_per_segment * theta_per_segment / 6,
193 193
               cos_T = 1 - 0.5f * sq_theta_per_segment; // Small angle approximation
194 194
 
195
+  #if HAS_Z_AXIS && DISABLED(AUTO_BED_LEVELING_UBL)
196
+    const float linear_per_segment = linear_travel / segments;
197
+  #endif
195 198
   #if HAS_EXTRUDERS
196 199
     const float extruder_per_segment = extruder_travel / segments;
197 200
   #endif
198 201
 
199 202
   // Initialize the linear axis
200
-  raw[l_axis] = current_position[l_axis];
203
+  TERN_(HAS_Z_AXIS, raw[l_axis] = current_position[l_axis]);
201 204
 
202 205
   // Initialize the extruder axis
203 206
   TERN_(HAS_EXTRUDERS, raw.e = current_position.e);
@@ -246,11 +249,8 @@ void plan_arc(
246 249
     // Update raw location
247 250
     raw[p_axis] = center_P + rvec.a;
248 251
     raw[q_axis] = center_Q + rvec.b;
249
-    #if ENABLED(AUTO_BED_LEVELING_UBL)
250
-      raw[l_axis] = start_L;
251
-      UNUSED(linear_per_segment);
252
-    #else
253
-      raw[l_axis] += linear_per_segment;
252
+    #if HAS_Z_AXIS
253
+      raw[l_axis] = TERN(AUTO_BED_LEVELING_UBL, start_L, raw[l_axis] + linear_per_segment);
254 254
     #endif
255 255
 
256 256
     TERN_(HAS_EXTRUDERS, raw.e += extruder_per_segment);
@@ -268,7 +268,7 @@ void plan_arc(
268 268
 
269 269
   // Ensure last segment arrives at target location.
270 270
   raw = cart;
271
-  TERN_(AUTO_BED_LEVELING_UBL, raw[l_axis] = start_L);
271
+  TERN_(AUTO_BED_LEVELING_UBL, TERN_(HAS_Z_AXIS, raw[l_axis] = start_L));
272 272
 
273 273
   apply_motion_limits(raw);
274 274
 
@@ -280,7 +280,7 @@ void plan_arc(
280 280
     OPTARG(SCARA_FEEDRATE_SCALING, inv_duration)
281 281
   );
282 282
 
283
-  TERN_(AUTO_BED_LEVELING_UBL, raw[l_axis] = start_L);
283
+  TERN_(AUTO_BED_LEVELING_UBL, TERN_(HAS_Z_AXIS, raw[l_axis] = start_L));
284 284
   current_position = raw;
285 285
 
286 286
 } // plan_arc

+ 1
- 1
Marlin/src/gcode/motion/M290.cpp View File

@@ -87,7 +87,7 @@ void GcodeSuite::M290() {
87 87
     }
88 88
   #endif
89 89
 
90
-  if (!parser.seen(LINEAR_AXIS_GANG("X", "Y", "Z")) || parser.seen('R')) {
90
+  if (!parser.seen(LINEAR_AXIS_GANG("X", "Y", "Z", AXIS4_STR, AXIS5_STR, AXIS6_STR)) || parser.seen('R')) {
91 91
     SERIAL_ECHO_START();
92 92
 
93 93
     #if ENABLED(BABYSTEP_ZPROBE_OFFSET)

+ 1
- 1
Marlin/src/gcode/parser.cpp View File

@@ -248,7 +248,7 @@ void GCodeParser::parse(char *p) {
248 248
         case 'R': if (!WITHIN(motion_mode_codenum, 2, 3)) return;
249 249
       #endif
250 250
 
251
-      LOGICAL_AXIS_GANG(case 'E':, case 'X':, case 'Y':, case 'Z':)
251
+      LOGICAL_AXIS_GANG(case 'E':, case 'X':, case 'Y':, case 'Z':, case AXIS4_NAME:, case AXIS5_NAME:, case AXIS6_NAME:)
252 252
       case 'F':
253 253
         if (motion_mode_codenum < 0) return;
254 254
         command_letter = 'G';

+ 1
- 1
Marlin/src/gcode/parser.h View File

@@ -226,7 +226,7 @@ public:
226 226
 
227 227
   // Seen any axis parameter
228 228
   static inline bool seen_axis() {
229
-    return seen(LOGICAL_AXIS_GANG("E", "X", "Y", "Z"));
229
+    return seen(LOGICAL_AXIS_GANG("E", "X", "Y", "Z", AXIS4_STR, AXIS5_STR, AXIS6_STR));
230 230
   }
231 231
 
232 232
   #if ENABLED(GCODE_QUOTED_STRINGS)

+ 2
- 0
Marlin/src/gcode/temp/M106_M107.cpp View File

@@ -83,6 +83,8 @@ void GcodeSuite::M106() {
83 83
     if (!got_preset && parser.seenval('S'))
84 84
       speed = parser.value_ushort();
85 85
 
86
+    TERN_(FOAMCUTTER_XYUV, speed *= 2.55); // Get command in % of max heat
87
+
86 88
     // Set speed, with constraint
87 89
     thermalManager.set_fan_speed(pfan, speed);
88 90
 

+ 33
- 7
Marlin/src/inc/Conditionals_LCD.h View File

@@ -612,6 +612,12 @@
612 612
 #ifndef LINEAR_AXES
613 613
   #define LINEAR_AXES XYZ
614 614
 #endif
615
+#if LINEAR_AXES >= XY
616
+  #define HAS_Y_AXIS 1
617
+  #if LINEAR_AXES >= XYZ
618
+    #define HAS_Z_AXIS 1
619
+  #endif
620
+#endif
615 621
 
616 622
 /**
617 623
  * Number of Logical Axes (e.g., XYZE)
@@ -624,10 +630,6 @@
624 630
   #define LOGICAL_AXES LINEAR_AXES
625 631
 #endif
626 632
 
627
-#if LINEAR_AXES >= XYZ
628
-  #define HAS_Z_AXIS 1
629
-#endif
630
-
631 633
 /**
632 634
  * DISTINCT_E_FACTORS is set to give extruders (some) individual settings.
633 635
  *
@@ -852,6 +854,21 @@
852 854
 #elif Z_HOME_DIR < 0
853 855
   #define Z_HOME_TO_MIN 1
854 856
 #endif
857
+#if I_HOME_DIR > 0
858
+  #define I_HOME_TO_MAX 1
859
+#elif I_HOME_DIR < 0
860
+  #define I_HOME_TO_MIN 1
861
+#endif
862
+#if J_HOME_DIR > 0
863
+  #define J_HOME_TO_MAX 1
864
+#elif J_HOME_DIR < 0
865
+  #define J_HOME_TO_MIN 1
866
+#endif
867
+#if K_HOME_DIR > 0
868
+  #define K_HOME_TO_MAX 1
869
+#elif K_HOME_DIR < 0
870
+  #define K_HOME_TO_MIN 1
871
+#endif
855 872
 
856 873
 /**
857 874
  * Conditionals based on the type of Bed Probe
@@ -1110,13 +1127,22 @@
1110 1127
 #ifndef INVERT_X_DIR
1111 1128
   #define INVERT_X_DIR false
1112 1129
 #endif
1113
-#ifndef INVERT_Y_DIR
1130
+#if HAS_Y_AXIS && !defined(INVERT_Y_DIR)
1114 1131
   #define INVERT_Y_DIR false
1115 1132
 #endif
1116
-#ifndef INVERT_Z_DIR
1133
+#if HAS_Z_AXIS && !defined(INVERT_Z_DIR)
1117 1134
   #define INVERT_Z_DIR false
1118 1135
 #endif
1119
-#ifndef INVERT_E_DIR
1136
+#if LINEAR_AXES >= 4 && !defined(INVERT_I_DIR)
1137
+  #define INVERT_I_DIR false
1138
+#endif
1139
+#if LINEAR_AXES >= 5 && !defined(INVERT_J_DIR)
1140
+  #define INVERT_J_DIR false
1141
+#endif
1142
+#if LINEAR_AXES >= 6 && !defined(INVERT_K_DIR)
1143
+  #define INVERT_K_DIR false
1144
+#endif
1145
+#if HAS_EXTRUDERS && !defined(INVERT_E_DIR)
1120 1146
   #define INVERT_E_DIR false
1121 1147
 #endif
1122 1148
 

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

@@ -26,6 +26,10 @@
26 26
  * Defines that depend on advanced configuration.
27 27
  */
28 28
 
29
+#ifndef AXIS_RELATIVE_MODES
30
+  #define AXIS_RELATIVE_MODES {}
31
+#endif
32
+
29 33
 #ifdef SWITCHING_NOZZLE_E1_SERVO_NR
30 34
   #define SWITCHING_NOZZLE_TWO_SERVOS 1
31 35
 #endif
@@ -488,12 +492,26 @@
488 492
 // Remove unused STEALTHCHOP flags
489 493
 #if LINEAR_AXES < 6
490 494
   #undef STEALTHCHOP_K
495
+  #undef CALIBRATION_MEASURE_KMIN
496
+  #undef CALIBRATION_MEASURE_KMAX
491 497
   #if LINEAR_AXES < 5
492 498
     #undef STEALTHCHOP_J
499
+    #undef CALIBRATION_MEASURE_JMIN
500
+    #undef CALIBRATION_MEASURE_JMAX
493 501
     #if LINEAR_AXES < 4
494 502
       #undef STEALTHCHOP_I
503
+      #undef CALIBRATION_MEASURE_IMIN
504
+      #undef CALIBRATION_MEASURE_IMAX
495 505
       #if LINEAR_AXES < 3
506
+        #undef Z_IDLE_HEIGHT
496 507
         #undef STEALTHCHOP_Z
508
+        #undef Z_PROBE_SLED
509
+        #undef Z_SAFE_HOMING
510
+        #undef HOME_Z_FIRST
511
+        #undef HOMING_Z_WITH_PROBE
512
+        #undef ENABLE_LEVELING_FADE_HEIGHT
513
+        #undef NUM_Z_STEPPER_DRIVERS
514
+        #undef CNC_WORKSPACE_PLANES
497 515
         #if LINEAR_AXES < 2
498 516
           #undef STEALTHCHOP_Y
499 517
         #endif

+ 367
- 87
Marlin/src/inc/Conditionals_post.h View File

@@ -78,17 +78,49 @@
78 78
 /**
79 79
  * Axis lengths and center
80 80
  */
81
+#ifndef AXIS4_NAME
82
+  #define AXIS4_NAME 'A'
83
+#endif
84
+#ifndef AXIS5_NAME
85
+  #define AXIS5_NAME 'B'
86
+#endif
87
+#ifndef AXIS6_NAME
88
+  #define AXIS6_NAME 'C'
89
+#endif
90
+
81 91
 #define X_MAX_LENGTH (X_MAX_POS - (X_MIN_POS))
82
-#define Y_MAX_LENGTH (Y_MAX_POS - (Y_MIN_POS))
83
-#define Z_MAX_LENGTH (Z_MAX_POS - (Z_MIN_POS))
92
+#if HAS_Y_AXIS
93
+  #define Y_MAX_LENGTH (Y_MAX_POS - (Y_MIN_POS))
94
+#endif
95
+#if HAS_Z_AXIS
96
+  #define Z_MAX_LENGTH (Z_MAX_POS - (Z_MIN_POS))
97
+#endif
98
+#if LINEAR_AXES >= 4
99
+  #define I_MAX_LENGTH (I_MAX_POS - (I_MIN_POS))
100
+#endif
101
+#if LINEAR_AXES >= 5
102
+  #define J_MAX_LENGTH (J_MAX_POS - (J_MIN_POS))
103
+#endif
104
+#if LINEAR_AXES >= 6
105
+  #define K_MAX_LENGTH (K_MAX_POS - (K_MIN_POS))
106
+#endif
84 107
 
85 108
 // Defined only if the sanity-check is bypassed
86 109
 #ifndef X_BED_SIZE
87 110
   #define X_BED_SIZE X_MAX_LENGTH
88 111
 #endif
89
-#ifndef Y_BED_SIZE
112
+#if HAS_Y_AXIS && !defined(Y_BED_SIZE)
90 113
   #define Y_BED_SIZE Y_MAX_LENGTH
91 114
 #endif
115
+#if LINEAR_AXES >= 4 && !defined(I_BED_SIZE)
116
+  #define I_BED_SIZE I_MAX_LENGTH
117
+#endif
118
+#if LINEAR_AXES >= 5 && !defined(J_BED_SIZE)
119
+  #define J_BED_SIZE J_MAX_LENGTH
120
+#endif
121
+#if LINEAR_AXES >= 6 && !defined(K_BED_SIZE)
122
+  #define K_BED_SIZE K_MAX_LENGTH
123
+#endif
92 124
 
93 125
 // Require 0,0 bed center for Delta and SCARA
94 126
 #if IS_KINEMATIC
@@ -97,16 +129,53 @@
97 129
 
98 130
 // Define center values for future use
99 131
 #define _X_HALF_BED ((X_BED_SIZE) / 2)
100
-#define _Y_HALF_BED ((Y_BED_SIZE) / 2)
132
+#if HAS_Y_AXIS
133
+  #define _Y_HALF_BED ((Y_BED_SIZE) / 2)
134
+#endif
135
+#if LINEAR_AXES >= 4
136
+  #define _I_HALF_IMAX ((I_BED_SIZE) / 2)
137
+#endif
138
+#if LINEAR_AXES >= 5
139
+  #define _J_HALF_JMAX ((J_BED_SIZE) / 2)
140
+#endif
141
+#if LINEAR_AXES >= 6
142
+  #define _K_HALF_KMAX ((K_BED_SIZE) / 2)
143
+#endif
144
+
101 145
 #define X_CENTER TERN(BED_CENTER_AT_0_0, 0, _X_HALF_BED)
102
-#define Y_CENTER TERN(BED_CENTER_AT_0_0, 0, _Y_HALF_BED)
103
-#define XY_CENTER { X_CENTER, Y_CENTER }
146
+#if HAS_Y_AXIS
147
+  #define Y_CENTER TERN(BED_CENTER_AT_0_0, 0, _Y_HALF_BED)
148
+  #define XY_CENTER { X_CENTER, Y_CENTER }
149
+#endif
150
+#if LINEAR_AXES >= 4
151
+  #define I_CENTER TERN(BED_CENTER_AT_0_0, 0, _I_HALF_BED)
152
+#endif
153
+#if LINEAR_AXES >= 5
154
+  #define J_CENTER TERN(BED_CENTER_AT_0_0, 0, _J_HALF_BED)
155
+#endif
156
+#if LINEAR_AXES >= 6
157
+  #define K_CENTER TERN(BED_CENTER_AT_0_0, 0, _K_HALF_BED)
158
+#endif
104 159
 
105 160
 // Get the linear boundaries of the bed
106 161
 #define X_MIN_BED (X_CENTER - _X_HALF_BED)
107 162
 #define X_MAX_BED (X_MIN_BED + X_BED_SIZE)
108
-#define Y_MIN_BED (Y_CENTER - _Y_HALF_BED)
109
-#define Y_MAX_BED (Y_MIN_BED + Y_BED_SIZE)
163
+#if HAS_Y_AXIS
164
+  #define Y_MIN_BED (Y_CENTER - _Y_HALF_BED)
165
+  #define Y_MAX_BED (Y_MIN_BED + Y_BED_SIZE)
166
+#endif
167
+#if LINEAR_AXES >= 4
168
+  #define I_MINIM (I_CENTER - _I_HALF_BED_SIZE)
169
+  #define I_MAXIM (I_MINIM + I_BED_SIZE)
170
+#endif
171
+#if LINEAR_AXES >= 5
172
+  #define J_MINIM (J_CENTER - _J_HALF_BED_SIZE)
173
+  #define J_MAXIM (J_MINIM + J_BED_SIZE)
174
+#endif
175
+#if LINEAR_AXES >= 6
176
+  #define K_MINIM (K_CENTER - _K_HALF_BED_SIZE)
177
+  #define K_MAXIM (K_MINIM + K_BED_SIZE)
178
+#endif
110 179
 
111 180
 /**
112 181
  * Dual X Carriage
@@ -163,14 +232,16 @@
163 232
   #endif
164 233
 #endif
165 234
 
166
-#ifdef MANUAL_Y_HOME_POS
167
-  #define Y_HOME_POS MANUAL_Y_HOME_POS
168
-#else
169
-  #define Y_END_POS TERN(Y_HOME_TO_MIN, Y_MIN_POS, Y_MAX_POS)
170
-  #if ENABLED(BED_CENTER_AT_0_0)
171
-    #define Y_HOME_POS TERN(DELTA, 0, Y_END_POS)
235
+#if HAS_Y_AXIS
236
+  #ifdef MANUAL_Y_HOME_POS
237
+    #define Y_HOME_POS MANUAL_Y_HOME_POS
172 238
   #else
173
-    #define Y_HOME_POS TERN(DELTA, Y_MIN_POS + (Y_BED_SIZE) * 0.5, Y_END_POS)
239
+    #define Y_END_POS TERN(Y_HOME_TO_MIN, Y_MIN_POS, Y_MAX_POS)
240
+    #if ENABLED(BED_CENTER_AT_0_0)
241
+      #define Y_HOME_POS TERN(DELTA, 0, Y_END_POS)
242
+    #else
243
+      #define Y_HOME_POS TERN(DELTA, Y_MIN_POS + (Y_BED_SIZE) * 0.5, Y_END_POS)
244
+    #endif
174 245
   #endif
175 246
 #endif
176 247
 
@@ -180,6 +251,28 @@
180 251
   #define Z_HOME_POS TERN(Z_HOME_TO_MIN, Z_MIN_POS, Z_MAX_POS)
181 252
 #endif
182 253
 
254
+#if LINEAR_AXES >= 4
255
+  #ifdef MANUAL_I_HOME_POS
256
+    #define I_HOME_POS MANUAL_I_HOME_POS
257
+  #else
258
+    #define I_HOME_POS TERN(I_HOME_TO_MIN, I_MIN_POS, I_MAX_POS)
259
+  #endif
260
+#endif
261
+#if LINEAR_AXES >= 5
262
+  #ifdef MANUAL_J_HOME_POS
263
+    #define J_HOME_POS MANUAL_J_HOME_POS
264
+  #else
265
+    #define J_HOME_POS TERN(J_HOME_TO_MIN, J_MIN_POS, J_MAX_POS)
266
+  #endif
267
+#endif
268
+#if LINEAR_AXES >= 6
269
+  #ifdef MANUAL_K_HOME_POS
270
+    #define K_HOME_POS MANUAL_K_HOME_POS
271
+  #else
272
+    #define K_HOME_POS TERN(K_HOME_TO_MIN, K_MIN_POS, K_MAX_POS)
273
+  #endif
274
+#endif
275
+
183 276
 /**
184 277
  * If DELTA_HEIGHT isn't defined use the old setting
185 278
  */
@@ -374,15 +467,24 @@
374 467
 #ifndef DISABLE_INACTIVE_X
375 468
   #define DISABLE_INACTIVE_X DISABLE_X
376 469
 #endif
377
-#ifndef DISABLE_INACTIVE_Y
470
+#if HAS_Y_AXIS && !defined(DISABLE_INACTIVE_Y)
378 471
   #define DISABLE_INACTIVE_Y DISABLE_Y
379 472
 #endif
380
-#ifndef DISABLE_INACTIVE_Z
473
+#if HAS_Z_AXIS && !defined(DISABLE_INACTIVE_Z)
381 474
   #define DISABLE_INACTIVE_Z DISABLE_Z
382 475
 #endif
383 476
 #ifndef DISABLE_INACTIVE_E
384 477
   #define DISABLE_INACTIVE_E DISABLE_E
385 478
 #endif
479
+#if LINEAR_AXES >= 4 && !defined(DISABLE_INACTIVE_I)
480
+  #define DISABLE_INACTIVE_I DISABLE_I
481
+#endif
482
+#if LINEAR_AXES >= 5 && !defined(DISABLE_INACTIVE_J)
483
+  #define DISABLE_INACTIVE_J DISABLE_J
484
+#endif
485
+#if LINEAR_AXES >= 6 && !defined(DISABLE_INACTIVE_K)
486
+  #define DISABLE_INACTIVE_K DISABLE_K
487
+#endif
386 488
 
387 489
 /**
388 490
  * Power Supply
@@ -1418,6 +1520,15 @@
1418 1520
   #if ENABLED(USE_ZMAX_PLUG)
1419 1521
     #define ENDSTOPPULLUP_ZMAX
1420 1522
   #endif
1523
+  #if ENABLED(USE_IMAX_PLUG)
1524
+    #define ENDSTOPPULLUP_IMAX
1525
+  #endif
1526
+  #if ENABLED(USE_JMAX_PLUG)
1527
+    #define ENDSTOPPULLUP_JMAX
1528
+  #endif
1529
+  #if ENABLED(USE_KMAX_PLUG)
1530
+    #define ENDSTOPPULLUP_KMAX
1531
+  #endif
1421 1532
   #if ENABLED(USE_XMIN_PLUG)
1422 1533
     #define ENDSTOPPULLUP_XMIN
1423 1534
   #endif
@@ -1427,6 +1538,15 @@
1427 1538
   #if ENABLED(USE_ZMIN_PLUG)
1428 1539
     #define ENDSTOPPULLUP_ZMIN
1429 1540
   #endif
1541
+  #if ENABLED(USE_IMIN_PLUG)
1542
+    #define ENDSTOPPULLUP_IMIN
1543
+  #endif
1544
+  #if ENABLED(USE_JMIN_PLUG)
1545
+    #define ENDSTOPPULLUP_JMIN
1546
+  #endif
1547
+  #if ENABLED(USE_KMIN_PLUG)
1548
+    #define ENDSTOPPULLUP_KMIN
1549
+  #endif
1430 1550
 #endif
1431 1551
 
1432 1552
 /**
@@ -1484,82 +1604,137 @@
1484 1604
   #define HAS_X2_MS_PINS 1
1485 1605
 #endif
1486 1606
 
1487
-#if PIN_EXISTS(Y_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Y))
1488
-  #define HAS_Y_ENABLE 1
1489
-#endif
1490
-#if PIN_EXISTS(Y_DIR)
1491
-  #define HAS_Y_DIR 1
1492
-#endif
1493
-#if PIN_EXISTS(Y_STEP)
1494
-  #define HAS_Y_STEP 1
1495
-#endif
1496
-#if PIN_EXISTS(Y_MS1)
1497
-  #define HAS_Y_MS_PINS 1
1498
-#endif
1607
+#if HAS_Y_AXIS
1608
+  #if PIN_EXISTS(Y_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Y))
1609
+    #define HAS_Y_ENABLE 1
1610
+  #endif
1611
+  #if PIN_EXISTS(Y_DIR)
1612
+    #define HAS_Y_DIR 1
1613
+  #endif
1614
+  #if PIN_EXISTS(Y_STEP)
1615
+    #define HAS_Y_STEP 1
1616
+  #endif
1617
+  #if PIN_EXISTS(Y_MS1)
1618
+    #define HAS_Y_MS_PINS 1
1619
+  #endif
1499 1620
 
1500
-#if PIN_EXISTS(Y2_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Y2))
1501
-  #define HAS_Y2_ENABLE 1
1502
-#endif
1503
-#if PIN_EXISTS(Y2_DIR)
1504
-  #define HAS_Y2_DIR 1
1505
-#endif
1506
-#if PIN_EXISTS(Y2_STEP)
1507
-  #define HAS_Y2_STEP 1
1508
-#endif
1509
-#if PIN_EXISTS(Y2_MS1)
1510
-  #define HAS_Y2_MS_PINS 1
1621
+  #if PIN_EXISTS(Y2_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Y2))
1622
+    #define HAS_Y2_ENABLE 1
1623
+  #endif
1624
+  #if PIN_EXISTS(Y2_DIR)
1625
+    #define HAS_Y2_DIR 1
1626
+  #endif
1627
+  #if PIN_EXISTS(Y2_STEP)
1628
+    #define HAS_Y2_STEP 1
1629
+  #endif
1630
+  #if PIN_EXISTS(Y2_MS1)
1631
+    #define HAS_Y2_MS_PINS 1
1632
+  #endif
1511 1633
 #endif
1512 1634
 
1513
-#if PIN_EXISTS(Z_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Z))
1514
-  #define HAS_Z_ENABLE 1
1515
-#endif
1516
-#if PIN_EXISTS(Z_DIR)
1517
-  #define HAS_Z_DIR 1
1518
-#endif
1519
-#if PIN_EXISTS(Z_STEP)
1520
-  #define HAS_Z_STEP 1
1521
-#endif
1522
-#if PIN_EXISTS(Z_MS1)
1523
-  #define HAS_Z_MS_PINS 1
1635
+#if HAS_Z_AXIS
1636
+  #if PIN_EXISTS(Z_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Z))
1637
+    #define HAS_Z_ENABLE 1
1638
+  #endif
1639
+  #if PIN_EXISTS(Z_DIR)
1640
+    #define HAS_Z_DIR 1
1641
+  #endif
1642
+  #if PIN_EXISTS(Z_STEP)
1643
+    #define HAS_Z_STEP 1
1644
+  #endif
1645
+  #if PIN_EXISTS(Z_MS1)
1646
+    #define HAS_Z_MS_PINS 1
1647
+  #endif
1524 1648
 #endif
1525 1649
 
1526
-#if PIN_EXISTS(Z2_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Z2))
1527
-  #define HAS_Z2_ENABLE 1
1528
-#endif
1529
-#if PIN_EXISTS(Z2_DIR)
1530
-  #define HAS_Z2_DIR 1
1531
-#endif
1532
-#if PIN_EXISTS(Z2_STEP)
1533
-  #define HAS_Z2_STEP 1
1534
-#endif
1535
-#if PIN_EXISTS(Z2_MS1)
1536
-  #define HAS_Z2_MS_PINS 1
1650
+#if NUM_Z_STEPPER_DRIVERS >= 2
1651
+  #if PIN_EXISTS(Z2_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Z2))
1652
+    #define HAS_Z2_ENABLE 1
1653
+  #endif
1654
+  #if PIN_EXISTS(Z2_DIR)
1655
+    #define HAS_Z2_DIR 1
1656
+  #endif
1657
+  #if PIN_EXISTS(Z2_STEP)
1658
+    #define HAS_Z2_STEP 1
1659
+  #endif
1660
+  #if PIN_EXISTS(Z2_MS1)
1661
+    #define HAS_Z2_MS_PINS 1
1662
+  #endif
1537 1663
 #endif
1538 1664
 
1539
-#if PIN_EXISTS(Z3_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Z3))
1540
-  #define HAS_Z3_ENABLE 1
1541
-#endif
1542
-#if PIN_EXISTS(Z3_DIR)
1543
-  #define HAS_Z3_DIR 1
1544
-#endif
1545
-#if PIN_EXISTS(Z3_STEP)
1546
-  #define HAS_Z3_STEP 1
1547
-#endif
1548
-#if PIN_EXISTS(Z3_MS1)
1549
-  #define HAS_Z3_MS_PINS 1
1665
+#if NUM_Z_STEPPER_DRIVERS >= 3
1666
+  #if PIN_EXISTS(Z3_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Z3))
1667
+    #define HAS_Z3_ENABLE 1
1668
+  #endif
1669
+  #if PIN_EXISTS(Z3_DIR)
1670
+    #define HAS_Z3_DIR 1
1671
+  #endif
1672
+  #if PIN_EXISTS(Z3_STEP)
1673
+    #define HAS_Z3_STEP 1
1674
+  #endif
1675
+  #if PIN_EXISTS(Z3_MS1)
1676
+    #define HAS_Z3_MS_PINS 1
1677
+  #endif
1550 1678
 #endif
1551 1679
 
1552
-#if PIN_EXISTS(Z4_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Z4))
1553
-  #define HAS_Z4_ENABLE 1
1680
+#if NUM_Z_STEPPER_DRIVERS >= 4
1681
+  #if PIN_EXISTS(Z4_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Z4))
1682
+    #define HAS_Z4_ENABLE 1
1683
+  #endif
1684
+  #if PIN_EXISTS(Z4_DIR)
1685
+    #define HAS_Z4_DIR 1
1686
+  #endif
1687
+  #if PIN_EXISTS(Z4_STEP)
1688
+    #define HAS_Z4_STEP 1
1689
+  #endif
1690
+  #if PIN_EXISTS(Z4_MS1)
1691
+    #define HAS_Z4_MS_PINS 1
1692
+  #endif
1554 1693
 #endif
1555
-#if PIN_EXISTS(Z4_DIR)
1556
-  #define HAS_Z4_DIR 1
1694
+
1695
+#if LINEAR_AXES >= 4
1696
+  #if PIN_EXISTS(I_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(I))
1697
+    #define HAS_I_ENABLE 1
1698
+  #endif
1699
+  #if PIN_EXISTS(I_DIR)
1700
+    #define HAS_I_DIR 1
1701
+  #endif
1702
+  #if PIN_EXISTS(I_STEP)
1703
+    #define HAS_I_STEP 1
1704
+  #endif
1705
+  #if PIN_EXISTS(I_MS1)
1706
+    #define HAS_I_MS_PINS 1
1707
+  #endif
1557 1708
 #endif
1558
-#if PIN_EXISTS(Z4_STEP)
1559
-  #define HAS_Z4_STEP 1
1709
+
1710
+#if LINEAR_AXES >= 5
1711
+  #if PIN_EXISTS(J_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(J))
1712
+    #define HAS_J_ENABLE 1
1713
+  #endif
1714
+  #if PIN_EXISTS(J_DIR)
1715
+    #define HAS_J_DIR 1
1716
+  #endif
1717
+  #if PIN_EXISTS(J_STEP)
1718
+    #define HAS_J_STEP 1
1719
+  #endif
1720
+  #if PIN_EXISTS(J_MS1)
1721
+    #define HAS_J_MS_PINS 1
1722
+  #endif
1560 1723
 #endif
1561
-#if PIN_EXISTS(Z4_MS1)
1562
-  #define HAS_Z4_MS_PINS 1
1724
+
1725
+#if LINEAR_AXES >= 6
1726
+  #if PIN_EXISTS(K_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(K))
1727
+    #define HAS_K_ENABLE 1
1728
+  #endif
1729
+  #if PIN_EXISTS(K_DIR)
1730
+    #define HAS_K_DIR 1
1731
+  #endif
1732
+  #if PIN_EXISTS(K_STEP)
1733
+    #define HAS_K_STEP 1
1734
+  #endif
1735
+  #if PIN_EXISTS(K_MS1)
1736
+    #define HAS_K_MS_PINS 1
1737
+  #endif
1563 1738
 #endif
1564 1739
 
1565 1740
 // Extruder steppers and solenoids
@@ -1700,7 +1875,7 @@
1700 1875
 //
1701 1876
 
1702 1877
 #if HAS_TRINAMIC_CONFIG
1703
-  #if ANY(STEALTHCHOP_XY, STEALTHCHOP_Z, STEALTHCHOP_E)
1878
+  #if ANY(STEALTHCHOP_E, STEALTHCHOP_XY, STEALTHCHOP_Z, STEALTHCHOP_I, STEALTHCHOP_J, STEALTHCHOP_K)
1704 1879
     #define STEALTHCHOP_ENABLED 1
1705 1880
   #endif
1706 1881
   #if EITHER(SENSORLESS_HOMING, SENSORLESS_PROBING)
@@ -1737,6 +1912,65 @@
1737 1912
   #if defined(Z4_STALL_SENSITIVITY) && AXIS_HAS_STALLGUARD(Z4)
1738 1913
     #define Z4_SENSORLESS 1
1739 1914
   #endif
1915
+
1916
+  #if AXIS_HAS_STEALTHCHOP(X)
1917
+    #define X_HAS_STEALTHCHOP 1
1918
+  #endif
1919
+  #if AXIS_HAS_STEALTHCHOP(X2)
1920
+    #define X2_HAS_STEALTHCHOP 1
1921
+  #endif
1922
+  #if AXIS_HAS_STEALTHCHOP(Y)
1923
+    #define Y_HAS_STEALTHCHOP 1
1924
+  #endif
1925
+  #if AXIS_HAS_STEALTHCHOP(Y2)
1926
+    #define Y2_HAS_STEALTHCHOP 1
1927
+  #endif
1928
+  #if AXIS_HAS_STEALTHCHOP(Z)
1929
+    #define Z_HAS_STEALTHCHOP 1
1930
+  #endif
1931
+  #if AXIS_HAS_STEALTHCHOP(Z2)
1932
+    #define Z2_HAS_STEALTHCHOP 1
1933
+  #endif
1934
+  #if AXIS_HAS_STEALTHCHOP(Z3)
1935
+    #define Z3_HAS_STEALTHCHOP 1
1936
+  #endif
1937
+  #if AXIS_HAS_STEALTHCHOP(Z4)
1938
+    #define Z4_HAS_STEALTHCHOP 1
1939
+  #endif
1940
+  #if AXIS_HAS_STEALTHCHOP(I)
1941
+    #define I_HAS_STEALTHCHOP 1
1942
+  #endif
1943
+  #if AXIS_HAS_STEALTHCHOP(J)
1944
+    #define J_HAS_STEALTHCHOP 1
1945
+  #endif
1946
+  #if AXIS_HAS_STEALTHCHOP(K)
1947
+    #define K_HAS_STEALTHCHOP 1
1948
+  #endif
1949
+  #if E_STEPPERS > 0 && AXIS_HAS_STEALTHCHOP(E0)
1950
+    #define E0_HAS_STEALTHCHOP 1
1951
+  #endif
1952
+  #if E_STEPPERS > 1 && AXIS_HAS_STEALTHCHOP(E1)
1953
+    #define E1_HAS_STEALTHCHOP 1
1954
+  #endif
1955
+  #if E_STEPPERS > 2 && AXIS_HAS_STEALTHCHOP(E2)
1956
+    #define E2_HAS_STEALTHCHOP 1
1957
+  #endif
1958
+  #if E_STEPPERS > 3 && AXIS_HAS_STEALTHCHOP(E3)
1959
+    #define E3_HAS_STEALTHCHOP 1
1960
+  #endif
1961
+  #if E_STEPPERS > 4 && AXIS_HAS_STEALTHCHOP(E4)
1962
+    #define E4_HAS_STEALTHCHOP 1
1963
+  #endif
1964
+  #if E_STEPPERS > 5 && AXIS_HAS_STEALTHCHOP(E5)
1965
+    #define E5_HAS_STEALTHCHOP 1
1966
+  #endif
1967
+  #if E_STEPPERS > 6 && AXIS_HAS_STEALTHCHOP(E6)
1968
+    #define E6_HAS_STEALTHCHOP 1
1969
+  #endif
1970
+  #if E_STEPPERS > 7 && AXIS_HAS_STEALTHCHOP(E7)
1971
+    #define E7_HAS_STEALTHCHOP 1
1972
+  #endif
1973
+
1740 1974
   #if ENABLED(SPI_ENDSTOPS)
1741 1975
     #define X_SPI_SENSORLESS X_SENSORLESS
1742 1976
     #define Y_SPI_SENSORLESS Y_SENSORLESS
@@ -1766,6 +2000,21 @@
1766 2000
   #ifndef Z4_INTERPOLATE
1767 2001
     #define Z4_INTERPOLATE INTERPOLATE
1768 2002
   #endif
2003
+  #if LINEAR_AXES >= 4
2004
+    #ifndef I_INTERPOLATE
2005
+      #define I_INTERPOLATE INTERPOLATE
2006
+    #endif
2007
+  #endif
2008
+  #if LINEAR_AXES >= 5
2009
+    #ifndef J_INTERPOLATE
2010
+      #define J_INTERPOLATE INTERPOLATE
2011
+    #endif
2012
+  #endif
2013
+  #if LINEAR_AXES >= 6
2014
+    #ifndef K_INTERPOLATE
2015
+      #define K_INTERPOLATE INTERPOLATE
2016
+    #endif
2017
+  #endif
1769 2018
   #ifndef E0_INTERPOLATE
1770 2019
     #define E0_INTERPOLATE INTERPOLATE
1771 2020
   #endif
@@ -1799,6 +2048,15 @@
1799 2048
   #ifndef Z_SLAVE_ADDRESS
1800 2049
     #define Z_SLAVE_ADDRESS  0
1801 2050
   #endif
2051
+  #ifndef I_SLAVE_ADDRESS
2052
+    #define I_SLAVE_ADDRESS 0
2053
+  #endif
2054
+  #ifndef J_SLAVE_ADDRESS
2055
+    #define J_SLAVE_ADDRESS 0
2056
+  #endif
2057
+  #ifndef K_SLAVE_ADDRESS
2058
+    #define K_SLAVE_ADDRESS 0
2059
+  #endif
1802 2060
   #ifndef X2_SLAVE_ADDRESS
1803 2061
     #define X2_SLAVE_ADDRESS 0
1804 2062
   #endif
@@ -1853,6 +2111,10 @@
1853 2111
   #define HAS_TMC_SW_SERIAL 1
1854 2112
 #endif
1855 2113
 
2114
+#if !USE_SENSORLESS
2115
+  #undef SENSORLESS_BACKOFF_MM
2116
+#endif
2117
+
1856 2118
 //
1857 2119
 // Set USING_HW_SERIALn flags for used Serial Ports
1858 2120
 //
@@ -1972,18 +2234,36 @@
1972 2234
 #if _HAS_STOP(X,MAX)
1973 2235
   #define HAS_X_MAX 1
1974 2236
 #endif
1975
-#if _HAS_STOP(Y,MIN)
2237
+#if HAS_Y_AXIS && _HAS_STOP(Y,MIN)
1976 2238
   #define HAS_Y_MIN 1
1977 2239
 #endif
1978
-#if _HAS_STOP(Y,MAX)
2240
+#if HAS_Y_AXIS && _HAS_STOP(Y,MAX)
1979 2241
   #define HAS_Y_MAX 1
1980 2242
 #endif
1981
-#if _HAS_STOP(Z,MIN)
2243
+#if BOTH(HAS_Z_AXIS, USE_ZMIN_PLUG) && _HAS_STOP(Z,MIN)
1982 2244
   #define HAS_Z_MIN 1
1983 2245
 #endif
1984
-#if _HAS_STOP(Z,MAX)
2246
+#if BOTH(HAS_Z_AXIS, USE_ZMAX_PLUG) && _HAS_STOP(Z,MAX)
1985 2247
   #define HAS_Z_MAX 1
1986 2248
 #endif
2249
+#if _HAS_STOP(I,MIN)
2250
+  #define HAS_I_MIN 1
2251
+#endif
2252
+#if _HAS_STOP(I,MAX)
2253
+  #define HAS_I_MAX 1
2254
+#endif
2255
+#if _HAS_STOP(J,MIN)
2256
+  #define HAS_J_MIN 1
2257
+#endif
2258
+#if _HAS_STOP(J,MAX)
2259
+  #define HAS_J_MAX 1
2260
+#endif
2261
+#if _HAS_STOP(K,MIN)
2262
+  #define HAS_K_MIN 1
2263
+#endif
2264
+#if _HAS_STOP(K,MAX)
2265
+  #define HAS_K_MAX 1
2266
+#endif
1987 2267
 #if PIN_EXISTS(X2_MIN)
1988 2268
   #define HAS_X2_MIN 1
1989 2269
 #endif
@@ -2365,7 +2645,7 @@
2365 2645
 #if ANY(HAS_E0_MS_PINS, HAS_E1_MS_PINS, HAS_E2_MS_PINS, HAS_E3_MS_PINS, HAS_E4_MS_PINS, HAS_E5_MS_PINS, HAS_E6_MS_PINS, HAS_E7_MS_PINS)
2366 2646
   #define HAS_SOME_E_MS_PINS 1
2367 2647
 #endif
2368
-#if ANY(HAS_X_MS_PINS, HAS_X2_MS_PINS, HAS_Y_MS_PINS, HAS_Y2_MS_PINS, HAS_SOME_Z_MS_PINS, HAS_SOME_E_MS_PINS)
2648
+#if ANY(HAS_X_MS_PINS, HAS_X2_MS_PINS, HAS_Y_MS_PINS, HAS_Y2_MS_PINS, HAS_SOME_Z_MS_PINS, HAS_I_MS_PINS, HAS_J_MS_PINS, HAS_K_MS_PINS, HAS_SOME_E_MS_PINS)
2369 2649
   #define HAS_MICROSTEPS 1
2370 2650
 #endif
2371 2651
 

+ 275
- 38
Marlin/src/inc/SanityCheck.h View File

@@ -34,6 +34,10 @@
34 34
   #error "Marlin requires C++11 support (gcc >= 4.7, Arduino IDE >= 1.6.8). Please upgrade your toolchain."
35 35
 #endif
36 36
 
37
+// Strings for sanity check messages
38
+#define _LINEAR_AXES_STR LINEAR_AXIS_GANG("X ", "Y ", "Z ", "I ", "J ", "K ")
39
+#define _LOGICAL_AXES_STR LOGICAL_AXIS_GANG("E ", "X ", "Y ", "Z ", "I ", "J ", "K ")
40
+
37 41
 // Make sure macros aren't borked
38 42
 #define TEST1
39 43
 #define TEST2 1
@@ -566,6 +570,9 @@
566 570
   #error "NEOPIXEL_BKGD_LED_INDEX is now NEOPIXEL_BKGD_INDEX_FIRST."
567 571
 #endif
568 572
 
573
+constexpr float sbm[] = AXIS_RELATIVE_MODES;
574
+static_assert(COUNT(sbm) == LOGICAL_AXES, "AXIS_RELATIVE_MODES must contain " _LOGICAL_AXES_STR "elements.");
575
+
569 576
 /**
570 577
  * Probe temp compensation requirements
571 578
  */
@@ -644,14 +651,18 @@
644 651
 
645 652
 #if ENABLED(Y_DUAL_STEPPER_DRIVERS) && !GOOD_AXIS_PINS(Y)
646 653
   #error "Y_DUAL_STEPPER_DRIVERS requires Y2 pins to be defined."
647
-#elif !WITHIN(NUM_Z_STEPPER_DRIVERS, 1, 4)
648
-  #error "NUM_Z_STEPPER_DRIVERS must be an integer from 1 to 4."
649
-#elif NUM_Z_STEPPER_DRIVERS == 2 && !GOOD_AXIS_PINS(Z2)
650
-  #error "If NUM_Z_STEPPER_DRIVERS is 2, you must define stepper pins for Z2."
651
-#elif NUM_Z_STEPPER_DRIVERS == 3 && !(GOOD_AXIS_PINS(Z2) && GOOD_AXIS_PINS(Z3))
652
-  #error "If NUM_Z_STEPPER_DRIVERS is 3, you must define stepper pins for Z2 and Z3."
653
-#elif NUM_Z_STEPPER_DRIVERS == 4 && !(GOOD_AXIS_PINS(Z2) && GOOD_AXIS_PINS(Z3) && GOOD_AXIS_PINS(Z4))
654
-  #error "If NUM_Z_STEPPER_DRIVERS is 4, you must define stepper pins for Z2, Z3, and Z4."
654
+#endif
655
+
656
+#if HAS_Z_AXIS
657
+  #if !WITHIN(NUM_Z_STEPPER_DRIVERS, 1, 4)
658
+    #error "NUM_Z_STEPPER_DRIVERS must be an integer from 1 to 4."
659
+  #elif NUM_Z_STEPPER_DRIVERS == 2 && !GOOD_AXIS_PINS(Z2)
660
+    #error "If NUM_Z_STEPPER_DRIVERS is 2, you must define stepper pins for Z2."
661
+  #elif NUM_Z_STEPPER_DRIVERS == 3 && !(GOOD_AXIS_PINS(Z2) && GOOD_AXIS_PINS(Z3))
662
+    #error "If NUM_Z_STEPPER_DRIVERS is 3, you must define stepper pins for Z2 and Z3."
663
+  #elif NUM_Z_STEPPER_DRIVERS == 4 && !(GOOD_AXIS_PINS(Z2) && GOOD_AXIS_PINS(Z3) && GOOD_AXIS_PINS(Z4))
664
+    #error "If NUM_Z_STEPPER_DRIVERS is 4, you must define stepper pins for Z2, Z3, and Z4."
665
+  #endif
655 666
 #endif
656 667
 
657 668
 /**
@@ -704,6 +715,12 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS
704 715
   #error "Enable only one of ENDSTOPPULLUP_Y_MIN or ENDSTOPPULLDOWN_Y_MIN."
705 716
 #elif BOTH(ENDSTOPPULLUP_ZMIN, ENDSTOPPULLDOWN_ZMIN)
706 717
   #error "Enable only one of ENDSTOPPULLUP_Z_MIN or ENDSTOPPULLDOWN_Z_MIN."
718
+#elif BOTH(ENDSTOPPULLUP_IMIN, ENDSTOPPULLDOWN_IMIN)
719
+  #error "Enable only one of ENDSTOPPULLUP_I_MIN or ENDSTOPPULLDOWN_I_MIN."
720
+#elif BOTH(ENDSTOPPULLUP_JMIN, ENDSTOPPULLDOWN_JMIN)
721
+  #error "Enable only one of ENDSTOPPULLUP_J_MIN or ENDSTOPPULLDOWN_J_MIN."
722
+#elif BOTH(ENDSTOPPULLUP_KMIN, ENDSTOPPULLDOWN_KMIN)
723
+  #error "Enable only one of ENDSTOPPULLUP_K_MIN or ENDSTOPPULLDOWN_K_MIN."
707 724
 #endif
708 725
 
709 726
 /**
@@ -927,6 +944,13 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS
927 944
 #endif
928 945
 
929 946
 /**
947
+ * Instant Freeze
948
+ */
949
+#if ENABLED(FREEZE_FEATURE) && !PIN_EXISTS(FREEZE)
950
+  #error "FREEZE_FEATURE requires a FREEZE_PIN to be defined."
951
+#endif
952
+
953
+/**
930 954
  * Individual axis homing is useless for DELTAS
931 955
  */
932 956
 #if BOTH(INDIVIDUAL_AXIS_HOMING_MENU, DELTA)
@@ -1267,14 +1291,50 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS
1267 1291
 #endif
1268 1292
 
1269 1293
 /**
1294
+ * Features that require a min/max/specific LINEAR_AXES
1295
+ */
1296
+#if HAS_LEVELING && !HAS_Z_AXIS
1297
+  #error "Leveling in Marlin requires three or more axes, with Z as the vertical axis."
1298
+#elif ENABLED(CNC_WORKSPACE_PLANES) && !HAS_Z_AXIS
1299
+  #error "CNC_WORKSPACE_PLANES currently requires LINEAR_AXES >= 3"
1300
+#elif ENABLED(DIRECT_STEPPING) && LINEAR_AXES > XYZ
1301
+  #error "DIRECT_STEPPING currently requires LINEAR_AXES 3"
1302
+#elif ENABLED(FOAMCUTTER_XYUV) && LINEAR_AXES < 5
1303
+  #error "FOAMCUTTER_XYUV requires LINEAR_AXES >= 5."
1304
+#endif
1305
+
1306
+/**
1307
+ * Allow only extra axis codes that do not conflict with G-code parameter names
1308
+ */
1309
+#if LINEAR_AXES >= 4
1310
+  #if AXIS4_NAME != 'A' && AXIS4_NAME != 'B' && AXIS4_NAME != 'C' && AXIS4_NAME != 'U' && AXIS4_NAME != 'V' && AXIS4_NAME != 'W'
1311
+    #error "AXIS4_NAME can only be one of 'A', 'B', 'C', 'U', 'V', or 'W'."
1312
+  #endif
1313
+#endif
1314
+#if LINEAR_AXES >= 5
1315
+  #if AXIS5_NAME == AXIS4_NAME || AXIS5_NAME == AXIS6_NAME
1316
+    #error "AXIS5_NAME must be different from AXIS4_NAME and AXIS6_NAME"
1317
+  #elif AXIS5_NAME != 'A' && AXIS5_NAME != 'B' && AXIS5_NAME != 'C' && AXIS5_NAME != 'U' && AXIS5_NAME != 'V' && AXIS5_NAME != 'W'
1318
+    #error "AXIS5_NAME can only be one of 'A', 'B', 'C', 'U', 'V', or 'W'."
1319
+  #endif
1320
+#endif
1321
+#if LINEAR_AXES >= 6
1322
+  #if AXIS6_NAME == AXIS5_NAME || AXIS6_NAME == AXIS4_NAME
1323
+    #error "AXIS6_NAME must be different from AXIS5_NAME and AXIS4_NAME."
1324
+  #elif AXIS6_NAME != 'A' && AXIS6_NAME != 'B' && AXIS6_NAME != 'C' && AXIS6_NAME != 'U' && AXIS6_NAME != 'V' && AXIS6_NAME != 'W'
1325
+    #error "AXIS6_NAME can only be one of 'A', 'B', 'C', 'U', 'V', or 'W'."
1326
+  #endif
1327
+#endif
1328
+
1329
+/**
1270 1330
  * Kinematics
1271 1331
  */
1272 1332
 
1273 1333
 /**
1274 1334
  * Allow only one kinematic type to be defined
1275 1335
  */
1276
-#if MANY(DELTA, MORGAN_SCARA, MP_SCARA, AXEL_TPARA, COREXY, COREXZ, COREYZ, COREYX, COREZX, COREZY, MARKFORGED_XY)
1277
-  #error "Please enable only one of DELTA, MORGAN_SCARA, AXEL_TPARA, COREXY, COREYX, COREXZ, COREZX, COREYZ, COREZY, or MARKFORGED_XY."
1336
+#if MANY(DELTA, MORGAN_SCARA, MP_SCARA, AXEL_TPARA, COREXY, COREXZ, COREYZ, COREYX, COREZX, COREZY, MARKFORGED_XY, FOAMCUTTER_XYUV)
1337
+  #error "Please enable only one of DELTA, MORGAN_SCARA, MP_SCARA, AXEL_TPARA, COREXY, COREXZ, COREYZ, COREYX, COREZX, COREZY, MARKFORGED_XY, or FOAMCUTTER_XYUV."
1278 1338
 #endif
1279 1339
 
1280 1340
 /**
@@ -1597,15 +1657,60 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS
1597 1657
 #endif
1598 1658
 
1599 1659
 /**
1600
- * Homing
1660
+ * Homing checks
1601 1661
  */
1602
-constexpr float hbm[] = HOMING_BUMP_MM;
1603
-static_assert(COUNT(hbm) == LINEAR_AXES, "HOMING_BUMP_MM requires one element per linear axis.");
1604
-LINEAR_AXIS_CODE(
1605
-  static_assert(hbm[X_AXIS] >= 0, "HOMING_BUMP_MM.X must be greater than or equal to 0."),
1606
-  static_assert(hbm[Y_AXIS] >= 0, "HOMING_BUMP_MM.Y must be greater than or equal to 0."),
1607
-  static_assert(hbm[Z_AXIS] >= 0, "HOMING_BUMP_MM.Z must be greater than or equal to 0.")
1608
-);
1662
+#ifndef HOMING_BUMP_MM
1663
+  #error "Required setting HOMING_BUMP_MM is missing!"
1664
+#elif !defined(HOMING_BUMP_DIVISOR)
1665
+  #error "Required setting HOMING_BUMP_DIVISOR is missing!"
1666
+#else
1667
+  constexpr float hbm[] = HOMING_BUMP_MM, hbd[] = HOMING_BUMP_DIVISOR;
1668
+  static_assert(COUNT(hbm) == LINEAR_AXES, "HOMING_BUMP_MM must have " _LINEAR_AXES_STR "elements (and no others).");
1669
+  LINEAR_AXIS_CODE(
1670
+    static_assert(hbm[X_AXIS] >= 0, "HOMING_BUMP_MM.X must be greater than or equal to 0."),
1671
+    static_assert(hbm[Y_AXIS] >= 0, "HOMING_BUMP_MM.Y must be greater than or equal to 0."),
1672
+    static_assert(hbm[Z_AXIS] >= 0, "HOMING_BUMP_MM.Z must be greater than or equal to 0."),
1673
+    static_assert(hbm[I_AXIS] >= 0, "HOMING_BUMP_MM.I must be greater than or equal to 0."),
1674
+    static_assert(hbm[J_AXIS] >= 0, "HOMING_BUMP_MM.J must be greater than or equal to 0."),
1675
+    static_assert(hbm[K_AXIS] >= 0, "HOMING_BUMP_MM.K must be greater than or equal to 0.")
1676
+  );
1677
+  static_assert(COUNT(hbd) == LINEAR_AXES, "HOMING_BUMP_DIVISOR must have " _LINEAR_AXES_STR "elements (and no others).");
1678
+  LINEAR_AXIS_CODE(
1679
+    static_assert(hbd[X_AXIS] >= 1, "HOMING_BUMP_DIVISOR.X must be greater than or equal to 1."),
1680
+    static_assert(hbd[Y_AXIS] >= 1, "HOMING_BUMP_DIVISOR.Y must be greater than or equal to 1."),
1681
+    static_assert(hbd[Z_AXIS] >= 1, "HOMING_BUMP_DIVISOR.Z must be greater than or equal to 1."),
1682
+    static_assert(hbd[I_AXIS] >= 1, "HOMING_BUMP_DIVISOR.I must be greater than or equal to 1."),
1683
+    static_assert(hbd[J_AXIS] >= 1, "HOMING_BUMP_DIVISOR.J must be greater than or equal to 1."),
1684
+    static_assert(hbd[K_AXIS] >= 1, "HOMING_BUMP_DIVISOR.K must be greater than or equal to 1.")
1685
+  );
1686
+#endif
1687
+
1688
+#ifdef HOMING_BACKOFF_POST_MM
1689
+  constexpr float hbp[] = HOMING_BACKOFF_POST_MM;
1690
+  static_assert(COUNT(hbp) == LINEAR_AXES, "HOMING_BACKOFF_POST_MM must have " _LINEAR_AXES_STR "elements (and no others).");
1691
+  LINEAR_AXIS_CODE(
1692
+    static_assert(hbp[X_AXIS] >= 0, "HOMING_BACKOFF_POST_MM.X must be greater than or equal to 0."),
1693
+    static_assert(hbp[Y_AXIS] >= 0, "HOMING_BACKOFF_POST_MM.Y must be greater than or equal to 0."),
1694
+    static_assert(hbp[Z_AXIS] >= 0, "HOMING_BACKOFF_POST_MM.Z must be greater than or equal to 0."),
1695
+    static_assert(hbp[I_AXIS] >= 0, "HOMING_BACKOFF_POST_MM.I must be greater than or equal to 0."),
1696
+    static_assert(hbp[J_AXIS] >= 0, "HOMING_BACKOFF_POST_MM.J must be greater than or equal to 0."),
1697
+    static_assert(hbp[K_AXIS] >= 0, "HOMING_BACKOFF_POST_MM.K must be greater than or equal to 0.")
1698
+  );
1699
+#endif
1700
+
1701
+#ifdef SENSORLESS_BACKOFF_MM
1702
+  constexpr float sbm[] = SENSORLESS_BACKOFF_MM;
1703
+  static_assert(COUNT(sbm) == LINEAR_AXES, "SENSORLESS_BACKOFF_MM must have " _LINEAR_AXES_STR "elements (and no others).");
1704
+  LINEAR_AXIS_CODE(
1705
+    static_assert(sbm[X_AXIS] >= 0, "SENSORLESS_BACKOFF_MM.X must be greater than or equal to 0."),
1706
+    static_assert(sbm[Y_AXIS] >= 0, "SENSORLESS_BACKOFF_MM.Y must be greater than or equal to 0."),
1707
+    static_assert(sbm[Z_AXIS] >= 0, "SENSORLESS_BACKOFF_MM.Z must be greater than or equal to 0."),
1708
+    static_assert(sbm[I_AXIS] >= 0, "SENSORLESS_BACKOFF_MM.I must be greater than or equal to 0."),
1709
+    static_assert(sbm[J_AXIS] >= 0, "SENSORLESS_BACKOFF_MM.J must be greater than or equal to 0."),
1710
+    static_assert(sbm[K_AXIS] >= 0, "SENSORLESS_BACKOFF_MM.K must be greater than or equal to 0.")
1711
+  );
1712
+#endif
1713
+
1609 1714
 #if ENABLED(CODEPENDENT_XY_HOMING)
1610 1715
   #if ENABLED(QUICK_HOME)
1611 1716
     #error "QUICK_HOME is incompatible with CODEPENDENT_XY_HOMING."
@@ -1625,9 +1730,9 @@ LINEAR_AXIS_CODE(
1625 1730
 /**
1626 1731
  * Make sure DISABLE_[XYZ] compatible with selected homing options
1627 1732
  */
1628
-#if ANY(DISABLE_X, DISABLE_Y, DISABLE_Z)
1733
+#if ANY(DISABLE_X, DISABLE_Y, DISABLE_Z, DISABLE_I, DISABLE_J, DISABLE_K)
1629 1734
   #if EITHER(HOME_AFTER_DEACTIVATE, Z_SAFE_HOMING)
1630
-    #error "DISABLE_[XYZ] is not compatible with HOME_AFTER_DEACTIVATE or Z_SAFE_HOMING."
1735
+    #error "DISABLE_[XYZIJK] is not compatible with HOME_AFTER_DEACTIVATE or Z_SAFE_HOMING."
1631 1736
   #endif
1632 1737
 #endif
1633 1738
 
@@ -2085,7 +2190,7 @@ LINEAR_AXIS_CODE(
2085 2190
 #define _PLUG_UNUSED_TEST(A,P) (DISABLED(USE_##P##MIN_PLUG, USE_##P##MAX_PLUG) \
2086 2191
   && !(ENABLED(A##_DUAL_ENDSTOPS) && WITHIN(A##2_USE_ENDSTOP, _##P##MAX_, _##P##MIN_)) \
2087 2192
   && !(ENABLED(A##_MULTI_ENDSTOPS) && WITHIN(A##2_USE_ENDSTOP, _##P##MAX_, _##P##MIN_)) )
2088
-#define _AXIS_PLUG_UNUSED_TEST(A) (_PLUG_UNUSED_TEST(A,X) && _PLUG_UNUSED_TEST(A,Y) && _PLUG_UNUSED_TEST(A,Z))
2193
+#define _AXIS_PLUG_UNUSED_TEST(A) (1 LINEAR_AXIS_GANG(&& _PLUG_UNUSED_TEST(A,X), && _PLUG_UNUSED_TEST(A,Y), && _PLUG_UNUSED_TEST(A,Z), && _PLUG_UNUSED_TEST(A,I), && _PLUG_UNUSED_TEST(A,J), && _PLUG_UNUSED_TEST(A,K) ) )
2089 2194
 
2090 2195
 // A machine with endstops must have a minimum of 3
2091 2196
 #if HAS_ENDSTOPS
@@ -2098,6 +2203,15 @@ LINEAR_AXIS_CODE(
2098 2203
   #if _AXIS_PLUG_UNUSED_TEST(Z)
2099 2204
     #error "You must enable USE_ZMIN_PLUG or USE_ZMAX_PLUG."
2100 2205
   #endif
2206
+  #if LINEAR_AXES >= 4 && _AXIS_PLUG_UNUSED_TEST(I)
2207
+    #error "You must enable USE_IMIN_PLUG or USE_IMAX_PLUG."
2208
+  #endif
2209
+  #if LINEAR_AXES >= 5 && _AXIS_PLUG_UNUSED_TEST(J)
2210
+    #error "You must enable USE_JMIN_PLUG or USE_JMAX_PLUG."
2211
+  #endif
2212
+  #if LINEAR_AXES >= 6 && _AXIS_PLUG_UNUSED_TEST(K)
2213
+    #error "You must enable USE_KMIN_PLUG or USE_KMAX_PLUG."
2214
+  #endif
2101 2215
 
2102 2216
   // Delta and Cartesian use 3 homing endstops
2103 2217
   #if NONE(IS_SCARA, SPI_ENDSTOPS)
@@ -2109,6 +2223,18 @@ LINEAR_AXIS_CODE(
2109 2223
       #error "Enable USE_YMIN_PLUG when homing Y to MIN."
2110 2224
     #elif Y_HOME_TO_MAX && DISABLED(USE_YMAX_PLUG)
2111 2225
       #error "Enable USE_YMAX_PLUG when homing Y to MAX."
2226
+    #elif LINEAR_AXES >= 4 && I_HOME_TO_MIN && DISABLED(USE_IMIN_PLUG)
2227
+      #error "Enable USE_IMIN_PLUG when homing I to MIN."
2228
+    #elif LINEAR_AXES >= 4 && I_HOME_TO_MAX && DISABLED(USE_IMAX_PLUG)
2229
+      #error "Enable USE_IMAX_PLUG when homing I to MAX."
2230
+    #elif LINEAR_AXES >= 5 && J_HOME_TO_MIN && DISABLED(USE_JMIN_PLUG)
2231
+      #error "Enable USE_JMIN_PLUG when homing J to MIN."
2232
+    #elif LINEAR_AXES >= 5 && J_HOME_TO_MAX && DISABLED(USE_JMAX_PLUG)
2233
+      #error "Enable USE_JMAX_PLUG when homing J to MAX."
2234
+    #elif LINEAR_AXES >= 6 && K_HOME_TO_MIN && DISABLED(USE_KMIN_PLUG)
2235
+      #error "Enable USE_KMIN_PLUG when homing K to MIN."
2236
+    #elif LINEAR_AXES >= 6 && K_HOME_TO_MAX && DISABLED(USE_KMAX_PLUG)
2237
+      #error "Enable USE_KMAX_PLUG when homing K to MAX."
2112 2238
     #endif
2113 2239
   #endif
2114 2240
 
@@ -2503,6 +2629,12 @@ LINEAR_AXIS_CODE(
2503 2629
   #error "An SPI driven TMC driver on E6 requires E6_CS_PIN."
2504 2630
 #elif INVALID_TMC_SPI(E7)
2505 2631
   #error "An SPI driven TMC driver on E7 requires E7_CS_PIN."
2632
+#elif INVALID_TMC_SPI(I)
2633
+  #error "An SPI driven TMC on I requires I_CS_PIN."
2634
+#elif INVALID_TMC_SPI(J)
2635
+  #error "An SPI driven TMC on J requires J_CS_PIN."
2636
+#elif INVALID_TMC_SPI(K)
2637
+  #error "An SPI driven TMC on K requires K_CS_PIN."
2506 2638
 #endif
2507 2639
 #undef INVALID_TMC_SPI
2508 2640
 
@@ -2542,6 +2674,12 @@ LINEAR_AXIS_CODE(
2542 2674
   #error "TMC2208 or TMC2209 on E6 requires E6_HARDWARE_SERIAL or E6_SERIAL_(RX|TX)_PIN."
2543 2675
 #elif INVALID_TMC_UART(E7)
2544 2676
   #error "TMC2208 or TMC2209 on E7 requires E7_HARDWARE_SERIAL or E7_SERIAL_(RX|TX)_PIN."
2677
+#elif LINEAR_AXES >= 4 && INVALID_TMC_UART(I)
2678
+  #error "TMC2208 or TMC2209 on I requires I_HARDWARE_SERIAL or I_SERIAL_(RX|TX)_PIN."
2679
+#elif LINEAR_AXES >= 5 && INVALID_TMC_UART(J)
2680
+  #error "TMC2208 or TMC2209 on J requires J_HARDWARE_SERIAL or J_SERIAL_(RX|TX)_PIN."
2681
+#elif LINEAR_AXES >= 6 && INVALID_TMC_UART(K)
2682
+  #error "TMC2208 or TMC2209 on K requires K_HARDWARE_SERIAL or K_SERIAL_(RX|TX)_PIN."
2545 2683
 #endif
2546 2684
 #undef INVALID_TMC_UART
2547 2685
 
@@ -2565,6 +2703,12 @@ LINEAR_AXIS_CODE(
2565 2703
   INVALID_TMC_ADDRESS(Z3);
2566 2704
 #elif AXIS_DRIVER_TYPE_Z4(TMC2209)
2567 2705
   INVALID_TMC_ADDRESS(Z4);
2706
+#elif AXIS_DRIVER_TYPE_I(TMC2209)
2707
+  INVALID_TMC_ADDRESS(I);
2708
+#elif AXIS_DRIVER_TYPE_J(TMC2209)
2709
+  INVALID_TMC_ADDRESS(J);
2710
+#elif AXIS_DRIVER_TYPE_K(TMC2209)
2711
+  INVALID_TMC_ADDRESS(K);
2568 2712
 #elif AXIS_DRIVER_TYPE_E0(TMC2209)
2569 2713
   INVALID_TMC_ADDRESS(E0);
2570 2714
 #elif AXIS_DRIVER_TYPE_E1(TMC2209)
@@ -2620,6 +2764,12 @@ LINEAR_AXIS_CODE(
2620 2764
   INVALID_TMC_MS(E6)
2621 2765
 #elif !TMC_MICROSTEP_IS_VALID(E7)
2622 2766
   INVALID_TMC_MS(E7)
2767
+#elif LINEAR_AXES >= 4 && !TMC_MICROSTEP_IS_VALID(I)
2768
+  INVALID_TMC_MS(I)
2769
+#elif LINEAR_AXES >= 5 && !TMC_MICROSTEP_IS_VALID(J)
2770
+  INVALID_TMC_MS(J)
2771
+#elif LINEAR_AXES >= 6 && !TMC_MICROSTEP_IS_VALID(K)
2772
+  INVALID_TMC_MS(K)
2623 2773
 #endif
2624 2774
 #undef INVALID_TMC_MS
2625 2775
 #undef TMC_MICROSTEP_IS_VALID
@@ -2640,6 +2790,15 @@ LINEAR_AXIS_CODE(
2640 2790
   #define X_ENDSTOP_INVERTING !AXIS_DRIVER_TYPE(X,TMC2209)
2641 2791
   #define Y_ENDSTOP_INVERTING !AXIS_DRIVER_TYPE(Y,TMC2209)
2642 2792
   #define Z_ENDSTOP_INVERTING !AXIS_DRIVER_TYPE(Z,TMC2209)
2793
+  #if LINEAR_AXES >= 4
2794
+    #define I_ENDSTOP_INVERTING !AXIS_DRIVER_TYPE(I,TMC2209)
2795
+  #endif
2796
+  #if LINEAR_AXES >= 5
2797
+    #define J_ENDSTOP_INVERTING !AXIS_DRIVER_TYPE(J,TMC2209)
2798
+  #endif
2799
+  #if LINEAR_AXES >= 6
2800
+    #define K_ENDSTOP_INVERTING !AXIS_DRIVER_TYPE(K,TMC2209)
2801
+  #endif
2643 2802
 
2644 2803
   #if NONE(SPI_ENDSTOPS, ONBOARD_ENDSTOPPULLUPS, ENDSTOPPULLUPS)
2645 2804
     #if   X_SENSORLESS && X_HOME_TO_MIN && DISABLED(ENDSTOPPULLUP_XMIN)
@@ -2654,6 +2813,12 @@ LINEAR_AXIS_CODE(
2654 2813
       #error "SENSORLESS_HOMING requires ENDSTOPPULLUP_ZMIN (or ENDSTOPPULLUPS) when homing to Z_MIN."
2655 2814
     #elif Z_SENSORLESS && Z_HOME_TO_MAX && DISABLED(ENDSTOPPULLUP_ZMAX)
2656 2815
       #error "SENSORLESS_HOMING requires ENDSTOPPULLUP_ZMAX (or ENDSTOPPULLUPS) when homing to Z_MAX."
2816
+    #elif LINEAR_AXES >= 4 && I_SENSORLESS && I_HOME_TO_MAX && DISABLED(ENDSTOPPULLUP_IMAX)
2817
+      #error "SENSORLESS_HOMING requires ENDSTOPPULLUP_IMAX (or ENDSTOPPULLUPS) when homing to I_MAX."
2818
+    #elif LINEAR_AXES >= 5 && J_SENSORLESS && J_HOME_TO_MAX && DISABLED(ENDSTOPPULLUP_JMAX)
2819
+      #error "SENSORLESS_HOMING requires ENDSTOPPULLUP_JMAX (or ENDSTOPPULLUPS) when homing to J_MAX."
2820
+    #elif LINEAR_AXES >= 6 && K_SENSORLESS && K_HOME_TO_MAX && DISABLED(ENDSTOPPULLUP_KMAX)
2821
+      #error "SENSORLESS_HOMING requires ENDSTOPPULLUP_KMAX (or ENDSTOPPULLUPS) when homing to K_MAX."
2657 2822
     #endif
2658 2823
   #endif
2659 2824
 
@@ -2698,6 +2863,42 @@ LINEAR_AXIS_CODE(
2698 2863
       #else
2699 2864
         #error "SENSORLESS_HOMING requires Z_MAX_ENDSTOP_INVERTING = false when homing TMC2209 to Z_MAX."
2700 2865
       #endif
2866
+    #elif LINEAR_AXES >= 4 && I_SENSORLESS && I_HOME_TO_MIN && I_MIN_ENDSTOP_INVERTING != I_ENDSTOP_INVERTING
2867
+      #if I_ENDSTOP_INVERTING
2868
+        #error "SENSORLESS_HOMING requires I_MIN_ENDSTOP_INVERTING = true when homing to I_MIN."
2869
+      #else
2870
+        #error "SENSORLESS_HOMING requires I_MIN_ENDSTOP_INVERTING = false when homing TMC2209 to I_MIN."
2871
+      #endif
2872
+    #elif LINEAR_AXES >= 4 && I_SENSORLESS && I_HOME_TO_MAX && I_MAX_ENDSTOP_INVERTING != I_ENDSTOP_INVERTING
2873
+      #if I_ENDSTOP_INVERTING
2874
+        #error "SENSORLESS_HOMING requires I_MAX_ENDSTOP_INVERTING = true when homing to I_MAX."
2875
+      #else
2876
+        #error "SENSORLESS_HOMING requires I_MAX_ENDSTOP_INVERTING = false when homing TMC2209 to I_MAX."
2877
+      #endif
2878
+    #elif LINEAR_AXES >= 5 && J_SENSORLESS && J_HOME_TO_MIN && J_MIN_ENDSTOP_INVERTING != J_ENDSTOP_INVERTING
2879
+      #if J_ENDSTOP_INVERTING
2880
+        #error "SENSORLESS_HOMING requires J_MIN_ENDSTOP_INVERTING = true when homing to J_MIN."
2881
+      #else
2882
+        #error "SENSORLESS_HOMING requires J_MIN_ENDSTOP_INVERTING = false when homing TMC2209 to J_MIN."
2883
+      #endif
2884
+    #elif LINEAR_AXES >= 5 && J_SENSORLESS && J_HOME_TO_MAX && J_MAX_ENDSTOP_INVERTING != J_ENDSTOP_INVERTING
2885
+      #if J_ENDSTOP_INVERTING
2886
+        #error "SENSORLESS_HOMING requires J_MAX_ENDSTOP_INVERTING = true when homing to J_MAX."
2887
+      #else
2888
+        #error "SENSORLESS_HOMING requires J_MAX_ENDSTOP_INVERTING = false when homing TMC2209 to J_MAX."
2889
+      #endif
2890
+    #elif LINEAR_AXES >= 6 && K_SENSORLESS && K_HOME_TO_MIN && K_MIN_ENDSTOP_INVERTING != K_ENDSTOP_INVERTING
2891
+      #if K_ENDSTOP_INVERTING
2892
+        #error "SENSORLESS_HOMING requires K_MIN_ENDSTOP_INVERTING = true when homing to K_MIN."
2893
+      #else
2894
+        #error "SENSORLESS_HOMING requires K_MIN_ENDSTOP_INVERTING = false when homing TMC2209 to K_MIN."
2895
+      #endif
2896
+    #elif LINEAR_AXES >= 6 && K_SENSORLESS && K_HOME_TO_MAX && K_MAX_ENDSTOP_INVERTING != K_ENDSTOP_INVERTING
2897
+      #if K_ENDSTOP_INVERTING
2898
+        #error "SENSORLESS_HOMING requires K_MAX_ENDSTOP_INVERTING = true when homing to K_MAX."
2899
+      #else
2900
+        #error "SENSORLESS_HOMING requires K_MAX_ENDSTOP_INVERTING = false when homing TMC2209 to K_MAX."
2901
+      #endif
2701 2902
     #endif
2702 2903
   #endif
2703 2904
 
@@ -2712,6 +2913,9 @@ LINEAR_AXIS_CODE(
2712 2913
   #undef X_ENDSTOP_INVERTING
2713 2914
   #undef Y_ENDSTOP_INVERTING
2714 2915
   #undef Z_ENDSTOP_INVERTING
2916
+  #undef I_ENDSTOP_INVERTING
2917
+  #undef J_ENDSTOP_INVERTING
2918
+  #undef K_ENDSTOP_INVERTING
2715 2919
 #endif
2716 2920
 
2717 2921
 // Sensorless probing requirements
@@ -2774,6 +2978,12 @@ LINEAR_AXIS_CODE(
2774 2978
       #define CS_COMPARE Z2_CS_PIN
2775 2979
     #elif IN_CHAIN(Z3)
2776 2980
       #define CS_COMPARE Z3_CS_PIN
2981
+    #elif IN_CHAIN(I)
2982
+      #define CS_COMPARE I_CS_PIN
2983
+    #elif IN_CHAIN(J)
2984
+      #define CS_COMPARE J_CS_PIN
2985
+    #elif IN_CHAIN(K)
2986
+      #define CS_COMPARE K_CS_PIN
2777 2987
     #elif IN_CHAIN(E0)
2778 2988
       #define CS_COMPARE E0_CS_PIN
2779 2989
     #elif IN_CHAIN(E1)
@@ -2793,6 +3003,7 @@ LINEAR_AXIS_CODE(
2793 3003
     #endif
2794 3004
     #define BAD_CS_PIN(A) (IN_CHAIN(A) && A##_CS_PIN != CS_COMPARE)
2795 3005
     #if  BAD_CS_PIN(X ) || BAD_CS_PIN(Y ) || BAD_CS_PIN(Z ) || BAD_CS_PIN(X2) || BAD_CS_PIN(Y2) || BAD_CS_PIN(Z2) || BAD_CS_PIN(Z3) || BAD_CS_PIN(Z4) \
3006
+      || BAD_CS_PIN(I) || BAD_CS_PIN(J) || BAD_CS_PIN(K) \
2796 3007
       || BAD_CS_PIN(E0) || BAD_CS_PIN(E1) || BAD_CS_PIN(E2) || BAD_CS_PIN(E3) || BAD_CS_PIN(E4) || BAD_CS_PIN(E5) || BAD_CS_PIN(E6) || BAD_CS_PIN(E7)
2797 3008
       #error "All chained TMC drivers must use the same CS pin."
2798 3009
     #endif
@@ -2804,6 +3015,13 @@ LINEAR_AXIS_CODE(
2804 3015
 #undef IN_CHAIN
2805 3016
 
2806 3017
 /**
3018
+ * L64XX requirement
3019
+ */
3020
+#if HAS_L64XX && LINEAR_AXES >= 4
3021
+  #error "L64XX requires LINEAR_AXES 3. Homing with L64XX is not yet implemented for LINEAR_AXES > 3."
3022
+#endif
3023
+
3024
+/**
2807 3025
  * Digipot requirement
2808 3026
  */
2809 3027
 #if HAS_MOTOR_CURRENT_I2C
@@ -2820,43 +3038,48 @@ LINEAR_AXIS_CODE(
2820 3038
  */
2821 3039
 constexpr float sanity_arr_1[] = DEFAULT_AXIS_STEPS_PER_UNIT,
2822 3040
                 sanity_arr_2[] = DEFAULT_MAX_FEEDRATE,
2823
-                sanity_arr_3[] = DEFAULT_MAX_ACCELERATION;
3041
+                sanity_arr_3[] = DEFAULT_MAX_ACCELERATION,
3042
+                sanity_arr_7[] = HOMING_FEEDRATE_MM_M;
2824 3043
 
2825 3044
 #define _ARR_TEST(N,I) (sanity_arr_##N[_MIN(I,int(COUNT(sanity_arr_##N))-1)] > 0)
2826 3045
 #if HAS_MULTI_EXTRUDER
2827 3046
   #define _EXTRA_NOTE " (Did you forget to enable DISTINCT_E_FACTORS?)"
2828
-#elif EXTRUDERS == 0
2829
-  #define _EXTRA_NOTE " (Note: EXTRUDERS is set to 0.)"
2830 3047
 #else
2831
-  #define _EXTRA_NOTE ""
3048
+  #define _EXTRA_NOTE " (Should be " STRINGIFY(LINEAR_AXES) "+" STRINGIFY(E_STEPPERS) ")"
2832 3049
 #endif
2833 3050
 
2834
-static_assert(COUNT(sanity_arr_1) >= LOGICAL_AXES,  "DEFAULT_AXIS_STEPS_PER_UNIT requires X, Y, Z and E elements.");
3051
+static_assert(COUNT(sanity_arr_1) >= LOGICAL_AXES,  "DEFAULT_AXIS_STEPS_PER_UNIT requires " _LOGICAL_AXES_STR "elements.");
2835 3052
 static_assert(COUNT(sanity_arr_1) <= DISTINCT_AXES, "DEFAULT_AXIS_STEPS_PER_UNIT has too many elements." _EXTRA_NOTE);
2836 3053
 static_assert(   _ARR_TEST(1,0) && _ARR_TEST(1,1) && _ARR_TEST(1,2)
2837 3054
               && _ARR_TEST(1,3) && _ARR_TEST(1,4) && _ARR_TEST(1,5)
2838 3055
               && _ARR_TEST(1,6) && _ARR_TEST(1,7) && _ARR_TEST(1,8),
2839 3056
               "DEFAULT_AXIS_STEPS_PER_UNIT values must be positive.");
2840 3057
 
2841
-static_assert(COUNT(sanity_arr_2) >= LOGICAL_AXES,  "DEFAULT_MAX_FEEDRATE requires X, Y, Z and E elements.");
3058
+static_assert(COUNT(sanity_arr_2) >= LOGICAL_AXES,  "DEFAULT_MAX_FEEDRATE requires " _LOGICAL_AXES_STR "elements.");
2842 3059
 static_assert(COUNT(sanity_arr_2) <= DISTINCT_AXES, "DEFAULT_MAX_FEEDRATE has too many elements." _EXTRA_NOTE);
2843 3060
 static_assert(   _ARR_TEST(2,0) && _ARR_TEST(2,1) && _ARR_TEST(2,2)
2844 3061
               && _ARR_TEST(2,3) && _ARR_TEST(2,4) && _ARR_TEST(2,5)
2845 3062
               && _ARR_TEST(2,6) && _ARR_TEST(2,7) && _ARR_TEST(2,8),
2846 3063
               "DEFAULT_MAX_FEEDRATE values must be positive.");
2847 3064
 
2848
-static_assert(COUNT(sanity_arr_3) >= LOGICAL_AXES,  "DEFAULT_MAX_ACCELERATION requires X, Y, Z and E elements.");
3065
+static_assert(COUNT(sanity_arr_3) >= LOGICAL_AXES,  "DEFAULT_MAX_ACCELERATION requires " _LOGICAL_AXES_STR "elements.");
2849 3066
 static_assert(COUNT(sanity_arr_3) <= DISTINCT_AXES, "DEFAULT_MAX_ACCELERATION has too many elements." _EXTRA_NOTE);
2850 3067
 static_assert(   _ARR_TEST(3,0) && _ARR_TEST(3,1) && _ARR_TEST(3,2)
2851 3068
               && _ARR_TEST(3,3) && _ARR_TEST(3,4) && _ARR_TEST(3,5)
2852 3069
               && _ARR_TEST(3,6) && _ARR_TEST(3,7) && _ARR_TEST(3,8),
2853 3070
               "DEFAULT_MAX_ACCELERATION values must be positive.");
2854 3071
 
3072
+static_assert(COUNT(sanity_arr_7) == LINEAR_AXES,  "HOMING_FEEDRATE_MM_M requires " _LINEAR_AXES_STR "elements (and no others).");
3073
+static_assert(   _ARR_TEST(3,0) && _ARR_TEST(3,1) && _ARR_TEST(3,2)
3074
+              && _ARR_TEST(3,3) && _ARR_TEST(3,4) && _ARR_TEST(3,5)
3075
+              && _ARR_TEST(3,6) && _ARR_TEST(3,7) && _ARR_TEST(3,8),
3076
+              "HOMING_FEEDRATE_MM_M values must be positive.");
3077
+
2855 3078
 #if ENABLED(LIMITED_MAX_ACCEL_EDITING)
2856 3079
   #ifdef MAX_ACCEL_EDIT_VALUES
2857 3080
     constexpr float sanity_arr_4[] = MAX_ACCEL_EDIT_VALUES;
2858
-    static_assert(COUNT(sanity_arr_4) >= LOGICAL_AXES, "MAX_ACCEL_EDIT_VALUES requires X, Y, Z and E elements.");
2859
-    static_assert(COUNT(sanity_arr_4) <= LOGICAL_AXES, "MAX_ACCEL_EDIT_VALUES has too many elements. X, Y, Z and E elements only.");
3081
+    static_assert(COUNT(sanity_arr_4) >= LOGICAL_AXES, "MAX_ACCEL_EDIT_VALUES requires " _LOGICAL_AXES_STR "elements.");
3082
+    static_assert(COUNT(sanity_arr_4) <= LOGICAL_AXES, "MAX_ACCEL_EDIT_VALUES has too many elements. " _LOGICAL_AXES_STR "elements only.");
2860 3083
     static_assert(   _ARR_TEST(4,0) && _ARR_TEST(4,1) && _ARR_TEST(4,2)
2861 3084
                   && _ARR_TEST(4,3) && _ARR_TEST(4,4) && _ARR_TEST(4,5)
2862 3085
                   && _ARR_TEST(4,6) && _ARR_TEST(4,7) && _ARR_TEST(4,8),
@@ -2867,8 +3090,8 @@ static_assert(   _ARR_TEST(3,0) && _ARR_TEST(3,1) && _ARR_TEST(3,2)
2867 3090
 #if ENABLED(LIMITED_MAX_FR_EDITING)
2868 3091
   #ifdef MAX_FEEDRATE_EDIT_VALUES
2869 3092
     constexpr float sanity_arr_5[] = MAX_FEEDRATE_EDIT_VALUES;
2870
-    static_assert(COUNT(sanity_arr_5) >= LOGICAL_AXES, "MAX_FEEDRATE_EDIT_VALUES requires X, Y, Z and E elements.");
2871
-    static_assert(COUNT(sanity_arr_5) <= LOGICAL_AXES, "MAX_FEEDRATE_EDIT_VALUES has too many elements. X, Y, Z and E elements only.");
3093
+    static_assert(COUNT(sanity_arr_5) >= LOGICAL_AXES, "MAX_FEEDRATE_EDIT_VALUES requires " _LOGICAL_AXES_STR "elements.");
3094
+    static_assert(COUNT(sanity_arr_5) <= LOGICAL_AXES, "MAX_FEEDRATE_EDIT_VALUES has too many elements. " _LOGICAL_AXES_STR "elements only.");
2872 3095
     static_assert(   _ARR_TEST(5,0) && _ARR_TEST(5,1) && _ARR_TEST(5,2)
2873 3096
                   && _ARR_TEST(5,3) && _ARR_TEST(5,4) && _ARR_TEST(5,5)
2874 3097
                   && _ARR_TEST(5,6) && _ARR_TEST(5,7) && _ARR_TEST(5,8),
@@ -2879,8 +3102,8 @@ static_assert(   _ARR_TEST(3,0) && _ARR_TEST(3,1) && _ARR_TEST(3,2)
2879 3102
 #if ENABLED(LIMITED_JERK_EDITING)
2880 3103
   #ifdef MAX_JERK_EDIT_VALUES
2881 3104
     constexpr float sanity_arr_6[] = MAX_JERK_EDIT_VALUES;
2882
-    static_assert(COUNT(sanity_arr_6) >= LOGICAL_AXES, "MAX_JERK_EDIT_VALUES requires X, Y, Z and E elements.");
2883
-    static_assert(COUNT(sanity_arr_6) <= LOGICAL_AXES, "MAX_JERK_EDIT_VALUES has too many elements. X, Y, Z and E elements only.");
3105
+    static_assert(COUNT(sanity_arr_6) >= LOGICAL_AXES, "MAX_JERK_EDIT_VALUES requires " _LOGICAL_AXES_STR "elements.");
3106
+    static_assert(COUNT(sanity_arr_6) <= LOGICAL_AXES, "MAX_JERK_EDIT_VALUES has too many elements. " _LOGICAL_AXES_STR "elements only.");
2884 3107
     static_assert(   _ARR_TEST(6,0) && _ARR_TEST(6,1) && _ARR_TEST(6,2)
2885 3108
                   && _ARR_TEST(6,3) && _ARR_TEST(6,4) && _ARR_TEST(6,5)
2886 3109
                   && _ARR_TEST(6,6) && _ARR_TEST(6,7) && _ARR_TEST(6,8),
@@ -3280,6 +3503,22 @@ static_assert(   _ARR_TEST(3,0) && _ARR_TEST(3,1) && _ARR_TEST(3,2)
3280 3503
 #if _BAD_DRIVER(Z)
3281 3504
   #error "Z_DRIVER_TYPE is not recognized."
3282 3505
 #endif
3506
+#if LINEAR_AXES >= 4
3507
+  #if _BAD_DRIVER(I)
3508
+    #error "I_DRIVER_TYPE is not recognized."
3509
+  #endif
3510
+#endif
3511
+#if LINEAR_AXES >= 5
3512
+  #if _BAD_DRIVER(J)
3513
+    #error "J_DRIVER_TYPE is not recognized."
3514
+  #endif
3515
+#endif
3516
+#if LINEAR_AXES >= 6
3517
+  #if _BAD_DRIVER(K)
3518
+    #error "K_DRIVER_TYPE is not recognized."
3519
+  #endif
3520
+#endif
3521
+
3283 3522
 #if _BAD_DRIVER(X2)
3284 3523
   #error "X2_DRIVER_TYPE is not recognized."
3285 3524
 #endif
@@ -3323,7 +3562,5 @@ static_assert(   _ARR_TEST(3,0) && _ARR_TEST(3,1) && _ARR_TEST(3,2)
3323 3562
 
3324 3563
 // Misc. Cleanup
3325 3564
 #undef _TEST_PWM
3326
-
3327
-#if ENABLED(FREEZE_FEATURE) && !PIN_EXISTS(FREEZE)
3328
-  #error "FREEZE_FEATURE requires a FREEZE_PIN to be defined."
3329
-#endif
3565
+#undef _LINEAR_AXES_STR
3566
+#undef _LOGICAL_AXES_STR

+ 1
- 1
Marlin/src/inc/Version.h View File

@@ -52,7 +52,7 @@
52 52
  * to alert users to major changes.
53 53
  */
54 54
 
55
-#define MARLIN_HEX_VERSION 02000801
55
+#define MARLIN_HEX_VERSION 02000900
56 56
 #ifndef REQUIRED_CONFIGURATION_H_VERSION
57 57
   #define REQUIRED_CONFIGURATION_H_VERSION MARLIN_HEX_VERSION
58 58
 #endif

+ 1
- 1
Marlin/src/lcd/dwin/e3v2/dwin.cpp View File

@@ -1235,7 +1235,7 @@ inline ENCODER_DiffState get_encoder_state() {
1235 1235
 void HMI_Plan_Move(const feedRate_t fr_mm_s) {
1236 1236
   if (!planner.is_full()) {
1237 1237
     planner.synchronize();
1238
-    planner.buffer_line(current_position, fr_mm_s, active_extruder);
1238
+    planner.buffer_line(current_position, fr_mm_s);
1239 1239
     DWIN_UpdateLCD();
1240 1240
   }
1241 1241
 }

+ 3
- 3
Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.cpp View File

@@ -697,13 +697,13 @@ const struct DGUS_VP_Variable ListOfVP[] PROGMEM = {
697 697
   #endif
698 698
 
699 699
   #if ENABLED(SENSORLESS_HOMING)  // TMC SENSORLESS Setting
700
-    #if AXIS_HAS_STEALTHCHOP(X)
700
+    #if X_HAS_STEALTHCHOP
701 701
       VPHELPER(VP_TMC_X_STEP, &tmc_step.x, ScreenHandler.TMC_ChangeConfig, ScreenHandler.DGUSLCD_SendTMCStepValue),
702 702
     #endif
703
-    #if AXIS_HAS_STEALTHCHOP(Y)
703
+    #if Y_HAS_STEALTHCHOP
704 704
       VPHELPER(VP_TMC_Y_STEP, &tmc_step.y, ScreenHandler.TMC_ChangeConfig, ScreenHandler.DGUSLCD_SendTMCStepValue),
705 705
     #endif
706
-    #if AXIS_HAS_STEALTHCHOP(Z)
706
+    #if Z_HAS_STEALTHCHOP
707 707
       VPHELPER(VP_TMC_Z_STEP, &tmc_step.z, ScreenHandler.TMC_ChangeConfig, ScreenHandler.DGUSLCD_SendTMCStepValue),
708 708
     #endif
709 709
   #endif

+ 5
- 5
Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.h View File

@@ -59,19 +59,19 @@ extern xyz_int_t tmc_step;
59 59
 
60 60
 extern uint16_t lcd_default_light;
61 61
 
62
-#if AXIS_HAS_STEALTHCHOP(X)
62
+#if X_HAS_STEALTHCHOP
63 63
   extern uint16_t tmc_x_current;
64 64
 #endif
65
-#if AXIS_HAS_STEALTHCHOP(Y)
65
+#if Y_HAS_STEALTHCHOP
66 66
   extern uint16_t tmc_y_current;
67 67
 #endif
68
-#if AXIS_HAS_STEALTHCHOP(Z)
68
+#if Z_HAS_STEALTHCHOP
69 69
   extern uint16_t tmc_z_current;
70 70
 #endif
71
-#if AXIS_HAS_STEALTHCHOP(E0)
71
+#if E0_HAS_STEALTHCHOP
72 72
   extern uint16_t tmc_e0_current;
73 73
 #endif
74
-#if AXIS_HAS_STEALTHCHOP(E1)
74
+#if E1_HAS_STEALTHCHOP
75 75
   extern uint16_t tmc_e1_current;
76 76
 #endif
77 77
 

+ 12
- 24
Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.cpp View File

@@ -134,15 +134,15 @@ void DGUSScreenHandler::DGUSLCD_SendStringToDisplay_Language_MKS(DGUS_VP_Variabl
134 134
 
135 135
 void DGUSScreenHandler::DGUSLCD_SendTMCStepValue(DGUS_VP_Variable &var) {
136 136
   #if ENABLED(SENSORLESS_HOMING)
137
-    #if AXIS_HAS_STEALTHCHOP(X)
137
+    #if X_HAS_STEALTHCHOP
138 138
       tmc_step.x = stepperX.homing_threshold();
139 139
       dgusdisplay.WriteVariable(var.VP, *(int16_t*)var.memadr);
140 140
     #endif
141
-    #if AXIS_HAS_STEALTHCHOP(Y)
141
+    #if Y_HAS_STEALTHCHOP
142 142
       tmc_step.y = stepperY.homing_threshold();
143 143
       dgusdisplay.WriteVariable(var.VP, *(int16_t*)var.memadr);
144 144
     #endif
145
-    #if AXIS_HAS_STEALTHCHOP(Z)
145
+    #if Z_HAS_STEALTHCHOP
146 146
       tmc_step.z = stepperZ.homing_threshold();
147 147
       dgusdisplay.WriteVariable(var.VP, *(int16_t*)var.memadr);
148 148
     #endif
@@ -659,7 +659,7 @@ void DGUSScreenHandler::TMC_ChangeConfig(DGUS_VP_Variable &var, void *val_ptr) {
659 659
   switch (var.VP) {
660 660
     case VP_TMC_X_STEP:
661 661
       #if USE_SENSORLESS
662
-        #if AXIS_HAS_STEALTHCHOP(X)
662
+        #if X_HAS_STEALTHCHOP
663 663
           stepperX.homing_threshold(mks_min(tmc_value, 255));
664 664
           settings.save();
665 665
           //tmc_step.x = stepperX.homing_threshold();
@@ -668,7 +668,7 @@ void DGUSScreenHandler::TMC_ChangeConfig(DGUS_VP_Variable &var, void *val_ptr) {
668 668
       break;
669 669
     case VP_TMC_Y_STEP:
670 670
       #if USE_SENSORLESS
671
-        #if AXIS_HAS_STEALTHCHOP(Y)
671
+        #if Y_HAS_STEALTHCHOP
672 672
           stepperY.homing_threshold(mks_min(tmc_value, 255));
673 673
           settings.save();
674 674
           //tmc_step.y = stepperY.homing_threshold();
@@ -677,7 +677,7 @@ void DGUSScreenHandler::TMC_ChangeConfig(DGUS_VP_Variable &var, void *val_ptr) {
677 677
       break;
678 678
     case VP_TMC_Z_STEP:
679 679
       #if USE_SENSORLESS
680
-        #if AXIS_HAS_STEALTHCHOP(Z)
680
+        #if Z_HAS_STEALTHCHOP
681 681
           stepperZ.homing_threshold(mks_min(tmc_value, 255));
682 682
           settings.save();
683 683
           //tmc_step.z = stepperZ.homing_threshold();
@@ -737,15 +737,9 @@ void DGUSScreenHandler::TMC_ChangeConfig(DGUS_VP_Variable &var, void *val_ptr) {
737 737
       break;
738 738
   }
739 739
   #if USE_SENSORLESS
740
-    #if AXIS_HAS_STEALTHCHOP(X)
741
-      tmc_step.x = stepperX.homing_threshold();
742
-    #endif
743
-    #if AXIS_HAS_STEALTHCHOP(Y)
744
-      tmc_step.y = stepperY.homing_threshold();
745
-    #endif
746
-    #if AXIS_HAS_STEALTHCHOP(Z)
747
-      tmc_step.z = stepperZ.homing_threshold();
748
-    #endif
740
+    TERN_(X_HAS_STEALTHCHOP, tmc_step.x = stepperX.homing_threshold());
741
+    TERN_(Y_HAS_STEALTHCHOP, tmc_step.y = stepperY.homing_threshold());
742
+    TERN_(Z_HAS_STEALTHCHOP, tmc_step.z = stepperZ.homing_threshold());
749 743
   #endif
750 744
 }
751 745
 
@@ -1419,15 +1413,9 @@ bool DGUSScreenHandler::loop() {
1419 1413
     if (!booted && ELAPSED(ms, TERN(USE_MKS_GREEN_UI, 1000, BOOTSCREEN_TIMEOUT))) {
1420 1414
       booted = true;
1421 1415
       #if USE_SENSORLESS
1422
-        #if AXIS_HAS_STEALTHCHOP(X)
1423
-          tmc_step.x = stepperX.homing_threshold();
1424
-        #endif
1425
-        #if AXIS_HAS_STEALTHCHOP(Y)
1426
-          tmc_step.y = stepperY.homing_threshold();
1427
-        #endif
1428
-        #if AXIS_HAS_STEALTHCHOP(Z)
1429
-          tmc_step.z = stepperZ.homing_threshold();
1430
-        #endif
1416
+        TERN_(X_HAS_STEALTHCHOP, tmc_step.x = stepperX.homing_threshold());
1417
+        TERN_(Y_HAS_STEALTHCHOP, tmc_step.y = stepperY.homing_threshold());
1418
+        TERN_(Z_HAS_STEALTHCHOP, tmc_step.z = stepperZ.homing_threshold());
1431 1419
       #endif
1432 1420
 
1433 1421
       #if ENABLED(PREVENT_COLD_EXTRUSION)

+ 6
- 6
Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/endstop_state_screen.cpp View File

@@ -60,32 +60,32 @@ void EndstopStatesScreen::onRedraw(draw_mode_t) {
60 60
   )
61 61
   .text(BTN_POS(1,1), BTN_SIZE(6,1), GET_TEXT_F(MSG_LCD_ENDSTOPS))
62 62
   .font(font_tiny);
63
-  #if PIN_EXISTS(X_MAX)
63
+  #if HAS_X_MAX
64 64
     PIN_ENABLED (1, 2, PSTR(STR_X_MAX), X_MAX, X_MAX_ENDSTOP_INVERTING)
65 65
   #else
66 66
     PIN_DISABLED(1, 2, PSTR(STR_X_MAX), X_MAX)
67 67
   #endif
68
-  #if PIN_EXISTS(Y_MAX)
68
+  #if HAS_Y_MAX
69 69
     PIN_ENABLED (3, 2, PSTR(STR_Y_MAX), Y_MAX, Y_MAX_ENDSTOP_INVERTING)
70 70
   #else
71 71
     PIN_DISABLED(3, 2, PSTR(STR_Y_MAX), Y_MAX)
72 72
   #endif
73
-  #if PIN_EXISTS(Z_MAX)
73
+  #if HAS_Z_MAX
74 74
     PIN_ENABLED (5, 2, PSTR(STR_Z_MAX), Z_MAX, Z_MAX_ENDSTOP_INVERTING)
75 75
   #else
76 76
     PIN_DISABLED(5, 2, PSTR(STR_Z_MAX), Z_MAX)
77 77
   #endif
78
-  #if PIN_EXISTS(X_MIN)
78
+  #if HAS_X_MIN
79 79
     PIN_ENABLED (1, 3, PSTR(STR_X_MIN), X_MIN, X_MIN_ENDSTOP_INVERTING)
80 80
   #else
81 81
     PIN_DISABLED(1, 3, PSTR(STR_X_MIN), X_MIN)
82 82
   #endif
83
-  #if PIN_EXISTS(Y_MIN)
83
+  #if HAS_Y_MIN
84 84
     PIN_ENABLED (3, 3, PSTR(STR_Y_MIN), Y_MIN, Y_MIN_ENDSTOP_INVERTING)
85 85
   #else
86 86
     PIN_DISABLED(3, 3, PSTR(STR_Y_MIN), Y_MIN)
87 87
   #endif
88
-  #if PIN_EXISTS(Z_MIN)
88
+  #if HAS_Z_MIN
89 89
     PIN_ENABLED (5, 3, PSTR(STR_Z_MIN), Z_MIN, Z_MIN_ENDSTOP_INVERTING)
90 90
   #else
91 91
     PIN_DISABLED(5, 3, PSTR(STR_Z_MIN), Z_MIN)

+ 15
- 35
Marlin/src/lcd/extui/mks_ui/draw_tmc_step_mode_settings.cpp View File

@@ -68,30 +68,20 @@ static void event_handler(lv_obj_t *obj, lv_event_t event) {
68 68
       draw_return_ui();
69 69
       break;
70 70
 
71
-    #if AXIS_HAS_STEALTHCHOP(X)
72
-      case ID_TMC_MODE_X:
73
-        toggle_chop(stepperX, buttonXState);
74
-        break;
71
+    #if X_HAS_STEALTHCHOP
72
+      case ID_TMC_MODE_X:  toggle_chop(stepperX,  buttonXState);  break;
75 73
     #endif
76
-    #if AXIS_HAS_STEALTHCHOP(Y)
77
-      case ID_TMC_MODE_Y:
78
-        toggle_chop(stepperY, buttonYState);
79
-        break;
74
+    #if Y_HAS_STEALTHCHOP
75
+      case ID_TMC_MODE_Y:  toggle_chop(stepperY,  buttonYState);  break;
80 76
     #endif
81
-    #if AXIS_HAS_STEALTHCHOP(Z)
82
-      case ID_TMC_MODE_Z:
83
-        toggle_chop(stepperZ, buttonZState);
84
-        break;
77
+    #if Z_HAS_STEALTHCHOP
78
+      case ID_TMC_MODE_Z:  toggle_chop(stepperZ,  buttonZState);  break;
85 79
     #endif
86
-    #if AXIS_HAS_STEALTHCHOP(E0)
87
-      case ID_TMC_MODE_E0:
88
-        toggle_chop(stepperE0, buttonE0State);
89
-        break;
80
+    #if E0_HAS_STEALTHCHOP
81
+      case ID_TMC_MODE_E0: toggle_chop(stepperE0, buttonE0State); break;
90 82
     #endif
91
-    #if AXIS_HAS_STEALTHCHOP(E1)
92
-      case ID_TMC_MODE_E1:
93
-        toggle_chop(stepperE1, buttonE1State);
94
-        break;
83
+    #if E1_HAS_STEALTHCHOP
84
+      case ID_TMC_MODE_E1: toggle_chop(stepperE1, buttonE1State); break;
95 85
     #endif
96 86
 
97 87
     case ID_TMC_MODE_UP:
@@ -113,21 +103,11 @@ void lv_draw_tmc_step_mode_settings() {
113 103
   scr = lv_screen_create(TMC_MODE_UI, machine_menu.TmcStepModeConfTitle);
114 104
 
115 105
   bool stealth_X = false, stealth_Y = false, stealth_Z = false, stealth_E0 = false, stealth_E1 = false;
116
-  #if AXIS_HAS_STEALTHCHOP(X)
117
-    stealth_X = stepperX.get_stealthChop();
118
-  #endif
119
-  #if AXIS_HAS_STEALTHCHOP(Y)
120
-    stealth_Y = stepperY.get_stealthChop();
121
-  #endif
122
-  #if AXIS_HAS_STEALTHCHOP(Z)
123
-    stealth_Z = stepperZ.get_stealthChop();
124
-  #endif
125
-  #if AXIS_HAS_STEALTHCHOP(E0)
126
-    stealth_E0 = stepperE0.get_stealthChop();
127
-  #endif
128
-  #if AXIS_HAS_STEALTHCHOP(E1)
129
-    stealth_E1 = stepperE1.get_stealthChop();
130
-  #endif
106
+  TERN_(X_HAS_STEALTHCHOP,  stealth_X = stepperX.get_stealthChop());
107
+  TERN_(Y_HAS_STEALTHCHOP,  stealth_Y = stepperY.get_stealthChop());
108
+  TERN_(Z_HAS_STEALTHCHOP,  stealth_Z = stepperZ.get_stealthChop());
109
+  TERN_(E0_HAS_STEALTHCHOP, stealth_E0 = stepperE0.get_stealthChop());
110
+  TERN_(E1_HAS_STEALTHCHOP, stealth_E1 = stepperE1.get_stealthChop());
131 111
 
132 112
   if (!uiCfg.para_ui_page) {
133 113
     buttonXState = lv_screen_menu_item_onoff(scr, machine_menu.X_StepMode, PARA_UI_POS_X, PARA_UI_POS_Y, event_handler, ID_TMC_MODE_X, 0, stealth_X);

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

@@ -72,6 +72,9 @@ namespace Language_en {
72 72
   PROGMEM Language_Str MSG_AUTO_HOME_X                     = _UxGT("Home X");
73 73
   PROGMEM Language_Str MSG_AUTO_HOME_Y                     = _UxGT("Home Y");
74 74
   PROGMEM Language_Str MSG_AUTO_HOME_Z                     = _UxGT("Home Z");
75
+  PROGMEM Language_Str MSG_AUTO_HOME_I                     = _UxGT("Home ") LCD_STR_I;
76
+  PROGMEM Language_Str MSG_AUTO_HOME_J                     = _UxGT("Home ") LCD_STR_J;
77
+  PROGMEM Language_Str MSG_AUTO_HOME_K                     = _UxGT("Home ") LCD_STR_K;
75 78
   PROGMEM Language_Str MSG_AUTO_Z_ALIGN                    = _UxGT("Auto Z-Align");
76 79
   PROGMEM Language_Str MSG_ITERATION                       = _UxGT("G34 Iteration: %i");
77 80
   PROGMEM Language_Str MSG_DECREASING_ACCURACY             = _UxGT("Accuracy Decreasing!");
@@ -85,6 +88,9 @@ namespace Language_en {
85 88
   PROGMEM Language_Str MSG_HOME_OFFSET_X                   = _UxGT("Home Offset X");
86 89
   PROGMEM Language_Str MSG_HOME_OFFSET_Y                   = _UxGT("Home Offset Y");
87 90
   PROGMEM Language_Str MSG_HOME_OFFSET_Z                   = _UxGT("Home Offset Z");
91
+  PROGMEM Language_Str MSG_HOME_OFFSET_I                   = _UxGT("Home Offset ") LCD_STR_I;
92
+  PROGMEM Language_Str MSG_HOME_OFFSET_J                   = _UxGT("Home Offset ") LCD_STR_J;
93
+  PROGMEM Language_Str MSG_HOME_OFFSET_K                   = _UxGT("Home Offset ") LCD_STR_K;
88 94
   PROGMEM Language_Str MSG_HOME_OFFSETS_APPLIED            = _UxGT("Offsets Applied");
89 95
   PROGMEM Language_Str MSG_SET_ORIGIN                      = _UxGT("Set Origin");
90 96
   PROGMEM Language_Str MSG_ASSISTED_TRAMMING               = _UxGT("Assisted Tramming");
@@ -265,6 +271,9 @@ namespace Language_en {
265 271
   PROGMEM Language_Str MSG_MOVE_X                          = _UxGT("Move X");
266 272
   PROGMEM Language_Str MSG_MOVE_Y                          = _UxGT("Move Y");
267 273
   PROGMEM Language_Str MSG_MOVE_Z                          = _UxGT("Move Z");
274
+  PROGMEM Language_Str MSG_MOVE_I                          = _UxGT("Move ") LCD_STR_I;
275
+  PROGMEM Language_Str MSG_MOVE_J                          = _UxGT("Move ") LCD_STR_J;
276
+  PROGMEM Language_Str MSG_MOVE_K                          = _UxGT("Move ") LCD_STR_K;
268 277
   PROGMEM Language_Str MSG_MOVE_E                          = _UxGT("Extruder");
269 278
   PROGMEM Language_Str MSG_MOVE_EN                         = _UxGT("Extruder *");
270 279
   PROGMEM Language_Str MSG_HOTEND_TOO_COLD                 = _UxGT("Hotend too cold");
@@ -329,12 +338,18 @@ namespace Language_en {
329 338
   PROGMEM Language_Str MSG_VA_JERK                         = _UxGT("V") LCD_STR_A _UxGT("-Jerk");
330 339
   PROGMEM Language_Str MSG_VB_JERK                         = _UxGT("V") LCD_STR_B _UxGT("-Jerk");
331 340
   PROGMEM Language_Str MSG_VC_JERK                         = _UxGT("V") LCD_STR_C _UxGT("-Jerk");
341
+  PROGMEM Language_Str MSG_VI_JERK                         = _UxGT("V") LCD_STR_I _UxGT("-Jerk");
342
+  PROGMEM Language_Str MSG_VJ_JERK                         = _UxGT("V") LCD_STR_J _UxGT("-Jerk");
343
+  PROGMEM Language_Str MSG_VK_JERK                         = _UxGT("V") LCD_STR_K _UxGT("-Jerk");
332 344
   PROGMEM Language_Str MSG_VE_JERK                         = _UxGT("Ve-Jerk");
333 345
   PROGMEM Language_Str MSG_JUNCTION_DEVIATION              = _UxGT("Junction Dev");
334 346
   PROGMEM Language_Str MSG_VELOCITY                        = _UxGT("Velocity");
335 347
   PROGMEM Language_Str MSG_VMAX_A                          = _UxGT("Vmax ") LCD_STR_A;
336 348
   PROGMEM Language_Str MSG_VMAX_B                          = _UxGT("Vmax ") LCD_STR_B;
337 349
   PROGMEM Language_Str MSG_VMAX_C                          = _UxGT("Vmax ") LCD_STR_C;
350
+  PROGMEM Language_Str MSG_VMAX_I                          = _UxGT("Vmax ") LCD_STR_I;
351
+  PROGMEM Language_Str MSG_VMAX_J                          = _UxGT("Vmax ") LCD_STR_J;
352
+  PROGMEM Language_Str MSG_VMAX_K                          = _UxGT("Vmax ") LCD_STR_K;
338 353
   PROGMEM Language_Str MSG_VMAX_E                          = _UxGT("Vmax ") LCD_STR_E;
339 354
   PROGMEM Language_Str MSG_VMAX_EN                         = _UxGT("Vmax *");
340 355
   PROGMEM Language_Str MSG_VMIN                            = _UxGT("Vmin");
@@ -343,6 +358,9 @@ namespace Language_en {
343 358
   PROGMEM Language_Str MSG_AMAX_A                          = _UxGT("Amax ") LCD_STR_A;
344 359
   PROGMEM Language_Str MSG_AMAX_B                          = _UxGT("Amax ") LCD_STR_B;
345 360
   PROGMEM Language_Str MSG_AMAX_C                          = _UxGT("Amax ") LCD_STR_C;
361
+  PROGMEM Language_Str MSG_AMAX_I                          = _UxGT("Amax ") LCD_STR_I;
362
+  PROGMEM Language_Str MSG_AMAX_J                          = _UxGT("Amax ") LCD_STR_J;
363
+  PROGMEM Language_Str MSG_AMAX_K                          = _UxGT("Amax ") LCD_STR_K;
346 364
   PROGMEM Language_Str MSG_AMAX_E                          = _UxGT("Amax ") LCD_STR_E;
347 365
   PROGMEM Language_Str MSG_AMAX_EN                         = _UxGT("Amax *");
348 366
   PROGMEM Language_Str MSG_A_RETRACT                       = _UxGT("A-Retract");
@@ -353,6 +371,9 @@ namespace Language_en {
353 371
   PROGMEM Language_Str MSG_A_STEPS                         = LCD_STR_A _UxGT(" Steps/mm");
354 372
   PROGMEM Language_Str MSG_B_STEPS                         = LCD_STR_B _UxGT(" Steps/mm");
355 373
   PROGMEM Language_Str MSG_C_STEPS                         = LCD_STR_C _UxGT(" Steps/mm");
374
+  PROGMEM Language_Str MSG_I_STEPS                         = LCD_STR_I _UxGT(" Steps/mm");
375
+  PROGMEM Language_Str MSG_J_STEPS                         = LCD_STR_J _UxGT(" Steps/mm");
376
+  PROGMEM Language_Str MSG_K_STEPS                         = LCD_STR_K _UxGT(" Steps/mm");
356 377
   PROGMEM Language_Str MSG_E_STEPS                         = _UxGT("E steps/mm");
357 378
   PROGMEM Language_Str MSG_EN_STEPS                        = _UxGT("* Steps/mm");
358 379
   PROGMEM Language_Str MSG_TEMPERATURE                     = _UxGT("Temperature");
@@ -486,6 +507,9 @@ namespace Language_en {
486 507
   PROGMEM Language_Str MSG_BABYSTEP_X                      = _UxGT("Babystep X");
487 508
   PROGMEM Language_Str MSG_BABYSTEP_Y                      = _UxGT("Babystep Y");
488 509
   PROGMEM Language_Str MSG_BABYSTEP_Z                      = _UxGT("Babystep Z");
510
+  PROGMEM Language_Str MSG_BABYSTEP_I                      = _UxGT("Babystep ") LCD_STR_I;
511
+  PROGMEM Language_Str MSG_BABYSTEP_J                      = _UxGT("Babystep ") LCD_STR_J;
512
+  PROGMEM Language_Str MSG_BABYSTEP_K                      = _UxGT("Babystep ") LCD_STR_K;
489 513
   PROGMEM Language_Str MSG_BABYSTEP_TOTAL                  = _UxGT("Total");
490 514
   PROGMEM Language_Str MSG_ENDSTOP_ABORT                   = _UxGT("Endstop Abort");
491 515
   PROGMEM Language_Str MSG_HEATING_FAILED_LCD              = _UxGT("Heating Failed");
@@ -566,6 +590,9 @@ namespace Language_en {
566 590
   PROGMEM Language_Str MSG_DAC_PERCENT_X                   = _UxGT("X Driver %");
567 591
   PROGMEM Language_Str MSG_DAC_PERCENT_Y                   = _UxGT("Y Driver %");
568 592
   PROGMEM Language_Str MSG_DAC_PERCENT_Z                   = _UxGT("Z Driver %");
593
+  PROGMEM Language_Str MSG_DAC_PERCENT_I                   = _UxGT("I Driver %");
594
+  PROGMEM Language_Str MSG_DAC_PERCENT_J                   = _UxGT("J Driver %");
595
+  PROGMEM Language_Str MSG_DAC_PERCENT_K                   = _UxGT("K Driver %");
569 596
   PROGMEM Language_Str MSG_DAC_PERCENT_E                   = _UxGT("E Driver %");
570 597
   PROGMEM Language_Str MSG_ERROR_TMC                       = _UxGT("TMC CONNECTION ERROR");
571 598
   PROGMEM Language_Str MSG_DAC_EEPROM_WRITE                = _UxGT("DAC EEPROM Write");
@@ -683,6 +710,9 @@ namespace Language_en {
683 710
   PROGMEM Language_Str MSG_BACKLASH_A                      = LCD_STR_A;
684 711
   PROGMEM Language_Str MSG_BACKLASH_B                      = LCD_STR_B;
685 712
   PROGMEM Language_Str MSG_BACKLASH_C                      = LCD_STR_C;
713
+  PROGMEM Language_Str MSG_BACKLASH_I                      = LCD_STR_I;
714
+  PROGMEM Language_Str MSG_BACKLASH_J                      = LCD_STR_J;
715
+  PROGMEM Language_Str MSG_BACKLASH_K                      = LCD_STR_K;
686 716
   PROGMEM Language_Str MSG_BACKLASH_CORRECTION             = _UxGT("Correction");
687 717
   PROGMEM Language_Str MSG_BACKLASH_SMOOTHING              = _UxGT("Smoothing");
688 718
 

+ 10
- 4
Marlin/src/lcd/menu/menu_advanced.cpp View File

@@ -356,7 +356,7 @@ void menu_backlash();
356 356
       #elif ENABLED(LIMITED_MAX_FR_EDITING)
357 357
         DEFAULT_MAX_FEEDRATE
358 358
       #else
359
-        LOGICAL_AXIS_ARRAY(9999, 9999, 9999, 9999)
359
+        LOGICAL_AXIS_ARRAY(9999, 9999, 9999, 9999, 9999, 9999, 9999)
360 360
       #endif
361 361
     ;
362 362
     #if ENABLED(LIMITED_MAX_FR_EDITING) && !defined(MAX_FEEDRATE_EDIT_VALUES)
@@ -399,7 +399,7 @@ void menu_backlash();
399 399
       #elif ENABLED(LIMITED_MAX_ACCEL_EDITING)
400 400
         DEFAULT_MAX_ACCELERATION
401 401
       #else
402
-        LOGICAL_AXIS_ARRAY(99000, 99000, 99000, 99000)
402
+        LOGICAL_AXIS_ARRAY(99000, 99000, 99000, 99000, 99000, 99000, 99000)
403 403
       #endif
404 404
     ;
405 405
     #if ENABLED(LIMITED_MAX_ACCEL_EDITING) && !defined(MAX_ACCEL_EDIT_VALUES)
@@ -477,7 +477,10 @@ void menu_backlash();
477 477
       #else
478 478
         #define EDIT_JERK_C() EDIT_ITEM_FAST(float52sign, MSG_VC_JERK, &planner.max_jerk.c, 0.1f, max_jerk_edit.c)
479 479
       #endif
480
-      LINEAR_AXIS_CODE(EDIT_JERK(A), EDIT_JERK(B), EDIT_JERK_C());
480
+      LINEAR_AXIS_CODE(
481
+        EDIT_JERK(A), EDIT_JERK(B), EDIT_JERK_C(),
482
+        EDIT_JERK(I), EDIT_JERK(J), EDIT_JERK(K)
483
+      );
481 484
 
482 485
       #if HAS_EXTRUDERS
483 486
         EDIT_ITEM_FAST(float52sign, MSG_VE_JERK, &planner.max_jerk.e, 0.1f, max_jerk_edit.e);
@@ -515,7 +518,10 @@ void menu_advanced_steps_per_mm() {
515 518
   BACK_ITEM(MSG_ADVANCED_SETTINGS);
516 519
 
517 520
   #define EDIT_QSTEPS(Q) EDIT_ITEM_FAST(float51, MSG_##Q##_STEPS, &planner.settings.axis_steps_per_mm[_AXIS(Q)], 5, 9999, []{ planner.refresh_positioning(); })
518
-  LINEAR_AXIS_CODE(EDIT_QSTEPS(A), EDIT_QSTEPS(B), EDIT_QSTEPS(C));
521
+  LINEAR_AXIS_CODE(
522
+    EDIT_QSTEPS(A), EDIT_QSTEPS(B), EDIT_QSTEPS(C),
523
+    EDIT_QSTEPS(I), EDIT_QSTEPS(J), EDIT_QSTEPS(K)
524
+  );
519 525
 
520 526
   #if ENABLED(DISTINCT_E_FACTORS)
521 527
     LOOP_L_N(n, E_STEPPERS)

+ 15
- 2
Marlin/src/lcd/menu/menu_backlash.cpp View File

@@ -45,8 +45,21 @@ void menu_backlash() {
45 45
   #endif
46 46
   #define EDIT_BACKLASH_DISTANCE(N) EDIT_ITEM_FAST(float43, MSG_BACKLASH_##N, &backlash.distance_mm[_AXIS(N)], 0.0f, 9.9f);
47 47
   if (_CAN_CALI(A)) EDIT_BACKLASH_DISTANCE(A);
48
-  if (_CAN_CALI(B)) EDIT_BACKLASH_DISTANCE(B);
49
-  if (_CAN_CALI(C)) EDIT_BACKLASH_DISTANCE(C);
48
+  #if HAS_Y_AXIS && _CAN_CALI(B)
49
+    EDIT_BACKLASH_DISTANCE(B);
50
+  #endif
51
+  #if HAS_Z_AXIS && _CAN_CALI(C)
52
+    EDIT_BACKLASH_DISTANCE(C);
53
+  #endif
54
+  #if LINEAR_AXES >= 4 && _CAN_CALI(I)
55
+    EDIT_BACKLASH_DISTANCE(I);
56
+  #endif
57
+  #if LINEAR_AXES >= 5 && _CAN_CALI(J)
58
+    EDIT_BACKLASH_DISTANCE(J);
59
+  #endif
60
+  #if LINEAR_AXES >= 6 && _CAN_CALI(K)
61
+    EDIT_BACKLASH_DISTANCE(K);
62
+  #endif
50 63
 
51 64
   #ifdef BACKLASH_SMOOTHING_MM
52 65
     EDIT_ITEM_FAST(float43, MSG_BACKLASH_SMOOTHING, &backlash.smoothing_mm, 0.0f, 9.9f);

+ 45
- 6
Marlin/src/lcd/menu/menu_motion.cpp View File

@@ -89,8 +89,21 @@ static void _lcd_move_xyz(PGM_P const name, const AxisEnum axis) {
89 89
   }
90 90
 }
91 91
 void lcd_move_x() { _lcd_move_xyz(GET_TEXT(MSG_MOVE_X), X_AXIS); }
92
-void lcd_move_y() { _lcd_move_xyz(GET_TEXT(MSG_MOVE_Y), Y_AXIS); }
93
-void lcd_move_z() { _lcd_move_xyz(GET_TEXT(MSG_MOVE_Z), Z_AXIS); }
92
+#if HAS_Y_AXIS
93
+  void lcd_move_y() { _lcd_move_xyz(GET_TEXT(MSG_MOVE_Y), Y_AXIS); }
94
+#endif
95
+#if HAS_Z_AXIS
96
+  void lcd_move_z() { _lcd_move_xyz(GET_TEXT(MSG_MOVE_Z), Z_AXIS); }
97
+#endif
98
+#if LINEAR_AXES >= 4
99
+  void lcd_move_i() { _lcd_move_xyz(GET_TEXT(MSG_MOVE_I), I_AXIS); }
100
+#endif
101
+#if LINEAR_AXES >= 5
102
+  void lcd_move_j() { _lcd_move_xyz(GET_TEXT(MSG_MOVE_J), J_AXIS); }
103
+#endif
104
+#if LINEAR_AXES >= 6
105
+  void lcd_move_k() { _lcd_move_xyz(GET_TEXT(MSG_MOVE_K), K_AXIS); }
106
+#endif
94 107
 
95 108
 #if E_MANUAL
96 109
 
@@ -217,14 +230,27 @@ void menu_move() {
217 230
   if (NONE(IS_KINEMATIC, NO_MOTION_BEFORE_HOMING) || all_axes_homed()) {
218 231
     if (TERN1(DELTA, current_position.z <= delta_clip_start_height)) {
219 232
       SUBMENU(MSG_MOVE_X, []{ _menu_move_distance(X_AXIS, lcd_move_x); });
220
-      SUBMENU(MSG_MOVE_Y, []{ _menu_move_distance(Y_AXIS, lcd_move_y); });
233
+      #if HAS_Y_AXIS
234
+        SUBMENU(MSG_MOVE_Y, []{ _menu_move_distance(Y_AXIS, lcd_move_y); });
235
+      #endif
221 236
     }
222 237
     #if ENABLED(DELTA)
223 238
       else
224 239
         ACTION_ITEM(MSG_FREE_XY, []{ line_to_z(delta_clip_start_height); ui.synchronize(); });
225 240
     #endif
226 241
 
227
-    SUBMENU(MSG_MOVE_Z, []{ _menu_move_distance(Z_AXIS, lcd_move_z); });
242
+    #if HAS_Z_AXIS
243
+      SUBMENU(MSG_MOVE_Z, []{ _menu_move_distance(Z_AXIS, lcd_move_z); });
244
+    #endif
245
+    #if LINEAR_AXES >= 4
246
+      SUBMENU(MSG_MOVE_I, []{ _menu_move_distance(I_AXIS, lcd_move_i); });
247
+    #endif
248
+    #if LINEAR_AXES >= 5
249
+      SUBMENU(MSG_MOVE_J, []{ _menu_move_distance(J_AXIS, lcd_move_j); });
250
+    #endif
251
+    #if LINEAR_AXES >= 6
252
+      SUBMENU(MSG_MOVE_K, []{ _menu_move_distance(K_AXIS, lcd_move_k); });
253
+    #endif
228 254
   }
229 255
   else
230 256
     GCODES_ITEM(MSG_AUTO_HOME, G28_STR);
@@ -321,8 +347,21 @@ void menu_motion() {
321 347
   GCODES_ITEM(MSG_AUTO_HOME, G28_STR);
322 348
   #if ENABLED(INDIVIDUAL_AXIS_HOMING_MENU)
323 349
     GCODES_ITEM(MSG_AUTO_HOME_X, PSTR("G28X"));
324
-    GCODES_ITEM(MSG_AUTO_HOME_Y, PSTR("G28Y"));
325
-    GCODES_ITEM(MSG_AUTO_HOME_Z, PSTR("G28Z"));
350
+    #if HAS_Y_AXIS
351
+      GCODES_ITEM(MSG_AUTO_HOME_Y, PSTR("G28Y"));
352
+    #endif
353
+    #if HAS_Z_AXIS
354
+      GCODES_ITEM(MSG_AUTO_HOME_Z, PSTR("G28Z"));
355
+    #endif
356
+    #if LINEAR_AXES >= 4
357
+      GCODES_ITEM(MSG_AUTO_HOME_I, PSTR("G28" I_STR));
358
+    #endif
359
+    #if LINEAR_AXES >= 5
360
+      GCODES_ITEM(MSG_AUTO_HOME_J, PSTR("G28" J_STR));
361
+    #endif
362
+    #if LINEAR_AXES >= 6
363
+      GCODES_ITEM(MSG_AUTO_HOME_K, PSTR("G28" K_STR));
364
+    #endif
326 365
   #endif
327 366
 
328 367
   //

+ 46
- 129
Marlin/src/lcd/menu/menu_tmc.cpp View File

@@ -95,54 +95,22 @@ void menu_tmc_current() {
95 95
   void menu_tmc_hybrid_thrs() {
96 96
     START_MENU();
97 97
     BACK_ITEM(MSG_TMC_DRIVERS);
98
-    #if AXIS_HAS_STEALTHCHOP(X)
99
-      TMC_EDIT_STORED_HYBRID_THRS(X, STR_X);
100
-    #endif
101
-    #if AXIS_HAS_STEALTHCHOP(Y)
102
-      TMC_EDIT_STORED_HYBRID_THRS(Y, STR_Y);
103
-    #endif
104
-    #if AXIS_HAS_STEALTHCHOP(Z)
105
-      TMC_EDIT_STORED_HYBRID_THRS(Z, STR_Z);
106
-    #endif
107
-    #if AXIS_HAS_STEALTHCHOP(X2)
108
-      TMC_EDIT_STORED_HYBRID_THRS(X2, STR_X2);
109
-    #endif
110
-    #if AXIS_HAS_STEALTHCHOP(Y2)
111
-      TMC_EDIT_STORED_HYBRID_THRS(Y2, STR_Y2);
112
-    #endif
113
-    #if AXIS_HAS_STEALTHCHOP(Z2)
114
-      TMC_EDIT_STORED_HYBRID_THRS(Z2, STR_Z2);
115
-    #endif
116
-    #if AXIS_HAS_STEALTHCHOP(Z3)
117
-      TMC_EDIT_STORED_HYBRID_THRS(Z3, STR_Z3);
118
-    #endif
119
-    #if AXIS_HAS_STEALTHCHOP(Z4)
120
-      TMC_EDIT_STORED_HYBRID_THRS(Z4, STR_Z4);
121
-    #endif
122
-    #if AXIS_HAS_STEALTHCHOP(E0)
123
-      TMC_EDIT_STORED_HYBRID_THRS(E0, LCD_STR_E0);
124
-    #endif
125
-    #if AXIS_HAS_STEALTHCHOP(E1)
126
-      TMC_EDIT_STORED_HYBRID_THRS(E1, LCD_STR_E1);
127
-    #endif
128
-    #if AXIS_HAS_STEALTHCHOP(E2)
129
-      TMC_EDIT_STORED_HYBRID_THRS(E2, LCD_STR_E2);
130
-    #endif
131
-    #if AXIS_HAS_STEALTHCHOP(E3)
132
-      TMC_EDIT_STORED_HYBRID_THRS(E3, LCD_STR_E3);
133
-    #endif
134
-    #if AXIS_HAS_STEALTHCHOP(E4)
135
-      TMC_EDIT_STORED_HYBRID_THRS(E4, LCD_STR_E4);
136
-    #endif
137
-    #if AXIS_HAS_STEALTHCHOP(E5)
138
-      TMC_EDIT_STORED_HYBRID_THRS(E5, LCD_STR_E5);
139
-    #endif
140
-    #if AXIS_HAS_STEALTHCHOP(E6)
141
-      TMC_EDIT_STORED_HYBRID_THRS(E6, LCD_STR_E6);
142
-    #endif
143
-    #if AXIS_HAS_STEALTHCHOP(E7)
144
-      TMC_EDIT_STORED_HYBRID_THRS(E7, LCD_STR_E7);
145
-    #endif
98
+    TERN_(X_HAS_STEALTHCHOP,  TMC_EDIT_STORED_HYBRID_THRS(X,  STR_X));
99
+    TERN_(Y_HAS_STEALTHCHOP,  TMC_EDIT_STORED_HYBRID_THRS(Y,  STR_Y));
100
+    TERN_(Z_HAS_STEALTHCHOP,  TMC_EDIT_STORED_HYBRID_THRS(Z,  STR_Z));
101
+    TERN_(X2_HAS_STEALTHCHOP, TMC_EDIT_STORED_HYBRID_THRS(X2, STR_X2));
102
+    TERN_(Y2_HAS_STEALTHCHOP, TMC_EDIT_STORED_HYBRID_THRS(Y2, STR_Y2));
103
+    TERN_(Z2_HAS_STEALTHCHOP, TMC_EDIT_STORED_HYBRID_THRS(Z2, STR_Z2));
104
+    TERN_(Z3_HAS_STEALTHCHOP, TMC_EDIT_STORED_HYBRID_THRS(Z3, STR_Z3));
105
+    TERN_(Z4_HAS_STEALTHCHOP, TMC_EDIT_STORED_HYBRID_THRS(Z4, STR_Z4));
106
+    TERN_(E0_HAS_STEALTHCHOP, TMC_EDIT_STORED_HYBRID_THRS(E0, LCD_STR_E0));
107
+    TERN_(E1_HAS_STEALTHCHOP, TMC_EDIT_STORED_HYBRID_THRS(E1, LCD_STR_E1));
108
+    TERN_(E2_HAS_STEALTHCHOP, TMC_EDIT_STORED_HYBRID_THRS(E2, LCD_STR_E2));
109
+    TERN_(E3_HAS_STEALTHCHOP, TMC_EDIT_STORED_HYBRID_THRS(E3, LCD_STR_E3));
110
+    TERN_(E4_HAS_STEALTHCHOP, TMC_EDIT_STORED_HYBRID_THRS(E4, LCD_STR_E4));
111
+    TERN_(E5_HAS_STEALTHCHOP, TMC_EDIT_STORED_HYBRID_THRS(E5, LCD_STR_E5));
112
+    TERN_(E6_HAS_STEALTHCHOP, TMC_EDIT_STORED_HYBRID_THRS(E6, LCD_STR_E6));
113
+    TERN_(E7_HAS_STEALTHCHOP, TMC_EDIT_STORED_HYBRID_THRS(E7, LCD_STR_E7));
146 114
     END_MENU();
147 115
   }
148 116
 
@@ -155,30 +123,17 @@ void menu_tmc_current() {
155 123
   void menu_tmc_homing_thrs() {
156 124
     START_MENU();
157 125
     BACK_ITEM(MSG_TMC_DRIVERS);
158
-    #if X_SENSORLESS
159
-      TMC_EDIT_STORED_SGT(X);
160
-      #if X2_SENSORLESS
161
-        TMC_EDIT_STORED_SGT(X2);
162
-      #endif
163
-    #endif
164
-    #if Y_SENSORLESS
165
-      TMC_EDIT_STORED_SGT(Y);
166
-      #if Y2_SENSORLESS
167
-        TMC_EDIT_STORED_SGT(Y2);
168
-      #endif
169
-    #endif
170
-    #if Z_SENSORLESS
171
-      TMC_EDIT_STORED_SGT(Z);
172
-      #if Z2_SENSORLESS
173
-        TMC_EDIT_STORED_SGT(Z2);
174
-      #endif
175
-      #if Z3_SENSORLESS
176
-        TMC_EDIT_STORED_SGT(Z3);
177
-      #endif
178
-      #if Z4_SENSORLESS
179
-        TMC_EDIT_STORED_SGT(Z4);
180
-      #endif
181
-    #endif
126
+    TERN_( X_SENSORLESS, TMC_EDIT_STORED_SGT(X));
127
+    TERN_(X2_SENSORLESS, TMC_EDIT_STORED_SGT(X2));
128
+    TERN_( Y_SENSORLESS, TMC_EDIT_STORED_SGT(Y));
129
+    TERN_(Y2_SENSORLESS, TMC_EDIT_STORED_SGT(Y2));
130
+    TERN_( Z_SENSORLESS, TMC_EDIT_STORED_SGT(Z));
131
+    TERN_(Z2_SENSORLESS, TMC_EDIT_STORED_SGT(Z2));
132
+    TERN_(Z3_SENSORLESS, TMC_EDIT_STORED_SGT(Z3));
133
+    TERN_(Z4_SENSORLESS, TMC_EDIT_STORED_SGT(Z4));
134
+    TERN_( I_SENSORLESS, TMC_EDIT_STORED_SGT(I));
135
+    TERN_( J_SENSORLESS, TMC_EDIT_STORED_SGT(J));
136
+    TERN_( K_SENSORLESS, TMC_EDIT_STORED_SGT(K));
182 137
     END_MENU();
183 138
   }
184 139
 
@@ -192,54 +147,22 @@ void menu_tmc_current() {
192 147
     START_MENU();
193 148
     STATIC_ITEM(MSG_TMC_STEALTH_ENABLED);
194 149
     BACK_ITEM(MSG_TMC_DRIVERS);
195
-    #if AXIS_HAS_STEALTHCHOP(X)
196
-      TMC_EDIT_STEP_MODE(X, STR_X);
197
-    #endif
198
-    #if AXIS_HAS_STEALTHCHOP(Y)
199
-      TMC_EDIT_STEP_MODE(Y, STR_Y);
200
-    #endif
201
-    #if AXIS_HAS_STEALTHCHOP(Z)
202
-      TMC_EDIT_STEP_MODE(Z, STR_Z);
203
-    #endif
204
-    #if AXIS_HAS_STEALTHCHOP(X2)
205
-      TMC_EDIT_STEP_MODE(X2, STR_X2);
206
-    #endif
207
-    #if AXIS_HAS_STEALTHCHOP(Y2)
208
-      TMC_EDIT_STEP_MODE(Y2, STR_Y2);
209
-    #endif
210
-    #if AXIS_HAS_STEALTHCHOP(Z2)
211
-      TMC_EDIT_STEP_MODE(Z2, STR_Z2);
212
-    #endif
213
-    #if AXIS_HAS_STEALTHCHOP(Z3)
214
-      TMC_EDIT_STEP_MODE(Z3, STR_Z3);
215
-    #endif
216
-    #if AXIS_HAS_STEALTHCHOP(Z4)
217
-      TMC_EDIT_STEP_MODE(Z4, STR_Z4);
218
-    #endif
219
-    #if AXIS_HAS_STEALTHCHOP(E0)
220
-      TMC_EDIT_STEP_MODE(E0, LCD_STR_E0);
221
-    #endif
222
-    #if AXIS_HAS_STEALTHCHOP(E1)
223
-      TMC_EDIT_STEP_MODE(E1, LCD_STR_E1);
224
-    #endif
225
-    #if AXIS_HAS_STEALTHCHOP(E2)
226
-      TMC_EDIT_STEP_MODE(E2, LCD_STR_E2);
227
-    #endif
228
-    #if AXIS_HAS_STEALTHCHOP(E3)
229
-      TMC_EDIT_STEP_MODE(E3, LCD_STR_E3);
230
-    #endif
231
-    #if AXIS_HAS_STEALTHCHOP(E4)
232
-      TMC_EDIT_STEP_MODE(E4, LCD_STR_E4);
233
-    #endif
234
-    #if AXIS_HAS_STEALTHCHOP(E5)
235
-      TMC_EDIT_STEP_MODE(E5, LCD_STR_E5);
236
-    #endif
237
-    #if AXIS_HAS_STEALTHCHOP(E6)
238
-      TMC_EDIT_STEP_MODE(E6, LCD_STR_E6);
239
-    #endif
240
-    #if AXIS_HAS_STEALTHCHOP(E7)
241
-      TMC_EDIT_STEP_MODE(E7, LCD_STR_E7);
242
-    #endif
150
+    TERN_( X_HAS_STEALTHCHOP, TMC_EDIT_STEP_MODE(X,  STR_X));
151
+    TERN_(X2_HAS_STEALTHCHOP, TMC_EDIT_STEP_MODE(X2, STR_X2));
152
+    TERN_( Y_HAS_STEALTHCHOP, TMC_EDIT_STEP_MODE(Y,  STR_Y));
153
+    TERN_(Y2_HAS_STEALTHCHOP, TMC_EDIT_STEP_MODE(Y2, STR_Y2));
154
+    TERN_( Z_HAS_STEALTHCHOP, TMC_EDIT_STEP_MODE(Z,  STR_Z));
155
+    TERN_(Z2_HAS_STEALTHCHOP, TMC_EDIT_STEP_MODE(Z2, STR_Z2));
156
+    TERN_(Z3_HAS_STEALTHCHOP, TMC_EDIT_STEP_MODE(Z3, STR_Z3));
157
+    TERN_(Z4_HAS_STEALTHCHOP, TMC_EDIT_STEP_MODE(Z4, STR_Z4));
158
+    TERN_(E0_HAS_STEALTHCHOP, TMC_EDIT_STEP_MODE(E0, LCD_STR_E0));
159
+    TERN_(E1_HAS_STEALTHCHOP, TMC_EDIT_STEP_MODE(E1, LCD_STR_E1));
160
+    TERN_(E2_HAS_STEALTHCHOP, TMC_EDIT_STEP_MODE(E2, LCD_STR_E2));
161
+    TERN_(E3_HAS_STEALTHCHOP, TMC_EDIT_STEP_MODE(E3, LCD_STR_E3));
162
+    TERN_(E4_HAS_STEALTHCHOP, TMC_EDIT_STEP_MODE(E4, LCD_STR_E4));
163
+    TERN_(E5_HAS_STEALTHCHOP, TMC_EDIT_STEP_MODE(E5, LCD_STR_E5));
164
+    TERN_(E6_HAS_STEALTHCHOP, TMC_EDIT_STEP_MODE(E6, LCD_STR_E6));
165
+    TERN_(E7_HAS_STEALTHCHOP, TMC_EDIT_STEP_MODE(E7, LCD_STR_E7));
243 166
     END_MENU();
244 167
   }
245 168
 
@@ -249,15 +172,9 @@ void menu_tmc() {
249 172
   START_MENU();
250 173
   BACK_ITEM(MSG_ADVANCED_SETTINGS);
251 174
   SUBMENU(MSG_TMC_CURRENT, menu_tmc_current);
252
-  #if ENABLED(HYBRID_THRESHOLD)
253
-    SUBMENU(MSG_TMC_HYBRID_THRS, menu_tmc_hybrid_thrs);
254
-  #endif
255
-  #if ENABLED(SENSORLESS_HOMING)
256
-    SUBMENU(MSG_TMC_HOMING_THRS, menu_tmc_homing_thrs);
257
-  #endif
258
-  #if HAS_STEALTHCHOP
259
-    SUBMENU(MSG_TMC_STEPPING_MODE, menu_tmc_step_mode);
260
-  #endif
175
+  TERN_(HYBRID_THRESHOLD,   SUBMENU(MSG_TMC_HYBRID_THRS, menu_tmc_hybrid_thrs));
176
+  TERN_(SENSORLESS_HOMING,  SUBMENU(MSG_TMC_HOMING_THRS, menu_tmc_homing_thrs));
177
+  TERN_(HAS_STEALTHCHOP,    SUBMENU(MSG_TMC_STEPPING_MODE, menu_tmc_step_mode));
261 178
   END_MENU();
262 179
 }
263 180
 

+ 6
- 4
Marlin/src/lcd/tft/ui_1024x600.cpp View File

@@ -653,10 +653,12 @@ static void drawAxisValue(const AxisEnum axis) {
653 653
 static void moveAxis(const AxisEnum axis, const int8_t direction) {
654 654
   quick_feedback();
655 655
 
656
-  if (axis == E_AXIS && thermalManager.tooColdToExtrude(motionAxisState.e_selection)) {
657
-    drawMessage("Too cold");
658
-    return;
659
-  }
656
+  #if ENABLED(PREVENT_COLD_EXTRUSION)
657
+    if (axis == E_AXIS && thermalManager.tooColdToExtrude(motionAxisState.e_selection)) {
658
+      drawMessage("Too cold");
659
+      return;
660
+    }
661
+  #endif
660 662
 
661 663
   const float diff = motionAxisState.currentStepSize * direction;
662 664
 

+ 6
- 4
Marlin/src/lcd/tft/ui_320x240.cpp View File

@@ -638,10 +638,12 @@ static void drawAxisValue(const AxisEnum axis) {
638 638
 static void moveAxis(const AxisEnum axis, const int8_t direction) {
639 639
   quick_feedback();
640 640
 
641
-  if (axis == E_AXIS && thermalManager.tooColdToExtrude(motionAxisState.e_selection)) {
642
-    drawMessage("Too cold");
643
-    return;
644
-  }
641
+  #if ENABLED(PREVENT_COLD_EXTRUSION)
642
+    if (axis == E_AXIS && thermalManager.tooColdToExtrude(motionAxisState.e_selection)) {
643
+      drawMessage("Too cold");
644
+      return;
645
+    }
646
+  #endif
645 647
 
646 648
   const float diff = motionAxisState.currentStepSize * direction;
647 649
 

+ 6
- 4
Marlin/src/lcd/tft/ui_480x320.cpp View File

@@ -640,10 +640,12 @@ static void drawAxisValue(const AxisEnum axis) {
640 640
 static void moveAxis(const AxisEnum axis, const int8_t direction) {
641 641
   quick_feedback();
642 642
 
643
-  if (axis == E_AXIS && thermalManager.tooColdToExtrude(motionAxisState.e_selection)) {
644
-    drawMessage("Too cold");
645
-    return;
646
-  }
643
+  #if ENABLED(PREVENT_COLD_EXTRUSION)
644
+    if (axis == E_AXIS && thermalManager.tooColdToExtrude(motionAxisState.e_selection)) {
645
+      drawMessage("Too cold");
646
+      return;
647
+    }
648
+  #endif
647 649
 
648 650
   const float diff = motionAxisState.currentStepSize * direction;
649 651
 

+ 144
- 56
Marlin/src/libs/L64XX/L64XX_Marlin.cpp View File

@@ -37,19 +37,27 @@ L64XX_Marlin L64xxManager;
37 37
 #include "../../module/planner.h"
38 38
 #include "../../HAL/shared/Delay.h"
39 39
 
40
-static const char str_X[] PROGMEM = "X ",  str_Y[] PROGMEM = "Y ",  str_Z[] PROGMEM = "Z ",
40
+static const char LINEAR_AXIS_LIST(
41
+                   str_X[] PROGMEM = "X ",          str_Y[] PROGMEM = "Y ",          str_Z[] PROGMEM = "Z ",
42
+                   str_I[] PROGMEM = AXIS4_STR " ", str_J[] PROGMEM = AXIS5_STR " ", str_K[] PROGMEM = AXIS6_STR " "
43
+                 ),
41 44
                  str_X2[] PROGMEM = "X2", str_Y2[] PROGMEM = "Y2",
42 45
                  str_Z2[] PROGMEM = "Z2", str_Z3[] PROGMEM = "Z3", str_Z4[] PROGMEM = "Z4",
43
-                 str_E0[] PROGMEM = "E0", str_E1[] PROGMEM = "E1",
44
-                 str_E2[] PROGMEM = "E2", str_E3[] PROGMEM = "E3",
45
-                 str_E4[] PROGMEM = "E4", str_E5[] PROGMEM = "E5",
46
-                 str_E6[] PROGMEM = "E6", str_E7[] PROGMEM = "E7"
46
+                 LIST_N(EXTRUDERS,
47
+                   str_E0[] PROGMEM = "E0", str_E1[] PROGMEM = "E1",
48
+                   str_E2[] PROGMEM = "E2", str_E3[] PROGMEM = "E3",
49
+                   str_E4[] PROGMEM = "E4", str_E5[] PROGMEM = "E5",
50
+                   str_E6[] PROGMEM = "E6", str_E7[] PROGMEM = "E7"
51
+                 )
47 52
                  ;
48 53
 
54
+#define _EN_ITEM(N) , str_E##N
49 55
 PGM_P const L64XX_Marlin::index_to_axis[] PROGMEM = {
50
-  str_X, str_Y, str_Z, str_X2, str_Y2, str_Z2, str_Z3, str_Z4,
51
-  str_E0, str_E1, str_E2, str_E3, str_E4, str_E5, str_E6, str_E7
56
+  LINEAR_AXIS_LIST(str_X, str_Y, str_Z, str_I, str_J, str_K),
57
+  str_X2, str_Y2, str_Z2, str_Z3, str_Z4
58
+  REPEAT(E_STEPPERS, _EN_ITEM)
52 59
 };
60
+#undef _EN_ITEM
53 61
 
54 62
 #define DEBUG_OUT ENABLED(L6470_CHITCHAT)
55 63
 #include "../../core/debug_out.h"
@@ -58,16 +66,17 @@ void echo_yes_no(const bool yes) { DEBUG_ECHOPGM_P(yes ? PSTR(" YES") : PSTR(" N
58 66
 
59 67
 uint8_t L64XX_Marlin::dir_commands[MAX_L64XX];  // array to hold direction command for each driver
60 68
 
69
+#define _EN_ITEM(N) , INVERT_E##N##_DIR
61 70
 const uint8_t L64XX_Marlin::index_to_dir[MAX_L64XX] = {
62
-  INVERT_X_DIR, INVERT_Y_DIR, INVERT_Z_DIR
71
+    LINEAR_AXIS_LIST(INVERT_X_DIR, INVERT_Y_DIR, INVERT_Z_DIR, INVERT_I_DIR, INVERT_J_DIR, INVERT_K_DIR)
63 72
   , (INVERT_X_DIR) ^ BOTH(X_DUAL_STEPPER_DRIVERS, INVERT_X2_VS_X_DIR) // X2
64 73
   , (INVERT_Y_DIR) ^ BOTH(Y_DUAL_STEPPER_DRIVERS, INVERT_Y2_VS_Y_DIR) // Y2
65 74
   , (INVERT_Z_DIR) ^ ENABLED(INVERT_Z2_VS_Z_DIR) // Z2
66 75
   , (INVERT_Z_DIR) ^ ENABLED(INVERT_Z3_VS_Z_DIR) // Z3
67 76
   , (INVERT_Z_DIR) ^ ENABLED(INVERT_Z4_VS_Z_DIR) // Z4
68
-  , INVERT_E0_DIR, INVERT_E1_DIR, INVERT_E2_DIR, INVERT_E3_DIR
69
-  , INVERT_E4_DIR, INVERT_E5_DIR, INVERT_E6_DIR, INVERT_E7_DIR
77
+    REPEAT(E_STEPPERS, _EN_ITEM)
70 78
 };
79
+#undef _EN_ITEM
71 80
 
72 81
 volatile uint8_t L64XX_Marlin::spi_abort = false;
73 82
 uint8_t L64XX_Marlin::spi_active = false;
@@ -326,6 +335,15 @@ void L64XX_Marlin::set_param(const L64XX_axis_t axis, const uint8_t param, const
326 335
     #if AXIS_IS_L64XX(Z)
327 336
       case Z : SET_L6470_PARAM(Z); break;
328 337
     #endif
338
+    #if AXIS_IS_L64XX(I)
339
+      case I : SET_L6470_PARAM(I); break;
340
+    #endif
341
+    #if AXIS_IS_L64XX(J)
342
+      case J : SET_L6470_PARAM(J); break;
343
+    #endif
344
+    #if AXIS_IS_L64XX(K)
345
+      case K : SET_L6470_PARAM(K); break;
346
+    #endif
329 347
     #if AXIS_IS_L64XX(X2)
330 348
       case X2: SET_L6470_PARAM(X2); break;
331 349
     #endif
@@ -370,8 +388,7 @@ void L64XX_Marlin::set_param(const L64XX_axis_t axis, const uint8_t param, const
370 388
 
371 389
 inline void echo_min_max(const char a, const_float_t min, const_float_t max) {
372 390
   DEBUG_CHAR(' '); DEBUG_CHAR(a);
373
-  DEBUG_ECHOPAIR(" min = ", min);
374
-  DEBUG_ECHOLNPAIR("  max = ", max);
391
+  DEBUG_ECHOLNPAIR(" min = ", min, "  max = ", max);
375 392
 }
376 393
 inline void echo_oct_used(const_float_t oct, const uint8_t stall) {
377 394
   DEBUG_ECHOPAIR("over_current_threshold used     : ", oct);
@@ -433,10 +450,15 @@ uint8_t L64XX_Marlin::get_user_input(uint8_t &driver_count, L64XX_axis_t axis_in
433 450
   // Position calcs & checks
434 451
   //
435 452
 
436
-  const float X_center = LOGICAL_X_POSITION(current_position.x),
437
-              Y_center = LOGICAL_Y_POSITION(current_position.y),
438
-              Z_center = LOGICAL_Z_POSITION(current_position.z),
439
-              E_center = current_position.e;
453
+  const float LOGICAL_AXIS_LIST(
454
+                E_center = current_position.e,
455
+                X_center = LOGICAL_X_POSITION(current_position.x),
456
+                Y_center = LOGICAL_Y_POSITION(current_position.y),
457
+                Z_center = LOGICAL_Z_POSITION(current_position.z),
458
+                I_center = LOGICAL_I_POSITION(current_position.i),
459
+                J_center = LOGICAL_J_POSITION(current_position.j),
460
+                K_center = LOGICAL_K_POSITION(current_position.k)
461
+              );
440 462
 
441 463
   switch (axis_mon[0][0]) {
442 464
     default: position_max = position_min = 0; break;
@@ -451,31 +473,73 @@ uint8_t L64XX_Marlin::get_user_input(uint8_t &driver_count, L64XX_axis_t axis_in
451 473
       }
452 474
     } break;
453 475
 
454
-    case 'Y': {
455
-      position_min = Y_center - displacement;
456
-      position_max = Y_center + displacement;
457
-      echo_min_max('Y', position_min, position_max);
458
-      if (TERN0(HAS_ENDSTOPS, position_min < (Y_MIN_POS) || position_max > (Y_MAX_POS))) {
459
-        err_out_of_bounds();
460
-        return true;
461
-      }
462
-    } break;
476
+    #if HAS_Y_AXIS
477
+      case 'Y': {
478
+        position_min = Y_center - displacement;
479
+        position_max = Y_center + displacement;
480
+        echo_min_max('Y', position_min, position_max);
481
+        if (TERN0(HAS_ENDSTOPS, position_min < (Y_MIN_POS) || position_max > (Y_MAX_POS))) {
482
+          err_out_of_bounds();
483
+          return true;
484
+        }
485
+      } break;
486
+    #endif
463 487
 
464
-    case 'Z': {
465
-      position_min = Z_center - displacement;
466
-      position_max = Z_center + displacement;
467
-      echo_min_max('Z', position_min, position_max);
468
-      if (TERN0(HAS_ENDSTOPS, position_min < (Z_MIN_POS) || position_max > (Z_MAX_POS))) {
469
-        err_out_of_bounds();
470
-        return true;
471
-      }
472
-    } break;
488
+    #if HAS_Z_AXIS
489
+      case 'Z': {
490
+        position_min = Z_center - displacement;
491
+        position_max = Z_center + displacement;
492
+        echo_min_max('Z', position_min, position_max);
493
+        if (TERN0(HAS_ENDSTOPS, position_min < (Z_MIN_POS) || position_max > (Z_MAX_POS))) {
494
+          err_out_of_bounds();
495
+          return true;
496
+        }
497
+      } break;
498
+    #endif
473 499
 
474
-    case 'E': {
475
-      position_min = E_center - displacement;
476
-      position_max = E_center + displacement;
477
-      echo_min_max('E', position_min, position_max);
478
-    } break;
500
+    #if LINEAR_AXES >= 4
501
+      case AXIS4_NAME: {
502
+        position_min = I_center - displacement;
503
+        position_max = I_center + displacement;
504
+        echo_min_max(AXIS4_NAME, position_min, position_max);
505
+        if (TERN0(HAS_ENDSTOPS, position_min < (I_MIN_POS) || position_max > (I_MAX_POS))) {
506
+          err_out_of_bounds();
507
+          return true;
508
+        }
509
+      } break;
510
+    #endif
511
+
512
+    #if LINEAR_AXES >= 5
513
+      case AXIS5_NAME: {
514
+        position_min = J_center - displacement;
515
+        position_max = J_center + displacement;
516
+        echo_min_max(AXIS5_NAME, position_min, position_max);
517
+        if (TERN1(HAS_ENDSTOPS, position_min < (J_MIN_POS) || position_max > (J_MAX_POS))) {
518
+          err_out_of_bounds();
519
+          return true;
520
+        }
521
+      } break;
522
+    #endif
523
+
524
+    #if LINEAR_AXES >= 6
525
+      case AXIS6_NAME: {
526
+        position_min = K_center - displacement;
527
+        position_max = K_center + displacement;
528
+        echo_min_max(AXIS6_NAME, position_min, position_max);
529
+        if (TERN2(HAS_ENDSTOPS, position_min < (K_MIN_POS) || position_max > (K_MAX_POS))) {
530
+          err_out_of_bounds();
531
+          return true;
532
+        }
533
+      } break;
534
+    #endif
535
+
536
+    #if HAS_EXTRUDERS
537
+      case 'E': {
538
+        position_min = E_center - displacement;
539
+        position_max = E_center + displacement;
540
+        echo_min_max('E', position_min, position_max);
541
+      } break;
542
+    #endif
479 543
   }
480 544
 
481 545
   //
@@ -660,7 +724,7 @@ void L64XX_Marlin::say_axis(const L64XX_axis_t axis, const uint8_t label/*=true*
660 724
   bool L64XX_Marlin::monitor_paused = false; // Flag to skip monitor during M122, M906, M916, M917, M918, etc.
661 725
 
662 726
   struct L6470_driver_data {
663
-    uint8_t driver_index;
727
+    L64XX_axis_t driver_index;
664 728
     uint32_t driver_status;
665 729
     uint8_t is_otw;
666 730
     uint8_t otw_counter;
@@ -671,52 +735,61 @@ void L64XX_Marlin::say_axis(const L64XX_axis_t axis, const uint8_t label/*=true*
671 735
 
672 736
   L6470_driver_data driver_L6470_data[] = {
673 737
     #if AXIS_IS_L64XX(X)
674
-      {  0, 0, 0, 0, 0, 0, 0 },
738
+      {  X, 0, 0, 0, 0, 0, 0 },
675 739
     #endif
676 740
     #if AXIS_IS_L64XX(Y)
677
-      {  1, 0, 0, 0, 0, 0, 0 },
741
+      {  Y, 0, 0, 0, 0, 0, 0 },
678 742
     #endif
679 743
     #if AXIS_IS_L64XX(Z)
680
-      {  2, 0, 0, 0, 0, 0, 0 },
744
+      {  Z, 0, 0, 0, 0, 0, 0 },
745
+    #endif
746
+    #if AXIS_IS_L64XX(I)
747
+      {  I, 0, 0, 0, 0, 0, 0 },
748
+    #endif
749
+    #if AXIS_IS_L64XX(J)
750
+      {  J, 0, 0, 0, 0, 0, 0 },
751
+    #endif
752
+    #if AXIS_IS_L64XX(K)
753
+      {  K, 0, 0, 0, 0, 0, 0 },
681 754
     #endif
682 755
     #if AXIS_IS_L64XX(X2)
683
-      {  3, 0, 0, 0, 0, 0, 0 },
756
+      { X2, 0, 0, 0, 0, 0, 0 },
684 757
     #endif
685 758
     #if AXIS_IS_L64XX(Y2)
686
-      {  4, 0, 0, 0, 0, 0, 0 },
759
+      { Y2, 0, 0, 0, 0, 0, 0 },
687 760
     #endif
688 761
     #if AXIS_IS_L64XX(Z2)
689
-      {  5, 0, 0, 0, 0, 0, 0 },
762
+      { Z2, 0, 0, 0, 0, 0, 0 },
690 763
     #endif
691 764
     #if AXIS_IS_L64XX(Z3)
692
-      {  6, 0, 0, 0, 0, 0, 0 },
765
+      { Z3, 0, 0, 0, 0, 0, 0 },
693 766
     #endif
694 767
     #if AXIS_IS_L64XX(Z4)
695
-      {  7, 0, 0, 0, 0, 0, 0 },
768
+      { Z4, 0, 0, 0, 0, 0, 0 },
696 769
     #endif
697 770
     #if AXIS_IS_L64XX(E0)
698
-      {  8, 0, 0, 0, 0, 0, 0 },
771
+      { E0, 0, 0, 0, 0, 0, 0 },
699 772
     #endif
700 773
     #if AXIS_IS_L64XX(E1)
701
-      {  9, 0, 0, 0, 0, 0, 0 },
774
+      { E1, 0, 0, 0, 0, 0, 0 },
702 775
     #endif
703 776
     #if AXIS_IS_L64XX(E2)
704
-      { 10, 0, 0, 0, 0, 0, 0 },
777
+      { E2, 0, 0, 0, 0, 0, 0 },
705 778
     #endif
706 779
     #if AXIS_IS_L64XX(E3)
707
-      { 11, 0, 0, 0, 0, 0, 0 },
780
+      { E3, 0, 0, 0, 0, 0, 0 },
708 781
     #endif
709 782
     #if AXIS_IS_L64XX(E4)
710
-      { 12, 0, 0, 0, 0, 0, 0 },
783
+      { E4, 0, 0, 0, 0, 0, 0 },
711 784
     #endif
712 785
     #if AXIS_IS_L64XX(E5)
713
-      { 13, 0, 0, 0, 0, 0, 0 }
786
+      { E5, 0, 0, 0, 0, 0, 0 }
714 787
     #endif
715 788
     #if AXIS_IS_L64XX(E6)
716
-      { 14, 0, 0, 0, 0, 0, 0 }
789
+      { E6, 0, 0, 0, 0, 0, 0 }
717 790
     #endif
718 791
     #if AXIS_IS_L64XX(E7)
719
-      { 16, 0, 0, 0, 0, 0, 0 }
792
+      { E7, 0, 0, 0, 0, 0, 0 }
720 793
     #endif
721 794
   };
722 795
 
@@ -863,6 +936,15 @@ void L64XX_Marlin::say_axis(const L64XX_axis_t axis, const uint8_t label/*=true*
863 936
         #if AXIS_IS_L64XX(Z)
864 937
           monitor_update(Z);
865 938
         #endif
939
+        #if AXIS_IS_L64XX(I)
940
+          monitor_update(I);
941
+        #endif
942
+        #if AXIS_IS_L64XX(J)
943
+          monitor_update(J);
944
+        #endif
945
+        #if AXIS_IS_L64XX(K)
946
+          monitor_update(K);
947
+        #endif
866 948
         #if AXIS_IS_L64XX(X2)
867 949
           monitor_update(X2);
868 950
         #endif
@@ -896,6 +978,12 @@ void L64XX_Marlin::say_axis(const L64XX_axis_t axis, const uint8_t label/*=true*
896 978
         #if AXIS_IS_L64XX(E5)
897 979
           monitor_update(E5);
898 980
         #endif
981
+        #if AXIS_IS_L64XX(E6)
982
+          monitor_update(E6);
983
+        #endif
984
+        #if AXIS_IS_L64XX(E7)
985
+          monitor_update(E7);
986
+        #endif
899 987
 
900 988
         if (TERN0(L6470_DEBUG, report_L6470_status)) DEBUG_EOL();
901 989
 

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

@@ -35,7 +35,9 @@
35 35
 #define dSPIN_STEP_CLOCK_REV dSPIN_STEP_CLOCK+1
36 36
 #define HAS_L64XX_EXTRUDER (AXIS_IS_L64XX(E0) || AXIS_IS_L64XX(E1) || AXIS_IS_L64XX(E2) || AXIS_IS_L64XX(E3) || AXIS_IS_L64XX(E4) || AXIS_IS_L64XX(E5) || AXIS_IS_L64XX(E6) || AXIS_IS_L64XX(E7))
37 37
 
38
-enum L64XX_axis_t : uint8_t { X, Y, Z, X2, Y2, Z2, Z3, Z4, E0, E1, E2, E3, E4, E5, E6, E7, MAX_L64XX };
38
+#define _EN_ITEM(N) , E##N
39
+enum L64XX_axis_t : uint8_t { LINEAR_AXIS_LIST(X, Y, Z, I, J, K), X2, Y2, Z2, Z3, Z4 REPEAT(E_STEPPERS, _EN_ITEM), MAX_L64XX };
40
+#undef _EN_ITEM
39 41
 
40 42
 class L64XX_Marlin : public L64XXHelper {
41 43
 public:

+ 12
- 13
Marlin/src/libs/vector_3.cpp View File

@@ -52,10 +52,9 @@
52 52
  */
53 53
 
54 54
 vector_3 vector_3::cross(const vector_3 &left, const vector_3 &right) {
55
-  const xyz_float_t &lv = left, &rv = right;
56
-  return vector_3(lv.y * rv.z - lv.z * rv.y,      // YZ cross
57
-                  lv.z * rv.x - lv.x * rv.z,      // ZX cross
58
-                  lv.x * rv.y - lv.y * rv.x);     // XY cross
55
+  return vector_3(left.y * right.z - left.z * right.y,  // YZ cross
56
+                  left.z * right.x - left.x * right.z,  // ZX cross
57
+                  left.x * right.y - left.y * right.x); // XY cross
59 58
 }
60 59
 
61 60
 vector_3 vector_3::get_normal() const {
@@ -64,16 +63,16 @@ vector_3 vector_3::get_normal() const {
64 63
   return normalized;
65 64
 }
66 65
 
67
-void vector_3::normalize() {
68
-  *this *= RSQRT(sq(x) + sq(y) + sq(z));
69
-}
66
+float vector_3::magnitude() const { return SQRT(sq(x) + sq(y) + sq(z)); }
67
+
68
+void vector_3::normalize() { *this *= RSQRT(sq(x) + sq(y) + sq(z)); }
70 69
 
71 70
 // Apply a rotation to the matrix
72 71
 void vector_3::apply_rotation(const matrix_3x3 &matrix) {
73 72
   const float _x = x, _y = y, _z = z;
74
-  *this = { matrix.vectors[0][0] * _x + matrix.vectors[1][0] * _y + matrix.vectors[2][0] * _z,
75
-            matrix.vectors[0][1] * _x + matrix.vectors[1][1] * _y + matrix.vectors[2][1] * _z,
76
-            matrix.vectors[0][2] * _x + matrix.vectors[1][2] * _y + matrix.vectors[2][2] * _z };
73
+  *this = { matrix.vectors[0].x * _x + matrix.vectors[1].x * _y + matrix.vectors[2].x * _z,
74
+            matrix.vectors[0].y * _x + matrix.vectors[1].y * _y + matrix.vectors[2].y * _z,
75
+            matrix.vectors[0].z * _x + matrix.vectors[1].z * _y + matrix.vectors[2].z * _z };
77 76
 }
78 77
 
79 78
 void vector_3::debug(PGM_P const title) {
@@ -105,9 +104,9 @@ matrix_3x3 matrix_3x3::create_from_rows(const vector_3 &row_0, const vector_3 &r
105 104
   //row_1.debug(PSTR("row_1"));
106 105
   //row_2.debug(PSTR("row_2"));
107 106
   matrix_3x3 new_matrix;
108
-  new_matrix.vectors[0] = row_0;
109
-  new_matrix.vectors[1] = row_1;
110
-  new_matrix.vectors[2] = row_2;
107
+  new_matrix.vectors[0].x = row_0.x; new_matrix.vectors[1].y = row_0.y; new_matrix.vectors[2].z = row_0.z;
108
+  new_matrix.vectors[3].x = row_1.x; new_matrix.vectors[4].y = row_1.y; new_matrix.vectors[5].z = row_1.z;
109
+  new_matrix.vectors[6].x = row_2.x; new_matrix.vectors[7].y = row_2.y; new_matrix.vectors[8].z = row_2.z;
111 110
   //new_matrix.debug(PSTR("new_matrix"));
112 111
   return new_matrix;
113 112
 }

+ 22
- 13
Marlin/src/libs/vector_3.h View File

@@ -44,12 +44,16 @@
44 44
 
45 45
 class matrix_3x3;
46 46
 
47
-struct vector_3 : xyz_float_t {
48
-  vector_3(const_float_t _x, const_float_t _y, const_float_t _z) { set(_x, _y, _z); }
49
-  vector_3(const xy_float_t   &in) { set(in.x, in.y); }
50
-  vector_3(const xyz_float_t  &in) { set(in.x, in.y, in.z); }
51
-  vector_3(const xyze_float_t &in) { set(in.x, in.y, in.z); }
52
-  vector_3() { reset(); }
47
+struct vector_3 {
48
+  union {
49
+    struct { float x, y, z; };
50
+    float pos[3];
51
+  };
52
+  vector_3(const_float_t _x, const_float_t _y, const_float_t _z) : x(_x), y(_y), z(_z) {}
53
+  vector_3(const xy_float_t   &in) { x = in.x; TERN_(HAS_Y_AXIS, y = in.y); }
54
+  vector_3(const xyz_float_t  &in) { x = in.x; TERN_(HAS_Y_AXIS, y = in.y); TERN_(HAS_Z_AXIS, z = in.z); }
55
+  vector_3(const xyze_float_t &in) { x = in.x; TERN_(HAS_Y_AXIS, y = in.y); TERN_(HAS_Z_AXIS, z = in.z); }
56
+  vector_3() { x = y = z = 0; }
53 57
 
54 58
   // Factory method
55 59
   static vector_3 cross(const vector_3 &a, const vector_3 &b);
@@ -59,19 +63,26 @@ struct vector_3 : xyz_float_t {
59 63
   void apply_rotation(const matrix_3x3 &matrix);
60 64
 
61 65
   // Accessors
62
-  float get_length() const;
66
+  float magnitude() const;
63 67
   vector_3 get_normal() const;
64 68
 
65 69
   // Operators
66
-  FORCE_INLINE vector_3 operator+(const vector_3 &v) const { vector_3 o = *this; o += v; return o; }
67
-  FORCE_INLINE vector_3 operator-(const vector_3 &v) const { vector_3 o = *this; o -= v; return o; }
68
-  FORCE_INLINE vector_3 operator*(const float    &v) const { vector_3 o = *this; o *= v; return o; }
70
+        float& operator[](const int n)       { return pos[n]; }
71
+  const float& operator[](const int n) const { return pos[n]; }
72
+
73
+  vector_3& operator*=(const float &v)  { x *= v; y *= v; z *= v; return *this; }
74
+  vector_3 operator+(const vector_3 &v) { return vector_3(x + v.x, y + v.y, z + v.z); }
75
+  vector_3 operator-(const vector_3 &v) { return vector_3(x - v.x, y - v.y, z - v.z); }
76
+  vector_3 operator*(const float &v)    { return vector_3(x * v, y * v, z * v); }
77
+
78
+  operator xy_float_t() { return xy_float_t({ x, y }); }
79
+  operator xyz_float_t() { return xyz_float_t({ x, y, z }); }
69 80
 
70 81
   void debug(PGM_P const title);
71 82
 };
72 83
 
73 84
 struct matrix_3x3 {
74
-  abc_float_t vectors[3];
85
+  vector_3 vectors[3];
75 86
 
76 87
   // Factory methods
77 88
   static matrix_3x3 create_from_rows(const vector_3 &row_0, const vector_3 &row_1, const vector_3 &row_2);
@@ -83,6 +94,4 @@ struct matrix_3x3 {
83 94
   void debug(PGM_P const title);
84 95
 
85 96
   void apply_rotation_xyz(float &x, float &y, float &z);
86
-
87
-  FORCE_INLINE void apply_rotation_xyz(xyz_pos_t &pos) { apply_rotation_xyz(pos.x, pos.y, pos.z); }
88 97
 };

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

@@ -245,6 +245,9 @@ void home_delta() {
245 245
     TERN_(X_SENSORLESS, sensorless_t stealth_states_x = start_sensorless_homing_per_axis(X_AXIS));
246 246
     TERN_(Y_SENSORLESS, sensorless_t stealth_states_y = start_sensorless_homing_per_axis(Y_AXIS));
247 247
     TERN_(Z_SENSORLESS, sensorless_t stealth_states_z = start_sensorless_homing_per_axis(Z_AXIS));
248
+    TERN_(I_SENSORLESS, sensorless_t stealth_states_i = start_sensorless_homing_per_axis(I_AXIS));
249
+    TERN_(J_SENSORLESS, sensorless_t stealth_states_j = start_sensorless_homing_per_axis(J_AXIS));
250
+    TERN_(K_SENSORLESS, sensorless_t stealth_states_k = start_sensorless_homing_per_axis(K_AXIS));
248 251
   #endif
249 252
 
250 253
   // Move all carriages together linearly until an endstop is hit.
@@ -257,6 +260,9 @@ void home_delta() {
257 260
     TERN_(X_SENSORLESS, end_sensorless_homing_per_axis(X_AXIS, stealth_states_x));
258 261
     TERN_(Y_SENSORLESS, end_sensorless_homing_per_axis(Y_AXIS, stealth_states_y));
259 262
     TERN_(Z_SENSORLESS, end_sensorless_homing_per_axis(Z_AXIS, stealth_states_z));
263
+    TERN_(I_SENSORLESS, end_sensorless_homing_per_axis(I_AXIS, stealth_states_i));
264
+    TERN_(J_SENSORLESS, end_sensorless_homing_per_axis(J_AXIS, stealth_states_j));
265
+    TERN_(K_SENSORLESS, end_sensorless_homing_per_axis(K_AXIS, stealth_states_k));
260 266
   #endif
261 267
 
262 268
   endstops.validate_homing_move();

+ 341
- 67
Marlin/src/module/endstops.cpp View File

@@ -259,6 +259,66 @@ void Endstops::init() {
259 259
     #endif
260 260
   #endif
261 261
 
262
+  #if HAS_I_MIN
263
+    #if ENABLED(ENDSTOPPULLUP_IMIN)
264
+      SET_INPUT_PULLUP(I_MIN_PIN);
265
+    #elif ENABLED(ENDSTOPPULLDOWN_IMIN)
266
+      SET_INPUT_PULLDOWN(I_MIN_PIN);
267
+    #else
268
+      SET_INPUT(I_MIN_PIN);
269
+    #endif
270
+  #endif
271
+
272
+  #if HAS_I_MAX
273
+    #if ENABLED(ENDSTOPPULLUP_IMAX)
274
+      SET_INPUT_PULLUP(I_MAX_PIN);
275
+    #elif ENABLED(ENDSTOPPULLDOWN_IMAX)
276
+      SET_INPUT_PULLDOWN(I_MAX_PIN);
277
+    #else
278
+      SET_INPUT(I_MAX_PIN);
279
+    #endif
280
+  #endif
281
+
282
+  #if HAS_J_MIN
283
+    #if ENABLED(ENDSTOPPULLUP_JMIN)
284
+      SET_INPUT_PULLUP(J_MIN_PIN);
285
+    #elif ENABLED(ENDSTOPPULLDOWN_IMIN)
286
+      SET_INPUT_PULLDOWN(J_MIN_PIN);
287
+    #else
288
+      SET_INPUT(J_MIN_PIN);
289
+    #endif
290
+  #endif
291
+
292
+  #if HAS_J_MAX
293
+    #if ENABLED(ENDSTOPPULLUP_JMAX)
294
+      SET_INPUT_PULLUP(J_MAX_PIN);
295
+    #elif ENABLED(ENDSTOPPULLDOWN_JMAX)
296
+      SET_INPUT_PULLDOWN(J_MAX_PIN);
297
+    #else
298
+      SET_INPUT(J_MAX_PIN);
299
+    #endif
300
+  #endif
301
+
302
+  #if HAS_K_MIN
303
+    #if ENABLED(ENDSTOPPULLUP_KMIN)
304
+      SET_INPUT_PULLUP(K_MIN_PIN);
305
+    #elif ENABLED(ENDSTOPPULLDOWN_KMIN)
306
+      SET_INPUT_PULLDOWN(K_MIN_PIN);
307
+    #else
308
+      SET_INPUT(K_MIN_PIN);
309
+    #endif
310
+  #endif
311
+
312
+  #if HAS_K_MAX
313
+    #if ENABLED(ENDSTOPPULLUP_KMAX)
314
+      SET_INPUT_PULLUP(K_MAX_PIN);
315
+    #elif ENABLED(ENDSTOPPULLDOWN_KMIN)
316
+      SET_INPUT_PULLDOWN(K_MAX_PIN);
317
+    #else
318
+      SET_INPUT(K_MAX_PIN);
319
+    #endif
320
+  #endif
321
+
262 322
   #if PIN_EXISTS(CALIBRATION)
263 323
     #if ENABLED(CALIBRATION_PIN_PULLUP)
264 324
       SET_INPUT_PULLUP(CALIBRATION_PIN);
@@ -361,7 +421,7 @@ void Endstops::event_handler() {
361 421
   prev_hit_state = hit_state;
362 422
   if (hit_state) {
363 423
     #if HAS_STATUS_MESSAGE
364
-      char LINEAR_AXIS_LIST(chrX = ' ', chrY = ' ', chrZ = ' '),
424
+      char LINEAR_AXIS_LIST(chrX = ' ', chrY = ' ', chrZ = ' ', chrI = ' ', chrJ = ' ', chrK = ' '),
365 425
            chrP = ' ';
366 426
       #define _SET_STOP_CHAR(A,C) (chr## A = C)
367 427
     #else
@@ -378,12 +438,20 @@ void Endstops::event_handler() {
378 438
     #define ENDSTOP_HIT_TEST_X() _ENDSTOP_HIT_TEST(X,'X')
379 439
     #define ENDSTOP_HIT_TEST_Y() _ENDSTOP_HIT_TEST(Y,'Y')
380 440
     #define ENDSTOP_HIT_TEST_Z() _ENDSTOP_HIT_TEST(Z,'Z')
441
+    #define ENDSTOP_HIT_TEST_I() _ENDSTOP_HIT_TEST(I,'I')
442
+    #define ENDSTOP_HIT_TEST_J() _ENDSTOP_HIT_TEST(J,'J')
443
+    #define ENDSTOP_HIT_TEST_K() _ENDSTOP_HIT_TEST(K,'K')
381 444
 
382 445
     SERIAL_ECHO_START();
383 446
     SERIAL_ECHOPGM(STR_ENDSTOPS_HIT);
384
-    ENDSTOP_HIT_TEST_X();
385
-    ENDSTOP_HIT_TEST_Y();
386
-    ENDSTOP_HIT_TEST_Z();
447
+    LINEAR_AXIS_CODE(
448
+       ENDSTOP_HIT_TEST_X(),
449
+       ENDSTOP_HIT_TEST_Y(),
450
+       ENDSTOP_HIT_TEST_Z(),
451
+      _ENDSTOP_HIT_TEST(I,'I'),
452
+      _ENDSTOP_HIT_TEST(J,'J'),
453
+      _ENDSTOP_HIT_TEST(K,'K')
454
+    );
387 455
 
388 456
     #if HAS_CUSTOM_PROBE_PIN
389 457
       #define P_AXIS Z_AXIS
@@ -395,7 +463,7 @@ void Endstops::event_handler() {
395 463
       ui.status_printf_P(0,
396 464
         PSTR(S_FMT GANG_N_1(LINEAR_AXES, " %c") " %c"),
397 465
         GET_TEXT(MSG_LCD_ENDSTOPS),
398
-        LINEAR_AXIS_LIST(chrX, chrY, chrZ), chrP
466
+        LINEAR_AXIS_LIST(chrX, chrY, chrZ, chrI, chrJ, chrK), chrP
399 467
       )
400 468
     );
401 469
 
@@ -477,6 +545,24 @@ void _O2 Endstops::report_states() {
477 545
   #if HAS_Z4_MAX
478 546
     ES_REPORT(Z4_MAX);
479 547
   #endif
548
+  #if HAS_I_MIN
549
+    ES_REPORT(I_MIN);
550
+  #endif
551
+  #if HAS_I_MAX
552
+    ES_REPORT(I_MAX);
553
+  #endif
554
+  #if HAS_J_MIN
555
+    ES_REPORT(J_MIN);
556
+  #endif
557
+  #if HAS_J_MAX
558
+    ES_REPORT(J_MAX);
559
+  #endif
560
+    #if HAS_K_MIN
561
+    ES_REPORT(K_MIN);
562
+  #endif
563
+  #if HAS_K_MAX
564
+    ES_REPORT(K_MAX);
565
+  #endif
480 566
   #if BOTH(MARLIN_DEV_MODE, PROBE_ACTIVATION_SWITCH)
481 567
     print_es_state(probe_switch_activated(), PSTR(STR_PROBE_EN));
482 568
   #endif
@@ -549,6 +635,10 @@ void Endstops::update() {
549 635
     #define Z_AXIS_HEAD Z_AXIS
550 636
   #endif
551 637
 
638
+  #define I_AXIS_HEAD I_AXIS
639
+  #define J_AXIS_HEAD J_AXIS
640
+  #define K_AXIS_HEAD K_AXIS
641
+
552 642
   /**
553 643
    * Check and update endstops
554 644
    */
@@ -656,6 +746,84 @@ void Endstops::update() {
656 746
     #endif
657 747
   #endif
658 748
 
749
+  #if HAS_I_MIN
750
+    #if ENABLED(I_DUAL_ENDSTOPS)
751
+      UPDATE_ENDSTOP_BIT(I, MIN);
752
+      #if HAS_I2_MIN
753
+        UPDATE_ENDSTOP_BIT(I2, MAX);
754
+      #else
755
+        COPY_LIVE_STATE(I_MIN, I2_MIN);
756
+      #endif
757
+    #else
758
+      UPDATE_ENDSTOP_BIT(I, MIN);
759
+    #endif
760
+  #endif
761
+
762
+  #if HAS_I_MAX
763
+    #if ENABLED(I_DUAL_ENDSTOPS)
764
+      UPDATE_ENDSTOP_BIT(I, MAX);
765
+      #if HAS_I2_MAX
766
+        UPDATE_ENDSTOP_BIT(I2, MAX);
767
+      #else
768
+        COPY_LIVE_STATE(I_MAX, I2_MAX);
769
+      #endif
770
+    #else
771
+      UPDATE_ENDSTOP_BIT(I, MAX);
772
+    #endif
773
+  #endif
774
+
775
+  #if HAS_J_MIN
776
+    #if ENABLED(J_DUAL_ENDSTOPS)
777
+      UPDATE_ENDSTOP_BIT(J, MIN);
778
+      #if HAS_J2_MIN
779
+        UPDATE_ENDSTOP_BIT(J2, MIN);
780
+      #else
781
+        COPY_LIVE_STATE(J_MIN, J2_MIN);
782
+      #endif
783
+    #else
784
+      UPDATE_ENDSTOP_BIT(J, MIN);
785
+    #endif
786
+  #endif
787
+
788
+  #if HAS_J_MAX
789
+    #if ENABLED(J_DUAL_ENDSTOPS)
790
+      UPDATE_ENDSTOP_BIT(J, MAX);
791
+      #if HAS_J2_MAX
792
+        UPDATE_ENDSTOP_BIT(J2, MAX);
793
+      #else
794
+        COPY_LIVE_STATE(J_MAX, J2_MAX);
795
+      #endif
796
+    #else
797
+      UPDATE_ENDSTOP_BIT(J, MAX);
798
+    #endif
799
+  #endif
800
+
801
+  #if HAS_K_MIN
802
+    #if ENABLED(K_DUAL_ENDSTOPS)
803
+      UPDATE_ENDSTOP_BIT(K, MIN);
804
+      #if HAS_K2_MIN
805
+        UPDATE_ENDSTOP_BIT(K2, MIN);
806
+      #else
807
+        COPY_LIVE_STATE(K_MIN, K2_MIN);
808
+      #endif
809
+    #else
810
+      UPDATE_ENDSTOP_BIT(K, MIN);
811
+    #endif
812
+  #endif
813
+
814
+  #if HAS_K_MAX
815
+    #if ENABLED(K_DUAL_ENDSTOPS)
816
+      UPDATE_ENDSTOP_BIT(K, MAX);
817
+      #if HAS_K2_MAX
818
+        UPDATE_ENDSTOP_BIT(K2, MAX);
819
+      #else
820
+        COPY_LIVE_STATE(K_MAX, K2_MAX);
821
+      #endif
822
+    #else
823
+      UPDATE_ENDSTOP_BIT(K, MAX);
824
+    #endif
825
+  #endif
826
+
659 827
   #if ENDSTOP_NOISE_THRESHOLD
660 828
 
661 829
     /**
@@ -804,79 +972,128 @@ void Endstops::update() {
804 972
     }
805 973
   }
806 974
 
807
-  if (stepper.axis_is_moving(Y_AXIS)) {
808
-    if (stepper.motor_direction(Y_AXIS_HEAD)) { // -direction
809
-      #if HAS_Y_MIN || (Y_SPI_SENSORLESS && Y_HOME_TO_MIN)
810
-        PROCESS_ENDSTOP_Y(MIN);
811
-        #if   CORE_DIAG(XY, X, MIN)
812
-          PROCESS_CORE_ENDSTOP(X,MIN,Y,MIN);
813
-        #elif CORE_DIAG(XY, X, MAX)
814
-          PROCESS_CORE_ENDSTOP(X,MAX,Y,MIN);
815
-        #elif CORE_DIAG(YZ, Z, MIN)
816
-          PROCESS_CORE_ENDSTOP(Z,MIN,Y,MIN);
817
-        #elif CORE_DIAG(YZ, Z, MAX)
818
-          PROCESS_CORE_ENDSTOP(Z,MAX,Y,MIN);
975
+  #if HAS_Y_AXIS
976
+    if (stepper.axis_is_moving(Y_AXIS)) {
977
+      if (stepper.motor_direction(Y_AXIS_HEAD)) { // -direction
978
+        #if HAS_Y_MIN || (Y_SPI_SENSORLESS && Y_HOME_TO_MIN)
979
+          PROCESS_ENDSTOP_Y(MIN);
980
+          #if   CORE_DIAG(XY, X, MIN)
981
+            PROCESS_CORE_ENDSTOP(X,MIN,Y,MIN);
982
+          #elif CORE_DIAG(XY, X, MAX)
983
+            PROCESS_CORE_ENDSTOP(X,MAX,Y,MIN);
984
+          #elif CORE_DIAG(YZ, Z, MIN)
985
+            PROCESS_CORE_ENDSTOP(Z,MIN,Y,MIN);
986
+          #elif CORE_DIAG(YZ, Z, MAX)
987
+            PROCESS_CORE_ENDSTOP(Z,MAX,Y,MIN);
988
+          #endif
819 989
         #endif
820
-      #endif
990
+      }
991
+      else { // +direction
992
+        #if HAS_Y_MAX || (Y_SPI_SENSORLESS && Y_HOME_TO_MAX)
993
+          PROCESS_ENDSTOP_Y(MAX);
994
+          #if   CORE_DIAG(XY, X, MIN)
995
+            PROCESS_CORE_ENDSTOP(X,MIN,Y,MAX);
996
+          #elif CORE_DIAG(XY, X, MAX)
997
+            PROCESS_CORE_ENDSTOP(X,MAX,Y,MAX);
998
+          #elif CORE_DIAG(YZ, Z, MIN)
999
+            PROCESS_CORE_ENDSTOP(Z,MIN,Y,MAX);
1000
+          #elif CORE_DIAG(YZ, Z, MAX)
1001
+            PROCESS_CORE_ENDSTOP(Z,MAX,Y,MAX);
1002
+          #endif
1003
+        #endif
1004
+      }
821 1005
     }
822
-    else { // +direction
823
-      #if HAS_Y_MAX || (Y_SPI_SENSORLESS && Y_HOME_TO_MAX)
824
-        PROCESS_ENDSTOP_Y(MAX);
825
-        #if   CORE_DIAG(XY, X, MIN)
826
-          PROCESS_CORE_ENDSTOP(X,MIN,Y,MAX);
827
-        #elif CORE_DIAG(XY, X, MAX)
828
-          PROCESS_CORE_ENDSTOP(X,MAX,Y,MAX);
829
-        #elif CORE_DIAG(YZ, Z, MIN)
830
-          PROCESS_CORE_ENDSTOP(Z,MIN,Y,MAX);
831
-        #elif CORE_DIAG(YZ, Z, MAX)
832
-          PROCESS_CORE_ENDSTOP(Z,MAX,Y,MAX);
1006
+  #endif
1007
+
1008
+  #if HAS_Z_AXIS
1009
+    if (stepper.axis_is_moving(Z_AXIS)) {
1010
+      if (stepper.motor_direction(Z_AXIS_HEAD)) { // Z -direction. Gantry down, bed up.
1011
+
1012
+        #if HAS_Z_MIN || (Z_SPI_SENSORLESS && Z_HOME_TO_MIN)
1013
+          if ( TERN1(Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN, z_probe_enabled)
1014
+            && TERN1(HAS_CUSTOM_PROBE_PIN, !z_probe_enabled)
1015
+          ) PROCESS_ENDSTOP_Z(MIN);
1016
+          #if   CORE_DIAG(XZ, X, MIN)
1017
+            PROCESS_CORE_ENDSTOP(X,MIN,Z,MIN);
1018
+          #elif CORE_DIAG(XZ, X, MAX)
1019
+            PROCESS_CORE_ENDSTOP(X,MAX,Z,MIN);
1020
+          #elif CORE_DIAG(YZ, Y, MIN)
1021
+            PROCESS_CORE_ENDSTOP(Y,MIN,Z,MIN);
1022
+          #elif CORE_DIAG(YZ, Y, MAX)
1023
+            PROCESS_CORE_ENDSTOP(Y,MAX,Z,MIN);
1024
+          #endif
833 1025
         #endif
834
-      #endif
1026
+
1027
+        // When closing the gap check the enabled probe
1028
+        #if HAS_CUSTOM_PROBE_PIN
1029
+          if (z_probe_enabled) PROCESS_ENDSTOP(Z, MIN_PROBE);
1030
+        #endif
1031
+      }
1032
+      else { // Z +direction. Gantry up, bed down.
1033
+        #if HAS_Z_MAX || (Z_SPI_SENSORLESS && Z_HOME_TO_MAX)
1034
+          #if ENABLED(Z_MULTI_ENDSTOPS)
1035
+            PROCESS_ENDSTOP_Z(MAX);
1036
+          #elif !HAS_CUSTOM_PROBE_PIN || Z_MAX_PIN != Z_MIN_PROBE_PIN  // No probe or probe is Z_MIN || Probe is not Z_MAX
1037
+            PROCESS_ENDSTOP(Z, MAX);
1038
+          #endif
1039
+          #if   CORE_DIAG(XZ, X, MIN)
1040
+            PROCESS_CORE_ENDSTOP(X,MIN,Z,MAX);
1041
+          #elif CORE_DIAG(XZ, X, MAX)
1042
+            PROCESS_CORE_ENDSTOP(X,MAX,Z,MAX);
1043
+          #elif CORE_DIAG(YZ, Y, MIN)
1044
+            PROCESS_CORE_ENDSTOP(Y,MIN,Z,MAX);
1045
+          #elif CORE_DIAG(YZ, Y, MAX)
1046
+            PROCESS_CORE_ENDSTOP(Y,MAX,Z,MAX);
1047
+          #endif
1048
+        #endif
1049
+      }
835 1050
     }
836
-  }
1051
+  #endif
837 1052
 
838
-  if (stepper.axis_is_moving(Z_AXIS)) {
839
-    if (stepper.motor_direction(Z_AXIS_HEAD)) { // Z -direction. Gantry down, bed up.
840
-
841
-      #if HAS_Z_MIN || (Z_SPI_SENSORLESS && Z_HOME_TO_MIN)
842
-        if ( TERN1(Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN, z_probe_enabled)
843
-          && TERN1(HAS_CUSTOM_PROBE_PIN, !z_probe_enabled)
844
-        ) PROCESS_ENDSTOP_Z(MIN);
845
-        #if   CORE_DIAG(XZ, X, MIN)
846
-          PROCESS_CORE_ENDSTOP(X,MIN,Z,MIN);
847
-        #elif CORE_DIAG(XZ, X, MAX)
848
-          PROCESS_CORE_ENDSTOP(X,MAX,Z,MIN);
849
-        #elif CORE_DIAG(YZ, Y, MIN)
850
-          PROCESS_CORE_ENDSTOP(Y,MIN,Z,MIN);
851
-        #elif CORE_DIAG(YZ, Y, MAX)
852
-          PROCESS_CORE_ENDSTOP(Y,MAX,Z,MIN);
1053
+  #if LINEAR_AXES >= 4
1054
+    if (stepper.axis_is_moving(I_AXIS)) {
1055
+      if (stepper.motor_direction(I_AXIS_HEAD)) { // -direction
1056
+        #if HAS_I_MIN || (I_SPI_SENSORLESS && I_HOME_TO_MIN)
1057
+          PROCESS_ENDSTOP(I, MIN);
853 1058
         #endif
854
-      #endif
1059
+      }
1060
+      else { // +direction
1061
+        #if HAS_I_MAX || (I_SPI_SENSORLESS && I_HOME_TO_MAX)
1062
+          PROCESS_ENDSTOP(I, MAX);
1063
+        #endif
1064
+      }
1065
+    }
1066
+  #endif
855 1067
 
856
-      // When closing the gap check the enabled probe
857
-      #if HAS_CUSTOM_PROBE_PIN
858
-        if (z_probe_enabled) PROCESS_ENDSTOP(Z, MIN_PROBE);
859
-      #endif
1068
+  #if LINEAR_AXES >= 5
1069
+    if (stepper.axis_is_moving(J_AXIS)) {
1070
+      if (stepper.motor_direction(J_AXIS_HEAD)) { // -direction
1071
+        #if HAS_J_MIN || (J_SPI_SENSORLESS && J_HOME_TO_MIN)
1072
+          PROCESS_ENDSTOP(J, MIN);
1073
+        #endif
1074
+      }
1075
+      else { // +direction
1076
+        #if HAS_J_MAX || (J_SPI_SENSORLESS && J_HOME_TO_MAX)
1077
+          PROCESS_ENDSTOP(J, MAX);
1078
+        #endif
1079
+      }
860 1080
     }
861
-    else { // Z +direction. Gantry up, bed down.
862
-      #if HAS_Z_MAX || (Z_SPI_SENSORLESS && Z_HOME_TO_MAX)
863
-        #if ENABLED(Z_MULTI_ENDSTOPS)
864
-          PROCESS_ENDSTOP_Z(MAX);
865
-        #elif !HAS_CUSTOM_PROBE_PIN || Z_MAX_PIN != Z_MIN_PROBE_PIN  // No probe or probe is Z_MIN || Probe is not Z_MAX
866
-          PROCESS_ENDSTOP(Z, MAX);
1081
+  #endif
1082
+
1083
+  #if LINEAR_AXES >= 6
1084
+    if (stepper.axis_is_moving(K_AXIS)) {
1085
+      if (stepper.motor_direction(K_AXIS_HEAD)) { // -direction
1086
+        #if HAS_K_MIN || (K_SPI_SENSORLESS && K_HOME_TO_MIN)
1087
+          PROCESS_ENDSTOP(K, MIN);
867 1088
         #endif
868
-        #if   CORE_DIAG(XZ, X, MIN)
869
-          PROCESS_CORE_ENDSTOP(X,MIN,Z,MAX);
870
-        #elif CORE_DIAG(XZ, X, MAX)
871
-          PROCESS_CORE_ENDSTOP(X,MAX,Z,MAX);
872
-        #elif CORE_DIAG(YZ, Y, MIN)
873
-          PROCESS_CORE_ENDSTOP(Y,MIN,Z,MAX);
874
-        #elif CORE_DIAG(YZ, Y, MAX)
875
-          PROCESS_CORE_ENDSTOP(Y,MAX,Z,MAX);
1089
+      }
1090
+      else { // +direction
1091
+        #if HAS_K_MAX || (K_SPI_SENSORLESS && K_HOME_TO_MAX)
1092
+          PROCESS_ENDSTOP(K, MAX);
876 1093
         #endif
877
-      #endif
1094
+      }
878 1095
     }
879
-  }
1096
+  #endif
880 1097
 } // Endstops::update()
881 1098
 
882 1099
 #if ENABLED(SPI_ENDSTOPS)
@@ -919,6 +1136,24 @@ void Endstops::update() {
919 1136
         hit = true;
920 1137
       }
921 1138
     #endif
1139
+    #if I_SPI_SENSORLESS
1140
+      if (tmc_spi_homing.i && stepperI.test_stall_status()) {
1141
+        SBI(live_state, I_ENDSTOP);
1142
+        hit = true;
1143
+      }
1144
+    #endif
1145
+    #if J_SPI_SENSORLESS
1146
+      if (tmc_spi_homing.j && stepperJ.test_stall_status()) {
1147
+        SBI(live_state, J_ENDSTOP);
1148
+        hit = true;
1149
+      }
1150
+    #endif
1151
+    #if K_SPI_SENSORLESS
1152
+      if (tmc_spi_homing.k && stepperK.test_stall_status()) {
1153
+        SBI(live_state, K_ENDSTOP);
1154
+        hit = true;
1155
+      }
1156
+    #endif
922 1157
 
923 1158
     if (TERN0(ENDSTOP_INTERRUPTS_FEATURE, hit)) update();
924 1159
 
@@ -929,6 +1164,9 @@ void Endstops::update() {
929 1164
     TERN_(X_SPI_SENSORLESS, CBI(live_state, X_ENDSTOP));
930 1165
     TERN_(Y_SPI_SENSORLESS, CBI(live_state, Y_ENDSTOP));
931 1166
     TERN_(Z_SPI_SENSORLESS, CBI(live_state, Z_ENDSTOP));
1167
+    TERN_(I_SPI_SENSORLESS, CBI(live_state, I_ENDSTOP));
1168
+    TERN_(J_SPI_SENSORLESS, CBI(live_state, J_ENDSTOP));
1169
+    TERN_(K_SPI_SENSORLESS, CBI(live_state, K_ENDSTOP));
932 1170
   }
933 1171
 
934 1172
 #endif // SPI_ENDSTOPS
@@ -1005,6 +1243,24 @@ void Endstops::update() {
1005 1243
     #if HAS_Z4_MAX
1006 1244
       ES_GET_STATE(Z4_MAX);
1007 1245
     #endif
1246
+    #if HAS_I_MAX
1247
+      ES_GET_STATE(I_MAX);
1248
+    #endif
1249
+    #if HAS_I_MIN
1250
+      ES_GET_STATE(I_MIN);
1251
+    #endif
1252
+    #if HAS_J_MAX
1253
+      ES_GET_STATE(J_MAX);
1254
+    #endif
1255
+    #if HAS_J_MIN
1256
+      ES_GET_STATE(J_MIN);
1257
+    #endif
1258
+    #if HAS_K_MAX
1259
+      ES_GET_STATE(K_MAX);
1260
+    #endif
1261
+    #if HAS_K_MIN
1262
+      ES_GET_STATE(K_MIN);
1263
+    #endif
1008 1264
 
1009 1265
     uint16_t endstop_change = live_state_local ^ old_live_state_local;
1010 1266
     #define ES_REPORT_CHANGE(S) if (TEST(endstop_change, S)) SERIAL_ECHOPAIR("  " STRINGIFY(S) ":", TEST(live_state_local, S))
@@ -1061,6 +1317,24 @@ void Endstops::update() {
1061 1317
       #if HAS_Z4_MAX
1062 1318
         ES_REPORT_CHANGE(Z4_MAX);
1063 1319
       #endif
1320
+      #if HAS_I_MIN
1321
+        ES_REPORT_CHANGE(I_MIN);
1322
+      #endif
1323
+      #if HAS_I_MAX
1324
+        ES_REPORT_CHANGE(I_MAX);
1325
+      #endif
1326
+      #if HAS_J_MIN
1327
+        ES_REPORT_CHANGE(J_MIN);
1328
+      #endif
1329
+      #if HAS_J_MAX
1330
+        ES_REPORT_CHANGE(J_MAX);
1331
+      #endif
1332
+      #if HAS_K_MIN
1333
+        ES_REPORT_CHANGE(K_MIN);
1334
+      #endif
1335
+      #if HAS_K_MAX
1336
+        ES_REPORT_CHANGE(K_MAX);
1337
+      #endif
1064 1338
       SERIAL_ECHOLNPGM("\n");
1065 1339
       analogWrite(pin_t(LED_PIN), local_LED_status);
1066 1340
       local_LED_status ^= 255;

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

@@ -39,6 +39,12 @@ enum EndstopEnum : char {
39 39
   _ES_ITEM(HAS_Y_MAX, Y_MAX)
40 40
   _ES_ITEM(HAS_Z_MIN, Z_MIN)
41 41
   _ES_ITEM(HAS_Z_MAX, Z_MAX)
42
+  _ES_ITEM(HAS_I_MIN, I_MIN)
43
+  _ES_ITEM(HAS_I_MAX, I_MAX)
44
+  _ES_ITEM(HAS_J_MIN, J_MIN)
45
+  _ES_ITEM(HAS_J_MAX, J_MAX)
46
+  _ES_ITEM(HAS_K_MIN, K_MIN)
47
+  _ES_ITEM(HAS_K_MAX, K_MAX)
42 48
 
43 49
   // Extra Endstops for XYZ
44 50
   #if ENABLED(X_DUAL_ENDSTOPS)

+ 266
- 155
Marlin/src/module/motion.cpp View File

@@ -89,7 +89,7 @@ bool relative_mode; // = false;
89 89
   #define Z_INIT_POS Z_HOME_POS
90 90
 #endif
91 91
 
92
-xyze_pos_t current_position = LOGICAL_AXIS_ARRAY(0, X_HOME_POS, Y_HOME_POS, Z_INIT_POS);
92
+xyze_pos_t current_position = LOGICAL_AXIS_ARRAY(0, X_HOME_POS, Y_HOME_POS, Z_INIT_POS, I_HOME_POS, J_HOME_POS, K_HOME_POS);
93 93
 
94 94
 /**
95 95
  * Cartesian Destination
@@ -143,7 +143,7 @@ xyz_pos_t cartes;
143 143
 
144 144
 #if IS_KINEMATIC
145 145
 
146
-  abc_pos_t delta;
146
+  abce_pos_t delta;
147 147
 
148 148
   #if HAS_SCARA_OFFSET
149 149
     abc_pos_t scara_home_offset;
@@ -196,7 +196,14 @@ inline void report_more_positions() {
196 196
 inline void report_logical_position(const xyze_pos_t &rpos) {
197 197
   const xyze_pos_t lpos = rpos.asLogical();
198 198
   SERIAL_ECHOPAIR_P(
199
-    LIST_N(DOUBLE(LINEAR_AXES), X_LBL, lpos.x, SP_Y_LBL, lpos.y, SP_Z_LBL, lpos.z)
199
+    LIST_N(DOUBLE(LINEAR_AXES),
200
+         X_LBL, lpos.x,
201
+      SP_Y_LBL, lpos.y,
202
+      SP_Z_LBL, lpos.z,
203
+      SP_I_LBL, lpos.i,
204
+      SP_J_LBL, lpos.j,
205
+      SP_K_LBL, lpos.k
206
+    )
200 207
     #if HAS_EXTRUDERS
201 208
       , SP_E_LBL, lpos.e
202 209
     #endif
@@ -209,7 +216,10 @@ void report_real_position() {
209 216
   get_cartesian_from_steppers();
210 217
   xyze_pos_t npos = LOGICAL_AXIS_ARRAY(
211 218
     planner.get_axis_position_mm(E_AXIS),
212
-    cartes.x, cartes.y, cartes.z
219
+    cartes.x, cartes.y, cartes.z,
220
+    planner.get_axis_position_mm(I_AXIS),
221
+    planner.get_axis_position_mm(J_AXIS),
222
+    planner.get_axis_position_mm(K_AXIS)
213 223
   );
214 224
 
215 225
   TERN_(HAS_POSITION_MODIFIERS, planner.unapply_modifiers(npos, true));
@@ -334,20 +344,21 @@ void sync_plan_position() {
334 344
 void get_cartesian_from_steppers() {
335 345
   #if ENABLED(DELTA)
336 346
     forward_kinematics(planner.get_axis_positions_mm());
337
-  #else
338
-    #if IS_SCARA
339
-      forward_kinematics(
340
-          planner.get_axis_position_degrees(A_AXIS)
341
-        , planner.get_axis_position_degrees(B_AXIS)
342
-        #if ENABLED(AXEL_TPARA)
343
-          , planner.get_axis_position_degrees(C_AXIS)
344
-        #endif
345
-      );
346
-    #else
347
-      cartes.x = planner.get_axis_position_mm(X_AXIS);
348
-      cartes.y = planner.get_axis_position_mm(Y_AXIS);
349
-    #endif
347
+  #elif IS_SCARA
348
+    forward_kinematics(
349
+      planner.get_axis_position_degrees(A_AXIS), planner.get_axis_position_degrees(B_AXIS)
350
+      OPTARG(AXEL_TPARA, planner.get_axis_position_degrees(C_AXIS))
351
+    );
350 352
     cartes.z = planner.get_axis_position_mm(Z_AXIS);
353
+  #else
354
+    LINEAR_AXIS_CODE(
355
+      cartes.x = planner.get_axis_position_mm(X_AXIS),
356
+      cartes.y = planner.get_axis_position_mm(Y_AXIS),
357
+      cartes.z = planner.get_axis_position_mm(Z_AXIS),
358
+      cartes.i = planner.get_axis_position_mm(I_AXIS),
359
+      cartes.j = planner.get_axis_position_mm(J_AXIS),
360
+      cartes.k = planner.get_axis_position_mm(K_AXIS)
361
+    );
351 362
   #endif
352 363
 }
353 364
 
@@ -366,13 +377,9 @@ void set_current_from_steppers_for_axis(const AxisEnum axis) {
366 377
   get_cartesian_from_steppers();
367 378
   xyze_pos_t pos = cartes;
368 379
 
369
-  #if HAS_EXTRUDERS
370
-    pos.e = planner.get_axis_position_mm(E_AXIS);
371
-  #endif
380
+  TERN_(HAS_EXTRUDERS, pos.e = planner.get_axis_position_mm(E_AXIS));
372 381
 
373
-  #if HAS_POSITION_MODIFIERS
374
-    planner.unapply_modifiers(pos, true);
375
-  #endif
382
+  TERN_(HAS_POSITION_MODIFIERS, planner.unapply_modifiers(pos, true));
376 383
 
377 384
   if (axis == ALL_AXES_ENUM)
378 385
     current_position = pos;
@@ -385,7 +392,7 @@ void set_current_from_steppers_for_axis(const AxisEnum axis) {
385 392
  * (or from wherever it has been told it is located).
386 393
  */
387 394
 void line_to_current_position(const_feedRate_t fr_mm_s/*=feedrate_mm_s*/) {
388
-  planner.buffer_line(current_position, fr_mm_s, active_extruder);
395
+  planner.buffer_line(current_position, fr_mm_s);
389 396
 }
390 397
 
391 398
 #if HAS_EXTRUDERS
@@ -411,7 +418,7 @@ void line_to_current_position(const_feedRate_t fr_mm_s/*=feedrate_mm_s*/) {
411 418
     #else
412 419
       if (current_position == destination) return;
413 420
 
414
-      planner.buffer_line(destination, scaled_fr_mm_s, active_extruder);
421
+      planner.buffer_line(destination, scaled_fr_mm_s);
415 422
     #endif
416 423
 
417 424
     current_position = destination;
@@ -449,25 +456,26 @@ void _internal_move_to_destination(const_feedRate_t fr_mm_s/*=0.0f*/
449 456
 }
450 457
 
451 458
 /**
452
- * Plan a move to (X, Y, Z) with separation of the XY and Z components.
459
+ * Plan a move to (X, Y, Z, [I, [J, [K]]]) and set the current_position
460
+ * Plan a move to (X, Y, Z) with separation of Z from other components.
453 461
  *
454
- * - If Z is moving up, the Z move is done before XY.
455
- * - If Z is moving down, the Z move is done after XY.
462
+ * - If Z is moving up, the Z move is done before XY, etc.
463
+ * - If Z is moving down, the Z move is done after XY, etc.
456 464
  * - Delta may lower Z first to get into the free motion zone.
457 465
  * - Before returning, wait for the planner buffer to empty.
458 466
  */
459
-void do_blocking_move_to(
460
-  LINEAR_AXIS_LIST(const float rx, const float ry, const float rz),
461
-  const_feedRate_t fr_mm_s/*=0.0f*/
462
-) {
467
+void do_blocking_move_to(LINEAR_AXIS_ARGS(const float), const_feedRate_t fr_mm_s/*=0.0f*/) {
463 468
   DEBUG_SECTION(log_move, "do_blocking_move_to", DEBUGGING(LEVELING));
464
-  if (DEBUGGING(LEVELING)) DEBUG_XYZ("> ", LINEAR_AXIS_LIST(rx, ry, rz));
469
+  if (DEBUGGING(LEVELING)) DEBUG_XYZ("> ", LINEAR_AXIS_ARGS());
470
+
471
+  const feedRate_t xy_feedrate = fr_mm_s ?: feedRate_t(XY_PROBE_FEEDRATE_MM_S);
465 472
 
466
-  const feedRate_t z_feedrate = fr_mm_s ?: homing_feedrate(Z_AXIS),
467
-                  xy_feedrate = fr_mm_s ?: feedRate_t(XY_PROBE_FEEDRATE_MM_S);
473
+  #if HAS_Z_AXIS
474
+    const feedRate_t z_feedrate = fr_mm_s ?: homing_feedrate(Z_AXIS);
475
+  #endif
468 476
 
469 477
   #if EITHER(DELTA, IS_SCARA)
470
-    if (!position_is_reachable(rx, ry)) return;
478
+    if (!position_is_reachable(x, y)) return;
471 479
     destination = current_position;          // sync destination at the start
472 480
   #endif
473 481
 
@@ -479,8 +487,8 @@ void do_blocking_move_to(
479 487
 
480 488
     // when in the danger zone
481 489
     if (current_position.z > delta_clip_start_height) {
482
-      if (rz > delta_clip_start_height) {                     // staying in the danger zone
483
-        destination.set(rx, ry, rz);                          // move directly (uninterpolated)
490
+      if (z > delta_clip_start_height) {                     // staying in the danger zone
491
+        destination.set(x, y, z);                          // move directly (uninterpolated)
484 492
         prepare_internal_fast_move_to_destination();          // set current_position from destination
485 493
         if (DEBUGGING(LEVELING)) DEBUG_POS("danger zone move", current_position);
486 494
         return;
@@ -490,18 +498,18 @@ void do_blocking_move_to(
490 498
       if (DEBUGGING(LEVELING)) DEBUG_POS("zone border move", current_position);
491 499
     }
492 500
 
493
-    if (rz > current_position.z) {                            // raising?
494
-      destination.z = rz;
501
+    if (z > current_position.z) {                            // raising?
502
+      destination.z = z;
495 503
       prepare_internal_fast_move_to_destination(z_feedrate);  // set current_position from destination
496 504
       if (DEBUGGING(LEVELING)) DEBUG_POS("z raise move", current_position);
497 505
     }
498 506
 
499
-    destination.set(rx, ry);
507
+    destination.set(x, y);
500 508
     prepare_internal_move_to_destination();                   // set current_position from destination
501 509
     if (DEBUGGING(LEVELING)) DEBUG_POS("xy move", current_position);
502 510
 
503
-    if (rz < current_position.z) {                            // lowering?
504
-      destination.z = rz;
511
+    if (z < current_position.z) {                            // lowering?
512
+      destination.z = z;
505 513
       prepare_internal_fast_move_to_destination(z_feedrate);  // set current_position from destination
506 514
       if (DEBUGGING(LEVELING)) DEBUG_POS("z lower move", current_position);
507 515
     }
@@ -509,36 +517,40 @@ void do_blocking_move_to(
509 517
   #elif IS_SCARA
510 518
 
511 519
     // If Z needs to raise, do it before moving XY
512
-    if (destination.z < rz) {
513
-      destination.z = rz;
520
+    if (destination.z < z) {
521
+      destination.z = z;
514 522
       prepare_internal_fast_move_to_destination(z_feedrate);
515 523
     }
516 524
 
517
-    destination.set(rx, ry);
525
+    destination.set(x, y);
518 526
     prepare_internal_fast_move_to_destination(xy_feedrate);
519 527
 
520 528
     // If Z needs to lower, do it after moving XY
521
-    if (destination.z > rz) {
522
-      destination.z = rz;
529
+    if (destination.z > z) {
530
+      destination.z = z;
523 531
       prepare_internal_fast_move_to_destination(z_feedrate);
524 532
     }
525 533
 
526 534
   #else
527 535
 
528
-    // If Z needs to raise, do it before moving XY
529
-    if (current_position.z < rz) {
530
-      current_position.z = rz;
531
-      line_to_current_position(z_feedrate);
532
-    }
536
+    #if HAS_Z_AXIS
537
+      // If Z needs to raise, do it before moving XY
538
+      if (current_position.z < z) {
539
+        current_position.z = z;
540
+        line_to_current_position(z_feedrate);
541
+      }
542
+    #endif
533 543
 
534
-    current_position.set(rx, ry);
544
+    current_position.set(x, y);
535 545
     line_to_current_position(xy_feedrate);
536 546
 
537
-    // If Z needs to lower, do it after moving XY
538
-    if (current_position.z > rz) {
539
-      current_position.z = rz;
540
-      line_to_current_position(z_feedrate);
541
-    }
547
+    #if HAS_Z_AXIS
548
+      // If Z needs to lower, do it after moving XY
549
+      if (current_position.z > z) {
550
+        current_position.z = z;
551
+        line_to_current_position(z_feedrate);
552
+      }
553
+    #endif
542 554
 
543 555
   #endif
544 556
 
@@ -546,53 +558,94 @@ void do_blocking_move_to(
546 558
 }
547 559
 
548 560
 void do_blocking_move_to(const xy_pos_t &raw, const_feedRate_t fr_mm_s/*=0.0f*/) {
549
-  do_blocking_move_to(LINEAR_AXIS_LIST(raw.x, raw.y, current_position.z, current_position.i), fr_mm_s);
561
+  do_blocking_move_to(LINEAR_AXIS_LIST(raw.x, raw.y, current_position.z, current_position.i, current_position.j, current_position.k), fr_mm_s);
550 562
 }
551 563
 void do_blocking_move_to(const xyz_pos_t &raw, const_feedRate_t fr_mm_s/*=0.0f*/) {
552
-  do_blocking_move_to(LINEAR_AXIS_LIST(raw.x, raw.y, raw.z), fr_mm_s);
564
+  do_blocking_move_to(LINEAR_AXIS_ELEM(raw), fr_mm_s);
553 565
 }
554 566
 void do_blocking_move_to(const xyze_pos_t &raw, const_feedRate_t fr_mm_s/*=0.0f*/) {
555
-  do_blocking_move_to(LINEAR_AXIS_LIST(raw.x, raw.y, raw.z), fr_mm_s);
567
+  do_blocking_move_to(LINEAR_AXIS_ELEM(raw), fr_mm_s);
556 568
 }
557
-
558 569
 void do_blocking_move_to_x(const_float_t rx, const_feedRate_t fr_mm_s/*=0.0*/) {
559 570
   do_blocking_move_to(
560
-    LINEAR_AXIS_LIST(rx, current_position.y, current_position.z),
561
-    fr_mm_s
562
-  );
563
-}
564
-void do_blocking_move_to_y(const_float_t ry, const_feedRate_t fr_mm_s/*=0.0*/) {
565
-  do_blocking_move_to(
566
-    LINEAR_AXIS_LIST(current_position.x, ry, current_position.z),
571
+    LINEAR_AXIS_LIST(rx, current_position.y, current_position.z, current_position.i, current_position.j, current_position.k),
567 572
     fr_mm_s
568 573
   );
569 574
 }
570
-void do_blocking_move_to_z(const_float_t rz, const_feedRate_t fr_mm_s/*=0.0*/) {
571
-  do_blocking_move_to_xy_z(current_position, rz, fr_mm_s);
572
-}
573 575
 
574
-void do_blocking_move_to_xy(const_float_t rx, const_float_t ry, const_feedRate_t fr_mm_s/*=0.0*/) {
575
-  do_blocking_move_to(
576
-    LINEAR_AXIS_LIST(rx, ry, current_position.z),
577
-    fr_mm_s
578
-  );
579
-}
580
-void do_blocking_move_to_xy(const xy_pos_t &raw, const_feedRate_t fr_mm_s/*=0.0f*/) {
581
-  do_blocking_move_to_xy(raw.x, raw.y, fr_mm_s);
582
-}
576
+#if HAS_Y_AXIS
577
+  void do_blocking_move_to_y(const_float_t ry, const_feedRate_t fr_mm_s/*=0.0*/) {
578
+    do_blocking_move_to(
579
+      LINEAR_AXIS_LIST(current_position.x, ry, current_position.z, current_position.i, current_position.j, current_position.k),
580
+      fr_mm_s
581
+    );
582
+  }
583
+#endif
583 584
 
584
-void do_blocking_move_to_xy_z(const xy_pos_t &raw, const_float_t z, const_feedRate_t fr_mm_s/*=0.0f*/) {
585
-  do_blocking_move_to(
586
-    LINEAR_AXIS_LIST(raw.x, raw.y, z),
587
-    fr_mm_s
588
-  );
589
-}
585
+#if HAS_Z_AXIS
586
+  void do_blocking_move_to_z(const_float_t rz, const_feedRate_t fr_mm_s/*=0.0*/) {
587
+    do_blocking_move_to_xy_z(current_position, rz, fr_mm_s);
588
+  }
589
+#endif
590 590
 
591
-void do_z_clearance(const_float_t zclear, const bool lower_allowed/*=false*/) {
592
-  float zdest = zclear;
593
-  if (!lower_allowed) NOLESS(zdest, current_position.z);
594
-  do_blocking_move_to_z(_MIN(zdest, Z_MAX_POS), TERN(HAS_BED_PROBE, z_probe_fast_mm_s, homing_feedrate(Z_AXIS)));
595
-}
591
+#if LINEAR_AXES == 4
592
+  void do_blocking_move_to_i(const_float_t ri, const_feedRate_t fr_mm_s/*=0.0*/) {
593
+    do_blocking_move_to_xyz_i(current_position, ri, fr_mm_s);
594
+  }
595
+  void do_blocking_move_to_xyz_i(const xyze_pos_t &raw, const_float_t i, const_feedRate_t fr_mm_s/*=0.0f*/) {
596
+	  do_blocking_move_to(raw.x, raw.y, raw.z, i, fr_mm_s);
597
+  }
598
+#endif
599
+
600
+#if LINEAR_AXES >= 5
601
+  void do_blocking_move_to_i(const_float_t ri, const_feedRate_t fr_mm_s/*=0.0*/) {
602
+    do_blocking_move_to_xyz_i(current_position, ri, fr_mm_s);
603
+  }
604
+  void do_blocking_move_to_xyz_i(const xyze_pos_t &raw, const_float_t i, const_feedRate_t fr_mm_s/*=0.0f*/) {
605
+	  do_blocking_move_to(raw.x, raw.y, raw.z, i, raw.j, fr_mm_s);
606
+  }
607
+  void do_blocking_move_to_j(const_float_t rj, const_feedRate_t fr_mm_s/*=0.0*/) {
608
+    do_blocking_move_to_xyzi_j(current_position, rj, fr_mm_s);
609
+  }
610
+  void do_blocking_move_to_xyzi_j(const xyze_pos_t &raw, const_float_t j, const_feedRate_t fr_mm_s/*=0.0f*/) {
611
+    do_blocking_move_to(raw.x, raw.y, raw.z, raw.i, j, fr_mm_s);
612
+  }
613
+#endif
614
+
615
+#if LINEAR_AXES >= 6
616
+  void do_blocking_move_to_k(const_float_t rk, const_feedRate_t fr_mm_s/*=0.0*/) {
617
+    do_blocking_move_to_xyzij_k(current_position, rk, fr_mm_s);
618
+  }
619
+  void do_blocking_move_to_xyzij_k(const xyze_pos_t &raw, const_float_t k, const_feedRate_t fr_mm_s/*=0.0f*/) {
620
+    do_blocking_move_to(raw.x, raw.y, raw.z, raw.i, raw.j, k, fr_mm_s);
621
+  }
622
+#endif
623
+
624
+#if HAS_Y_AXIS
625
+  void do_blocking_move_to_xy(const_float_t rx, const_float_t ry, const_feedRate_t fr_mm_s/*=0.0*/) {
626
+    do_blocking_move_to(
627
+      LINEAR_AXIS_LIST(rx, ry, current_position.z, current_position.i, current_position.j, current_position.k),
628
+      fr_mm_s
629
+    );
630
+  }
631
+  void do_blocking_move_to_xy(const xy_pos_t &raw, const_feedRate_t fr_mm_s/*=0.0f*/) {
632
+    do_blocking_move_to_xy(raw.x, raw.y, fr_mm_s);
633
+  }
634
+#endif
635
+
636
+#if HAS_Z_AXIS
637
+  void do_blocking_move_to_xy_z(const xy_pos_t &raw, const_float_t z, const_feedRate_t fr_mm_s/*=0.0f*/) {
638
+    do_blocking_move_to(
639
+      LINEAR_AXIS_LIST(raw.x, raw.y, z, current_position.i, current_position.j, current_position.k),
640
+      fr_mm_s
641
+    );
642
+  }
643
+  void do_z_clearance(const_float_t zclear, const bool lower_allowed/*=false*/) {
644
+    float zdest = zclear;
645
+    if (!lower_allowed) NOLESS(zdest, current_position.z);
646
+    do_blocking_move_to_z(_MIN(zdest, Z_MAX_POS), TERN(HAS_BED_PROBE, z_probe_fast_mm_s, homing_feedrate(Z_AXIS)));
647
+  }
648
+#endif
596 649
 
597 650
 //
598 651
 // Prepare to do endstop or probe moves with custom feedrates.
@@ -618,8 +671,8 @@ void restore_feedrate_and_scaling() {
618 671
   // Software Endstops are based on the configured limits.
619 672
   soft_endstops_t soft_endstop = {
620 673
     true, false,
621
-    LINEAR_AXIS_ARRAY(X_MIN_POS, Y_MIN_POS, Z_MIN_POS),
622
-    LINEAR_AXIS_ARRAY(X_MAX_BED, Y_MAX_BED, Z_MAX_POS)
674
+    LINEAR_AXIS_ARRAY(X_MIN_POS, Y_MIN_POS, Z_MIN_POS, I_MIN_POS, J_MIN_POS, K_MIN_POS),
675
+    LINEAR_AXIS_ARRAY(X_MAX_BED, Y_MAX_BED, Z_MAX_POS, I_MAX_POS, J_MAX_POS, K_MAX_POS)
623 676
   };
624 677
 
625 678
   /**
@@ -746,25 +799,59 @@ void restore_feedrate_and_scaling() {
746 799
         #endif
747 800
       }
748 801
 
749
-      if (axis_was_homed(Y_AXIS)) {
750
-        #if !HAS_SOFTWARE_ENDSTOPS || ENABLED(MIN_SOFTWARE_ENDSTOP_Y)
751
-          NOLESS(target.y, soft_endstop.min.y);
802
+      #if HAS_Y_AXIS
803
+        if (axis_was_homed(Y_AXIS)) {
804
+          #if !HAS_SOFTWARE_ENDSTOPS || ENABLED(MIN_SOFTWARE_ENDSTOP_Y)
805
+            NOLESS(target.y, soft_endstop.min.y);
806
+          #endif
807
+          #if !HAS_SOFTWARE_ENDSTOPS || ENABLED(MAX_SOFTWARE_ENDSTOP_Y)
808
+            NOMORE(target.y, soft_endstop.max.y);
809
+          #endif
810
+        }
811
+      #endif
812
+
813
+    #endif
814
+
815
+    #if HAS_Z_AXIS
816
+      if (axis_was_homed(Z_AXIS)) {
817
+        #if !HAS_SOFTWARE_ENDSTOPS || ENABLED(MIN_SOFTWARE_ENDSTOP_Z)
818
+          NOLESS(target.z, soft_endstop.min.z);
752 819
         #endif
753
-        #if !HAS_SOFTWARE_ENDSTOPS || ENABLED(MAX_SOFTWARE_ENDSTOP_Y)
754
-          NOMORE(target.y, soft_endstop.max.y);
820
+        #if !HAS_SOFTWARE_ENDSTOPS || ENABLED(MAX_SOFTWARE_ENDSTOP_Z)
821
+          NOMORE(target.z, soft_endstop.max.z);
822
+        #endif
823
+      }
824
+    #endif
825
+    #if LINEAR_AXES >= 4  // TODO (DerAndere): Find out why this was missing / removed
826
+      if (axis_was_homed(I_AXIS)) {
827
+        #if !HAS_SOFTWARE_ENDSTOPS || ENABLED(MIN_SOFTWARE_ENDSTOP_I)
828
+          NOLESS(target.i, soft_endstop.min.i);
829
+        #endif
830
+        #if !HAS_SOFTWARE_ENDSTOPS || ENABLED(MAX_SOFTWARE_ENDSTOP_I)
831
+          NOMORE(target.i, soft_endstop.max.i);
832
+        #endif
833
+      }
834
+    #endif
835
+    #if LINEAR_AXES >= 5
836
+      if (axis_was_homed(J_AXIS)) {
837
+        #if !HAS_SOFTWARE_ENDSTOPS || ENABLED(MIN_SOFTWARE_ENDSTOP_J)
838
+          NOLESS(target.j, soft_endstop.min.j);
839
+        #endif
840
+        #if !HAS_SOFTWARE_ENDSTOPS || ENABLED(MAX_SOFTWARE_ENDSTOP_J)
841
+          NOMORE(target.j, soft_endstop.max.j);
842
+        #endif
843
+      }
844
+    #endif
845
+    #if LINEAR_AXES >= 6
846
+      if (axis_was_homed(K_AXIS)) {
847
+        #if !HAS_SOFTWARE_ENDSTOPS || ENABLED(MIN_SOFTWARE_ENDSTOP_K)
848
+          NOLESS(target.k, soft_endstop.min.k);
849
+        #endif
850
+        #if !HAS_SOFTWARE_ENDSTOPS || ENABLED(MAX_SOFTWARE_ENDSTOP_K)
851
+          NOMORE(target.k, soft_endstop.max.k);
755 852
         #endif
756 853
       }
757
-
758 854
     #endif
759
-
760
-    if (axis_was_homed(Z_AXIS)) {
761
-      #if !HAS_SOFTWARE_ENDSTOPS || ENABLED(MIN_SOFTWARE_ENDSTOP_Z)
762
-        NOLESS(target.z, soft_endstop.min.z);
763
-      #endif
764
-      #if !HAS_SOFTWARE_ENDSTOPS || ENABLED(MAX_SOFTWARE_ENDSTOP_Z)
765
-        NOMORE(target.z, soft_endstop.max.z);
766
-      #endif
767
-    }
768 855
   }
769 856
 
770 857
 #else // !HAS_SOFTWARE_ENDSTOPS
@@ -824,7 +911,7 @@ FORCE_INLINE void segment_idle(millis_t &next_idle_ms) {
824 911
 
825 912
     // If the move is only in Z/E don't split up the move
826 913
     if (!diff.x && !diff.y) {
827
-      planner.buffer_line(destination, scaled_fr_mm_s, active_extruder);
914
+      planner.buffer_line(destination, scaled_fr_mm_s);
828 915
       return false; // caller will update current_position
829 916
     }
830 917
 
@@ -880,15 +967,11 @@ FORCE_INLINE void segment_idle(millis_t &next_idle_ms) {
880 967
     while (--segments) {
881 968
       segment_idle(next_idle_ms);
882 969
       raw += segment_distance;
883
-      if (!planner.buffer_line(raw, scaled_fr_mm_s, active_extruder, cartesian_segment_mm
884
-        OPTARG(SCARA_FEEDRATE_SCALING, inv_duration)
885
-      )) break;
970
+      if (!planner.buffer_line(raw, scaled_fr_mm_s, active_extruder, cartesian_segment_mm OPTARG(SCARA_FEEDRATE_SCALING, inv_duration))) break;
886 971
     }
887 972
 
888 973
     // Ensure last segment arrives at target location.
889
-    planner.buffer_line(destination, scaled_fr_mm_s, active_extruder, cartesian_segment_mm
890
-      OPTARG(SCARA_FEEDRATE_SCALING, inv_duration)
891
-    );
974
+    planner.buffer_line(destination, scaled_fr_mm_s, active_extruder, cartesian_segment_mm OPTARG(SCARA_FEEDRATE_SCALING, inv_duration));
892 975
 
893 976
     return false; // caller will update current_position
894 977
   }
@@ -910,7 +993,7 @@ FORCE_INLINE void segment_idle(millis_t &next_idle_ms) {
910 993
 
911 994
       // If the move is only in Z/E don't split up the move
912 995
       if (!diff.x && !diff.y) {
913
-        planner.buffer_line(destination, fr_mm_s, active_extruder);
996
+        planner.buffer_line(destination, fr_mm_s);
914 997
         return;
915 998
       }
916 999
 
@@ -947,18 +1030,12 @@ FORCE_INLINE void segment_idle(millis_t &next_idle_ms) {
947 1030
       while (--segments) {
948 1031
         segment_idle(next_idle_ms);
949 1032
         raw += segment_distance;
950
-        if (!planner.buffer_line(raw, fr_mm_s, active_extruder, cartesian_segment_mm
951
-          OPTARG(SCARA_FEEDRATE_SCALING, inv_duration)
952
-        )) break;
1033
+        if (!planner.buffer_line(raw, fr_mm_s, active_extruder, cartesian_segment_mm OPTARG(SCARA_FEEDRATE_SCALING, inv_duration))) break;
953 1034
       }
954 1035
 
955 1036
       // Since segment_distance is only approximate,
956 1037
       // the final move must be to the exact destination.
957
-      planner.buffer_line(destination, fr_mm_s, active_extruder, cartesian_segment_mm
958
-        #if ENABLED(SCARA_FEEDRATE_SCALING)
959
-          , inv_duration
960
-        #endif
961
-      );
1038
+      planner.buffer_line(destination, fr_mm_s, active_extruder, cartesian_segment_mm OPTARG(SCARA_FEEDRATE_SCALING, inv_duration));
962 1039
     }
963 1040
 
964 1041
   #endif // SEGMENT_LEVELED_MOVES
@@ -998,7 +1075,7 @@ FORCE_INLINE void segment_idle(millis_t &next_idle_ms) {
998 1075
       }
999 1076
     #endif // HAS_MESH
1000 1077
 
1001
-    planner.buffer_line(destination, scaled_fr_mm_s, active_extruder);
1078
+    planner.buffer_line(destination, scaled_fr_mm_s);
1002 1079
     return false; // caller will update current_position
1003 1080
   }
1004 1081
 
@@ -1080,12 +1157,12 @@ FORCE_INLINE void segment_idle(millis_t &next_idle_ms) {
1080 1157
           // Un-park the active extruder
1081 1158
           //
1082 1159
           const feedRate_t fr_zfast = planner.settings.max_feedrate_mm_s[Z_AXIS];
1083
-          #define CURPOS current_position
1084
-          #define RAISED raised_parked_position
1085 1160
           //  1. Move to the raised parked XYZ. Presumably the tool is already at XY.
1086
-          if (planner.buffer_line(RAISED.x, RAISED.y, RAISED.z, CURPOS.e, fr_zfast, active_extruder)) {
1161
+          xyze_pos_t raised = raised_parked_position; raised.e = current_position.e;
1162
+          if (planner.buffer_line(raised, fr_zfast)) {
1087 1163
             //  2. Move to the current native XY and raised Z. Presumably this is a null move.
1088
-            if (planner.buffer_line(CURPOS.x, CURPOS.y, RAISED.z, CURPOS.e, PLANNER_XY_FEEDRATE(), active_extruder)) {
1164
+            xyze_pos_t curpos = current_position; curpos.z = raised_parked_position.z;
1165
+            if (planner.buffer_line(curpos, PLANNER_XY_FEEDRATE())) {
1089 1166
               //  3. Lower Z back down
1090 1167
               line_to_current_position(fr_zfast);
1091 1168
             }
@@ -1099,21 +1176,24 @@ FORCE_INLINE void segment_idle(millis_t &next_idle_ms) {
1099 1176
         case DXC_MIRRORED_MODE:
1100 1177
         case DXC_DUPLICATION_MODE:
1101 1178
           if (active_extruder == 0) {
1102
-            xyze_pos_t new_pos = current_position;
1179
+            // Restore planner to parked head (T1) X position
1180
+            xyze_pos_t pos_now = current_position;
1181
+            pos_now.x = inactive_extruder_x;
1182
+            planner.set_position_mm(pos_now);
1183
+
1184
+            // Keep the same X or add the duplication X offset
1185
+            xyze_pos_t new_pos = pos_now;
1103 1186
             if (dual_x_carriage_mode == DXC_DUPLICATION_MODE)
1104 1187
               new_pos.x += duplicate_extruder_x_offset;
1105
-            else
1106
-              new_pos.x = inactive_extruder_x;
1107
-            // Move duplicate extruder into correct duplication position.
1188
+
1189
+            // Move duplicate extruder into the correct position
1108 1190
             if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("Set planner X", inactive_extruder_x, " ... Line to X", new_pos.x);
1109
-            planner.set_position_mm(inactive_extruder_x, current_position.y, current_position.z, current_position.e);
1110 1191
             if (!planner.buffer_line(new_pos, planner.settings.max_feedrate_mm_s[X_AXIS], 1)) break;
1111
-
1112 1192
             planner.synchronize();
1113
-            sync_plan_position();
1114 1193
 
1115
-            set_duplication_enabled(true);
1116
-            idex_set_parked(false);
1194
+            sync_plan_position();             // Extra sync for good measure
1195
+            set_duplication_enabled(true);    // Enable Duplication
1196
+            idex_set_parked(false);           // No longer parked
1117 1197
             if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("set_duplication_enabled(true)\nidex_set_parked(false)");
1118 1198
           }
1119 1199
           else if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("Active extruder not 0");
@@ -1207,22 +1287,24 @@ void prepare_line_to_destination() {
1207 1287
     };
1208 1288
     // Clear test bits that are trusted
1209 1289
     LINEAR_AXIS_CODE(
1210
-      set_should(axis_bits, X_AXIS),
1211
-      set_should(axis_bits, Y_AXIS),
1212
-      set_should(axis_bits, Z_AXIS)
1290
+      set_should(axis_bits, X_AXIS), set_should(axis_bits, Y_AXIS), set_should(axis_bits, Z_AXIS),
1291
+      set_should(axis_bits, I_AXIS), set_should(axis_bits, J_AXIS), set_should(axis_bits, K_AXIS)
1213 1292
     );
1214 1293
     return axis_bits;
1215 1294
   }
1216 1295
 
1217 1296
   bool homing_needed_error(linear_axis_bits_t axis_bits/*=linear_bits*/) {
1218 1297
     if ((axis_bits = axes_should_home(axis_bits))) {
1219
-      PGM_P home_first = GET_TEXT(MSG_HOME_FIRST);
1298
+      PGM_P home_first = GET_TEXT(MSG_HOME_FIRST);  // TODO: (DerAndere) Set this up for extra axes
1220 1299
       char msg[strlen_P(home_first)+1];
1221 1300
       sprintf_P(msg, home_first,
1222 1301
         LINEAR_AXIS_LIST(
1223 1302
           TEST(axis_bits, X_AXIS) ? "X" : "",
1224 1303
           TEST(axis_bits, Y_AXIS) ? "Y" : "",
1225
-          TEST(axis_bits, Z_AXIS) ? "Z" : ""
1304
+          TEST(axis_bits, Z_AXIS) ? "Z" : "",
1305
+          TEST(axis_bits, I_AXIS) ? AXIS4_STR : "",
1306
+          TEST(axis_bits, J_AXIS) ? AXIS5_STR : "",
1307
+          TEST(axis_bits, K_AXIS) ? AXIS6_STR : ""
1226 1308
         )
1227 1309
       );
1228 1310
       SERIAL_ECHO_START();
@@ -1374,6 +1456,9 @@ void prepare_line_to_destination() {
1374 1456
           case X_AXIS: if (ENABLED(X_SPI_SENSORLESS)) endstops.tmc_spi_homing.x = false; break;
1375 1457
           case Y_AXIS: if (ENABLED(Y_SPI_SENSORLESS)) endstops.tmc_spi_homing.y = false; break;
1376 1458
           case Z_AXIS: if (ENABLED(Z_SPI_SENSORLESS)) endstops.tmc_spi_homing.z = false; break;
1459
+          case I_AXIS: if (ENABLED(I_SPI_SENSORLESS)) endstops.tmc_spi_homing.i = false; break;
1460
+          case J_AXIS: if (ENABLED(J_SPI_SENSORLESS)) endstops.tmc_spi_homing.j = false; break;
1461
+          case K_AXIS: if (ENABLED(K_SPI_SENSORLESS)) endstops.tmc_spi_homing.k = false; break;
1377 1462
           default: break;
1378 1463
         }
1379 1464
       #endif
@@ -1446,12 +1531,7 @@ void prepare_line_to_destination() {
1446 1531
 
1447 1532
       // Set delta/cartesian axes directly
1448 1533
       target[axis] = distance;                  // The move will be towards the endstop
1449
-      planner.buffer_segment(target
1450
-        #if HAS_DIST_MM_ARG
1451
-          , cart_dist_mm
1452
-        #endif
1453
-        , home_fr_mm_s, active_extruder
1454
-      );
1534
+      planner.buffer_segment(target OPTARG(HAS_DIST_MM_ARG, cart_dist_mm), home_fr_mm_s, active_extruder);
1455 1535
     #endif
1456 1536
 
1457 1537
     planner.synchronize();
@@ -1531,6 +1611,30 @@ void prepare_line_to_destination() {
1531 1611
             stepperBackoutDir = INVERT_Z_DIR ? effectorBackoutDir : -effectorBackoutDir;
1532 1612
             break;
1533 1613
         #endif
1614
+        #ifdef I_MICROSTEPS
1615
+          case I_AXIS:
1616
+            phasePerUStep = PHASE_PER_MICROSTEP(I);
1617
+            phaseCurrent = stepperI.get_microstep_counter();
1618
+            effectorBackoutDir = -I_HOME_DIR;
1619
+            stepperBackoutDir = INVERT_I_DIR ? effectorBackoutDir : -effectorBackoutDir;
1620
+            break;
1621
+        #endif
1622
+        #ifdef J_MICROSTEPS
1623
+          case J_AXIS:
1624
+            phasePerUStep = PHASE_PER_MICROSTEP(J);
1625
+            phaseCurrent = stepperJ.get_microstep_counter();
1626
+            effectorBackoutDir = -J_HOME_DIR;
1627
+            stepperBackoutDir = INVERT_J_DIR ? effectorBackoutDir : -effectorBackoutDir;
1628
+            break;
1629
+        #endif
1630
+        #ifdef K_MICROSTEPS
1631
+          case K_AXIS:
1632
+            phasePerUStep = PHASE_PER_MICROSTEP(K);
1633
+            phaseCurrent = stepperK.get_microstep_counter();
1634
+            effectorBackoutDir = -K_HOME_DIR;
1635
+            stepperBackoutDir = INVERT_K_DIR ? effectorBackoutDir : -effectorBackoutDir;
1636
+            break;
1637
+        #endif
1534 1638
         default: return;
1535 1639
       }
1536 1640
 
@@ -1583,11 +1687,18 @@ void prepare_line_to_destination() {
1583 1687
     #else
1584 1688
       #define _CAN_HOME(A) (axis == _AXIS(A) && ( \
1585 1689
            ENABLED(A##_SPI_SENSORLESS) \
1586
-        || (_AXIS(A) == Z_AXIS && ENABLED(HOMING_Z_WITH_PROBE)) \
1690
+        || TERN0(HAS_Z_AXIS, TERN0(HOMING_Z_WITH_PROBE, _AXIS(A) == Z_AXIS)) \
1587 1691
         || TERN0(A##_HOME_TO_MIN, A##_MIN_PIN > -1) \
1588 1692
         || TERN0(A##_HOME_TO_MAX, A##_MAX_PIN > -1) \
1589 1693
       ))
1590
-      if (!_CAN_HOME(X) && !_CAN_HOME(Y) && !_CAN_HOME(Z)) return;
1694
+      if (LINEAR_AXIS_GANG(
1695
+           !_CAN_HOME(X),
1696
+        && !_CAN_HOME(Y),
1697
+        && !_CAN_HOME(Z),
1698
+        && !_CAN_HOME(I),
1699
+        && !_CAN_HOME(J),
1700
+        && !_CAN_HOME(K))
1701
+      ) return;
1591 1702
     #endif
1592 1703
 
1593 1704
     if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR(">>> homeaxis(", AS_CHAR(AXIS_CHAR(axis)), ")");
@@ -1636,9 +1747,9 @@ void prepare_line_to_destination() {
1636 1747
 
1637 1748
     // Determine if a homing bump will be done and the bumps distance
1638 1749
     // When homing Z with probe respect probe clearance
1639
-    const bool use_probe_bump = TERN0(HOMING_Z_WITH_PROBE, axis == Z_AXIS && home_bump_mm(Z_AXIS));
1750
+    const bool use_probe_bump = TERN0(HOMING_Z_WITH_PROBE, axis == Z_AXIS && home_bump_mm(axis));
1640 1751
     const float bump = axis_home_dir * (
1641
-      use_probe_bump ? _MAX(TERN0(HOMING_Z_WITH_PROBE, Z_CLEARANCE_BETWEEN_PROBES), home_bump_mm(Z_AXIS)) : home_bump_mm(axis)
1752
+      use_probe_bump ? _MAX(TERN0(HOMING_Z_WITH_PROBE, Z_CLEARANCE_BETWEEN_PROBES), home_bump_mm(axis)) : home_bump_mm(axis)
1642 1753
     );
1643 1754
 
1644 1755
     //

+ 98
- 38
Marlin/src/module/motion.h View File

@@ -44,7 +44,7 @@ extern xyze_pos_t current_position,  // High-level current tool position
44 44
 
45 45
 // G60/G61 Position Save and Return
46 46
 #if SAVED_POSITIONS
47
-  extern uint8_t saved_slots[(SAVED_POSITIONS + 7) >> 3];
47
+  extern uint8_t saved_slots[(SAVED_POSITIONS + 7) >> 3]; // TODO: Add support for LINEAR_AXES >= 4
48 48
   extern xyze_pos_t stored_position[SAVED_POSITIONS];
49 49
 #endif
50 50
 
@@ -53,7 +53,7 @@ extern xyz_pos_t cartes;
53 53
 
54 54
 // Until kinematics.cpp is created, declare this here
55 55
 #if IS_KINEMATIC
56
-  extern abc_pos_t delta;
56
+  extern abce_pos_t delta;
57 57
 #endif
58 58
 
59 59
 #if HAS_ABL_NOT_UBL
@@ -75,16 +75,16 @@ extern xyz_pos_t cartes;
75 75
  */
76 76
 constexpr xyz_feedrate_t homing_feedrate_mm_m = HOMING_FEEDRATE_MM_M;
77 77
 FORCE_INLINE feedRate_t homing_feedrate(const AxisEnum a) {
78
-  float v;
79
-  #if ENABLED(DELTA)
80
-    v = homing_feedrate_mm_m.z;
81
-  #else
82
-    switch (a) {
83
-      case X_AXIS: v = homing_feedrate_mm_m.x; break;
84
-      case Y_AXIS: v = homing_feedrate_mm_m.y; break;
85
-      case Z_AXIS:
86
-          default: v = homing_feedrate_mm_m.z;
87
-    }
78
+  float v = TERN0(HAS_Z_AXIS, homing_feedrate_mm_m.z);
79
+  #if DISABLED(DELTA)
80
+    LINEAR_AXIS_CODE(
81
+           if (a == X_AXIS) v = homing_feedrate_mm_m.x,
82
+      else if (a == Y_AXIS) v = homing_feedrate_mm_m.y,
83
+      else if (a == Z_AXIS) v = homing_feedrate_mm_m.z,
84
+      else if (a == I_AXIS) v = homing_feedrate_mm_m.i,
85
+      else if (a == J_AXIS) v = homing_feedrate_mm_m.j,
86
+      else if (a == K_AXIS) v = homing_feedrate_mm_m.k
87
+    );
88 88
   #endif
89 89
   return MMM_TO_MMS(v);
90 90
 }
@@ -124,7 +124,7 @@ inline int8_t pgm_read_any(const int8_t *p) { return TERN(__IMXRT1062__, *p, pgm
124 124
 
125 125
 #define XYZ_DEFS(T, NAME, OPT) \
126 126
   inline T NAME(const AxisEnum axis) { \
127
-    static const XYZval<T> NAME##_P DEFS_PROGMEM = LINEAR_AXIS_ARRAY(X_##OPT, Y_##OPT, Z_##OPT); \
127
+    static const XYZval<T> NAME##_P DEFS_PROGMEM = LINEAR_AXIS_ARRAY(X_##OPT, Y_##OPT, Z_##OPT, I_##OPT, J_##OPT, K_##OPT); \
128 128
     return pgm_read_any(&NAME##_P[axis]); \
129 129
   }
130 130
 XYZ_DEFS(float, base_min_pos,   MIN_POS);
@@ -168,13 +168,36 @@ inline float home_bump_mm(const AxisEnum axis) {
168 168
             TERN_(MIN_SOFTWARE_ENDSTOP_X, amin = min.x);
169 169
             TERN_(MAX_SOFTWARE_ENDSTOP_X, amax = max.x);
170 170
             break;
171
-          case Y_AXIS:
172
-            TERN_(MIN_SOFTWARE_ENDSTOP_Y, amin = min.y);
173
-            TERN_(MAX_SOFTWARE_ENDSTOP_Y, amax = max.y);
174
-            break;
175
-          case Z_AXIS:
176
-            TERN_(MIN_SOFTWARE_ENDSTOP_Z, amin = min.z);
177
-            TERN_(MAX_SOFTWARE_ENDSTOP_Z, amax = max.z);
171
+          #if HAS_Y_AXIS
172
+            case Y_AXIS:
173
+              TERN_(MIN_SOFTWARE_ENDSTOP_Y, amin = min.y);
174
+              TERN_(MAX_SOFTWARE_ENDSTOP_Y, amax = max.y);
175
+              break;
176
+          #endif
177
+          #if HAS_Z_AXIS
178
+            case Z_AXIS:
179
+              TERN_(MIN_SOFTWARE_ENDSTOP_Z, amin = min.z);
180
+              TERN_(MAX_SOFTWARE_ENDSTOP_Z, amax = max.z);
181
+              break;
182
+          #endif
183
+          #if LINEAR_AXES >= 4 // TODO (DerAndere): Test for LINEAR_AXES >= 4
184
+            case I_AXIS:
185
+              TERN_(MIN_SOFTWARE_ENDSTOP_I, amin = min.i);
186
+              TERN_(MIN_SOFTWARE_ENDSTOP_I, amax = max.i);
187
+              break;
188
+          #endif
189
+          #if LINEAR_AXES >= 5
190
+            case J_AXIS:
191
+              TERN_(MIN_SOFTWARE_ENDSTOP_J, amin = min.j);
192
+              TERN_(MIN_SOFTWARE_ENDSTOP_J, amax = max.j);
193
+              break;
194
+          #endif
195
+          #if LINEAR_AXES >= 6
196
+            case K_AXIS:
197
+              TERN_(MIN_SOFTWARE_ENDSTOP_K, amin = min.k);
198
+              TERN_(MIN_SOFTWARE_ENDSTOP_K, amax = max.k);
199
+              break;
200
+          #endif
178 201
           default: break;
179 202
         }
180 203
       #endif
@@ -298,32 +321,53 @@ inline void prepare_internal_move_to_destination(const_feedRate_t fr_mm_s=0.0f)
298 321
 /**
299 322
  * Blocking movement and shorthand functions
300 323
  */
301
-void do_blocking_move_to(
302
-  LINEAR_AXIS_LIST(const float rx, const float ry, const float rz),
303
-  const_feedRate_t fr_mm_s=0.0f
304
-);
324
+void do_blocking_move_to(LINEAR_AXIS_ARGS(const float), const_feedRate_t fr_mm_s=0.0f);
305 325
 void do_blocking_move_to(const xy_pos_t &raw, const_feedRate_t fr_mm_s=0.0f);
306 326
 void do_blocking_move_to(const xyz_pos_t &raw, const_feedRate_t fr_mm_s=0.0f);
307 327
 void do_blocking_move_to(const xyze_pos_t &raw, const_feedRate_t fr_mm_s=0.0f);
308 328
 
309 329
 void do_blocking_move_to_x(const_float_t rx, const_feedRate_t fr_mm_s=0.0f);
310
-void do_blocking_move_to_y(const_float_t ry, const_feedRate_t fr_mm_s=0.0f);
311
-void do_blocking_move_to_z(const_float_t rz, const_feedRate_t fr_mm_s=0.0f);
330
+#if HAS_Y_AXIS
331
+  void do_blocking_move_to_y(const_float_t ry, const_feedRate_t fr_mm_s=0.0f);
332
+#endif
333
+#if HAS_Z_AXIS
334
+  void do_blocking_move_to_z(const_float_t rz, const_feedRate_t fr_mm_s=0.0f);
335
+#endif
336
+#if LINEAR_AXES >= 4
337
+  void do_blocking_move_to_i(const_float_t ri, const_feedRate_t fr_mm_s=0.0f);
338
+  void do_blocking_move_to_xyz_i(const xyze_pos_t &raw, const_float_t i, const_feedRate_t fr_mm_s=0.0f);
339
+#endif
340
+#if LINEAR_AXES >= 5
341
+  void do_blocking_move_to_j(const_float_t rj, const_feedRate_t fr_mm_s=0.0f);
342
+  void do_blocking_move_to_xyzi_j(const xyze_pos_t &raw, const_float_t j, const_feedRate_t fr_mm_s=0.0f);
343
+#endif
344
+#if LINEAR_AXES >= 6
345
+  void do_blocking_move_to_k(const_float_t rk, const_feedRate_t fr_mm_s=0.0f);
346
+  void do_blocking_move_to_xyzij_k(const xyze_pos_t &raw, const_float_t k, const_feedRate_t fr_mm_s=0.0f);
347
+#endif
312 348
 
313
-void do_blocking_move_to_xy(const_float_t rx, const_float_t ry, const_feedRate_t fr_mm_s=0.0f);
314
-void do_blocking_move_to_xy(const xy_pos_t &raw, const_feedRate_t fr_mm_s=0.0f);
315
-FORCE_INLINE void do_blocking_move_to_xy(const xyz_pos_t &raw, const_feedRate_t fr_mm_s=0.0f)  { do_blocking_move_to_xy(xy_pos_t(raw), fr_mm_s); }
316
-FORCE_INLINE void do_blocking_move_to_xy(const xyze_pos_t &raw, const_feedRate_t fr_mm_s=0.0f) { do_blocking_move_to_xy(xy_pos_t(raw), fr_mm_s); }
349
+#if HAS_Y_AXIS
350
+  void do_blocking_move_to_xy(const_float_t rx, const_float_t ry, const_feedRate_t fr_mm_s=0.0f);
351
+  void do_blocking_move_to_xy(const xy_pos_t &raw, const_feedRate_t fr_mm_s=0.0f);
352
+  FORCE_INLINE void do_blocking_move_to_xy(const xyz_pos_t &raw, const_feedRate_t fr_mm_s=0.0f)  { do_blocking_move_to_xy(xy_pos_t(raw), fr_mm_s); }
353
+  FORCE_INLINE void do_blocking_move_to_xy(const xyze_pos_t &raw, const_feedRate_t fr_mm_s=0.0f) { do_blocking_move_to_xy(xy_pos_t(raw), fr_mm_s); }
354
+#endif
317 355
 
318
-void do_blocking_move_to_xy_z(const xy_pos_t &raw, const_float_t z, const_feedRate_t fr_mm_s=0.0f);
319
-FORCE_INLINE void do_blocking_move_to_xy_z(const xyz_pos_t &raw, const_float_t z, const_feedRate_t fr_mm_s=0.0f)  { do_blocking_move_to_xy_z(xy_pos_t(raw), z, fr_mm_s); }
320
-FORCE_INLINE void do_blocking_move_to_xy_z(const xyze_pos_t &raw, const_float_t z, const_feedRate_t fr_mm_s=0.0f) { do_blocking_move_to_xy_z(xy_pos_t(raw), z, fr_mm_s); }
356
+#if HAS_Z_AXIS
357
+  void do_blocking_move_to_xy_z(const xy_pos_t &raw, const_float_t z, const_feedRate_t fr_mm_s=0.0f);
358
+  FORCE_INLINE void do_blocking_move_to_xy_z(const xyz_pos_t &raw, const_float_t z, const_feedRate_t fr_mm_s=0.0f)  { do_blocking_move_to_xy_z(xy_pos_t(raw), z, fr_mm_s); }
359
+  FORCE_INLINE void do_blocking_move_to_xy_z(const xyze_pos_t &raw, const_float_t z, const_feedRate_t fr_mm_s=0.0f) { do_blocking_move_to_xy_z(xy_pos_t(raw), z, fr_mm_s); }
360
+#endif
321 361
 
322 362
 void remember_feedrate_and_scaling();
323 363
 void remember_feedrate_scaling_off();
324 364
 void restore_feedrate_and_scaling();
325 365
 
326
-void do_z_clearance(const_float_t zclear, const bool lower_allowed=false);
366
+#if HAS_Z_AXIS
367
+  void do_z_clearance(const_float_t zclear, const bool lower_allowed=false);
368
+#else
369
+  inline void do_z_clearance(float, bool=false) {}
370
+#endif
327 371
 
328 372
 /**
329 373
  * Homing and Trusted Axes
@@ -421,11 +465,27 @@ FORCE_INLINE bool all_axes_trusted()                        { return linear_bits
421 465
   FORCE_INLINE void toNative(xyze_pos_t&)  {}
422 466
 #endif
423 467
 #define LOGICAL_X_POSITION(POS) NATIVE_TO_LOGICAL(POS, X_AXIS)
424
-#define LOGICAL_Y_POSITION(POS) NATIVE_TO_LOGICAL(POS, Y_AXIS)
425
-#define LOGICAL_Z_POSITION(POS) NATIVE_TO_LOGICAL(POS, Z_AXIS)
426 468
 #define RAW_X_POSITION(POS)     LOGICAL_TO_NATIVE(POS, X_AXIS)
427
-#define RAW_Y_POSITION(POS)     LOGICAL_TO_NATIVE(POS, Y_AXIS)
428
-#define RAW_Z_POSITION(POS)     LOGICAL_TO_NATIVE(POS, Z_AXIS)
469
+#if HAS_Y_AXIS
470
+  #define LOGICAL_Y_POSITION(POS) NATIVE_TO_LOGICAL(POS, Y_AXIS)
471
+  #define RAW_Y_POSITION(POS)     LOGICAL_TO_NATIVE(POS, Y_AXIS)
472
+#endif
473
+#if HAS_Z_AXIS
474
+  #define LOGICAL_Z_POSITION(POS) NATIVE_TO_LOGICAL(POS, Z_AXIS)
475
+  #define RAW_Z_POSITION(POS)     LOGICAL_TO_NATIVE(POS, Z_AXIS)
476
+#endif
477
+#if LINEAR_AXES >= 4
478
+  #define LOGICAL_I_POSITION(POS) NATIVE_TO_LOGICAL(POS, I_AXIS)
479
+  #define RAW_I_POSITION(POS)     LOGICAL_TO_NATIVE(POS, I_AXIS)
480
+#endif
481
+#if LINEAR_AXES >= 5
482
+  #define LOGICAL_J_POSITION(POS) NATIVE_TO_LOGICAL(POS, J_AXIS)
483
+  #define RAW_J_POSITION(POS)     LOGICAL_TO_NATIVE(POS, J_AXIS)
484
+#endif
485
+#if LINEAR_AXES >= 6
486
+  #define LOGICAL_K_POSITION(POS) NATIVE_TO_LOGICAL(POS, K_AXIS)
487
+  #define RAW_K_POSITION(POS)     LOGICAL_TO_NATIVE(POS, K_AXIS)
488
+#endif
429 489
 
430 490
 /**
431 491
  * position_is_reachable family of functions

+ 154
- 104
Marlin/src/module/planner.cpp View File

@@ -1310,7 +1310,7 @@ void Planner::recalculate() {
1310 1310
  */
1311 1311
 void Planner::check_axes_activity() {
1312 1312
 
1313
-  #if ANY(DISABLE_X, DISABLE_Y, DISABLE_Z, DISABLE_E)
1313
+  #if ANY(DISABLE_X, DISABLE_Y, DISABLE_Z , DISABLE_I , DISABLE_J , DISABLE_K, DISABLE_E)
1314 1314
     xyze_bool_t axis_active = { false };
1315 1315
   #endif
1316 1316
 
@@ -1342,14 +1342,17 @@ void Planner::check_axes_activity() {
1342 1342
       TERN_(HAS_HEATER_2, tail_e_to_p_pressure = block->e_to_p_pressure);
1343 1343
     #endif
1344 1344
 
1345
-    #if ANY(DISABLE_X, DISABLE_Y, DISABLE_Z, DISABLE_E)
1345
+    #if ANY(DISABLE_X, DISABLE_Y, DISABLE_Z, DISABLE_I, DISABLE_J, DISABLE_K, DISABLE_E)
1346 1346
       for (uint8_t b = block_buffer_tail; b != block_buffer_head; b = next_block_index(b)) {
1347 1347
         block_t *block = &block_buffer[b];
1348 1348
         LOGICAL_AXIS_CODE(
1349 1349
           if (TERN0(DISABLE_E, block->steps.e)) axis_active.e = true,
1350 1350
           if (TERN0(DISABLE_X, block->steps.x)) axis_active.x = true,
1351 1351
           if (TERN0(DISABLE_Y, block->steps.y)) axis_active.y = true,
1352
-          if (TERN0(DISABLE_Z, block->steps.z)) axis_active.z = true
1352
+          if (TERN0(DISABLE_Z, block->steps.z)) axis_active.z = true,
1353
+          if (TERN0(DISABLE_I, block->steps.i)) axis_active.i = true,
1354
+          if (TERN0(DISABLE_J, block->steps.j)) axis_active.j = true,
1355
+          if (TERN0(DISABLE_K, block->steps.k)) axis_active.k = true
1353 1356
         );
1354 1357
       }
1355 1358
     #endif
@@ -1375,7 +1378,10 @@ void Planner::check_axes_activity() {
1375 1378
     if (TERN0(DISABLE_E, !axis_active.e)) disable_e_steppers(),
1376 1379
     if (TERN0(DISABLE_X, !axis_active.x)) DISABLE_AXIS_X(),
1377 1380
     if (TERN0(DISABLE_Y, !axis_active.y)) DISABLE_AXIS_Y(),
1378
-    if (TERN0(DISABLE_Z, !axis_active.z)) DISABLE_AXIS_Z()
1381
+    if (TERN0(DISABLE_Z, !axis_active.z)) DISABLE_AXIS_Z(),
1382
+    if (TERN0(DISABLE_I, !axis_active.i)) DISABLE_AXIS_I(),
1383
+    if (TERN0(DISABLE_J, !axis_active.j)) DISABLE_AXIS_J(),
1384
+    if (TERN0(DISABLE_K, !axis_active.k)) DISABLE_AXIS_K()
1379 1385
   );
1380 1386
 
1381 1387
   //
@@ -1445,7 +1451,7 @@ void Planner::check_axes_activity() {
1445 1451
     float high = 0.0;
1446 1452
     for (uint8_t b = block_buffer_tail; b != block_buffer_head; b = next_block_index(b)) {
1447 1453
       block_t *block = &block_buffer[b];
1448
-      if (block->steps.x || block->steps.y || block->steps.z) {
1454
+      if (LINEAR_AXIS_GANG(block->steps.x, || block->steps.y, || block->steps.z, block->steps.i, || block->steps.j, || block->steps.k)) {
1449 1455
         const float se = (float)block->steps.e / block->step_event_count * SQRT(block->nominal_speed_sqr); // mm/sec;
1450 1456
         NOLESS(high, se);
1451 1457
       }
@@ -1831,7 +1837,10 @@ bool Planner::_populate_block(block_t * const block, bool split_move,
1831 1837
     de = target.e - position.e,
1832 1838
     da = target.a - position.a,
1833 1839
     db = target.b - position.b,
1834
-    dc = target.c - position.c
1840
+    dc = target.c - position.c,
1841
+    di = target.i - position.i,
1842
+    dj = target.j - position.j,
1843
+    dk = target.k - position.k
1835 1844
   );
1836 1845
 
1837 1846
   /* <-- add a slash to enable
@@ -1910,7 +1919,10 @@ bool Planner::_populate_block(block_t * const block, bool split_move,
1910 1919
     LINEAR_AXIS_CODE(
1911 1920
       if (da < 0) SBI(dm, X_AXIS),
1912 1921
       if (db < 0) SBI(dm, Y_AXIS),
1913
-      if (dc < 0) SBI(dm, Z_AXIS)
1922
+      if (dc < 0) SBI(dm, Z_AXIS),
1923
+      if (di < 0) SBI(dm, I_AXIS),
1924
+      if (dj < 0) SBI(dm, J_AXIS),
1925
+      if (dk < 0) SBI(dm, K_AXIS)
1914 1926
     );
1915 1927
   #endif
1916 1928
   #if HAS_EXTRUDERS
@@ -1951,7 +1963,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move,
1951 1963
     block->steps.set(ABS(da), ABS(db), ABS(dc));
1952 1964
   #else
1953 1965
     // default non-h-bot planning
1954
-    block->steps.set(LINEAR_AXIS_LIST(ABS(da), ABS(db), ABS(dc)));
1966
+    block->steps.set(LINEAR_AXIS_LIST(ABS(da), ABS(db), ABS(dc), ABS(di), ABS(dj), ABS(dk)));
1955 1967
   #endif
1956 1968
 
1957 1969
   /**
@@ -1997,7 +2009,10 @@ bool Planner::_populate_block(block_t * const block, bool split_move,
1997 2009
     LINEAR_AXIS_CODE(
1998 2010
       steps_dist_mm.a = da * steps_to_mm[A_AXIS],
1999 2011
       steps_dist_mm.b = db * steps_to_mm[B_AXIS],
2000
-      steps_dist_mm.c = dc * steps_to_mm[C_AXIS]
2012
+      steps_dist_mm.c = dc * steps_to_mm[C_AXIS],
2013
+      steps_dist_mm.i = di * steps_to_mm[I_AXIS],
2014
+      steps_dist_mm.j = dj * steps_to_mm[J_AXIS],
2015
+      steps_dist_mm.k = dk * steps_to_mm[K_AXIS]
2001 2016
     );
2002 2017
   #endif
2003 2018
 
@@ -2010,7 +2025,10 @@ bool Planner::_populate_block(block_t * const block, bool split_move,
2010 2025
   if (true LINEAR_AXIS_GANG(
2011 2026
       && block->steps.a < MIN_STEPS_PER_SEGMENT,
2012 2027
       && block->steps.b < MIN_STEPS_PER_SEGMENT,
2013
-      && block->steps.c < MIN_STEPS_PER_SEGMENT
2028
+      && block->steps.c < MIN_STEPS_PER_SEGMENT,
2029
+      && block->steps.i < MIN_STEPS_PER_SEGMENT,
2030
+      && block->steps.j < MIN_STEPS_PER_SEGMENT,
2031
+      && block->steps.k < MIN_STEPS_PER_SEGMENT
2014 2032
     )
2015 2033
   ) {
2016 2034
     block->millimeters = TERN0(HAS_EXTRUDERS, ABS(steps_dist_mm.e));
@@ -2022,19 +2040,30 @@ bool Planner::_populate_block(block_t * const block, bool split_move,
2022 2040
       block->millimeters = SQRT(
2023 2041
         #if EITHER(CORE_IS_XY, MARKFORGED_XY)
2024 2042
           LINEAR_AXIS_GANG(
2025
-            sq(steps_dist_mm.head.x), + sq(steps_dist_mm.head.y), + sq(steps_dist_mm.z)
2043
+              sq(steps_dist_mm.head.x), + sq(steps_dist_mm.head.y), + sq(steps_dist_mm.z),
2044
+            + sq(steps_dist_mm.i),      + sq(steps_dist_mm.j),      + sq(steps_dist_mm.k)
2026 2045
           )
2027 2046
         #elif CORE_IS_XZ
2028 2047
           LINEAR_AXIS_GANG(
2029
-            sq(steps_dist_mm.head.x), + sq(steps_dist_mm.y), + sq(steps_dist_mm.head.z)
2048
+              sq(steps_dist_mm.head.x), + sq(steps_dist_mm.y), + sq(steps_dist_mm.head.z),
2049
+            + sq(steps_dist_mm.i),      + sq(steps_dist_mm.j), + sq(steps_dist_mm.k)
2030 2050
           )
2031 2051
         #elif CORE_IS_YZ
2032 2052
           LINEAR_AXIS_GANG(
2033
-            sq(steps_dist_mm.x), + sq(steps_dist_mm.head.y), + sq(steps_dist_mm.head.z)
2053
+              sq(steps_dist_mm.x)  + sq(steps_dist_mm.head.y) + sq(steps_dist_mm.head.z)
2054
+            + sq(steps_dist_mm.i), + sq(steps_dist_mm.j),     + sq(steps_dist_mm.k)
2034 2055
           )
2056
+        #elif ENABLED(FOAMCUTTER_XYUV)
2057
+          // Return the largest distance move from either X/Y or I/J plane
2058
+          #if LINEAR_AXES >= 5
2059
+            _MAX(sq(steps_dist_mm.x) + sq(steps_dist_mm.y), sq(steps_dist_mm.i) + sq(steps_dist_mm.j))
2060
+          #else
2061
+            sq(steps_dist_mm.x) + sq(steps_dist_mm.y)
2062
+          #endif
2035 2063
         #else
2036 2064
           LINEAR_AXIS_GANG(
2037
-            sq(steps_dist_mm.x), + sq(steps_dist_mm.y), + sq(steps_dist_mm.z)
2065
+              sq(steps_dist_mm.x), + sq(steps_dist_mm.y), + sq(steps_dist_mm.z),
2066
+            + sq(steps_dist_mm.i), + sq(steps_dist_mm.j), + sq(steps_dist_mm.k)
2038 2067
           )
2039 2068
         #endif
2040 2069
       );
@@ -2055,7 +2084,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move,
2055 2084
   TERN_(HAS_EXTRUDERS, block->steps.e = esteps);
2056 2085
 
2057 2086
   block->step_event_count = _MAX(LOGICAL_AXIS_LIST(
2058
-    esteps, block->steps.a, block->steps.b, block->steps.c
2087
+    esteps, block->steps.a, block->steps.b, block->steps.c, block->steps.i, block->steps.j, block->steps.k
2059 2088
   ));
2060 2089
 
2061 2090
   // Bail if this is a zero-length block
@@ -2082,7 +2111,10 @@ bool Planner::_populate_block(block_t * const block, bool split_move,
2082 2111
     if (LINEAR_AXIS_GANG(
2083 2112
          block->steps.x,
2084 2113
       || block->steps.y,
2085
-      || block->steps.z
2114
+      || block->steps.z,
2115
+      || block->steps.i,
2116
+      || block->steps.j,
2117
+      || block->steps.k
2086 2118
     )) powerManager.power_on();
2087 2119
   #endif
2088 2120
 
@@ -2111,7 +2143,10 @@ bool Planner::_populate_block(block_t * const block, bool split_move,
2111 2143
     LINEAR_AXIS_CODE(
2112 2144
       if (block->steps.x) ENABLE_AXIS_X(),
2113 2145
       if (block->steps.y) ENABLE_AXIS_Y(),
2114
-      if (TERN(Z_LATE_ENABLE, 0, block->steps.z)) ENABLE_AXIS_Z()
2146
+      if (TERN(Z_LATE_ENABLE, 0, block->steps.z)) ENABLE_AXIS_Z(),
2147
+      if (block->steps.i) ENABLE_AXIS_I(),
2148
+      if (block->steps.j) ENABLE_AXIS_J(),
2149
+      if (block->steps.k) ENABLE_AXIS_K()
2115 2150
     );
2116 2151
   #endif
2117 2152
 
@@ -2301,8 +2336,9 @@ bool Planner::_populate_block(block_t * const block, bool split_move,
2301 2336
   const float steps_per_mm = block->step_event_count * inverse_millimeters;
2302 2337
   uint32_t accel;
2303 2338
   if (LINEAR_AXIS_GANG(
2304
-    !block->steps.a, && !block->steps.b, && !block->steps.c
2305
-  )) {                                                            // Is this a retract / recover move?
2339
+         !block->steps.a, && !block->steps.b, && !block->steps.c,
2340
+      && !block->steps.i, && !block->steps.j, && !block->steps.k)
2341
+  ) {                                                             // Is this a retract / recover move?
2306 2342
     accel = CEIL(settings.retract_acceleration * steps_per_mm);   // Convert to: acceleration steps/sec^2
2307 2343
     TERN_(LIN_ADVANCE, block->use_advance_lead = false);          // No linear advance for simple retract/recover
2308 2344
   }
@@ -2371,7 +2407,10 @@ bool Planner::_populate_block(block_t * const block, bool split_move,
2371 2407
         LIMIT_ACCEL_LONG(E_AXIS, E_INDEX_N(extruder)),
2372 2408
         LIMIT_ACCEL_LONG(A_AXIS, 0),
2373 2409
         LIMIT_ACCEL_LONG(B_AXIS, 0),
2374
-        LIMIT_ACCEL_LONG(C_AXIS, 0)
2410
+        LIMIT_ACCEL_LONG(C_AXIS, 0),
2411
+        LIMIT_ACCEL_LONG(I_AXIS, 0),
2412
+        LIMIT_ACCEL_LONG(J_AXIS, 0),
2413
+        LIMIT_ACCEL_LONG(K_AXIS, 0)
2375 2414
       );
2376 2415
     }
2377 2416
     else {
@@ -2379,7 +2418,10 @@ bool Planner::_populate_block(block_t * const block, bool split_move,
2379 2418
         LIMIT_ACCEL_FLOAT(E_AXIS, E_INDEX_N(extruder)),
2380 2419
         LIMIT_ACCEL_FLOAT(A_AXIS, 0),
2381 2420
         LIMIT_ACCEL_FLOAT(B_AXIS, 0),
2382
-        LIMIT_ACCEL_FLOAT(C_AXIS, 0)
2421
+        LIMIT_ACCEL_FLOAT(C_AXIS, 0),
2422
+        LIMIT_ACCEL_FLOAT(I_AXIS, 0),
2423
+        LIMIT_ACCEL_FLOAT(J_AXIS, 0),
2424
+        LIMIT_ACCEL_FLOAT(K_AXIS, 0)
2383 2425
       );
2384 2426
     }
2385 2427
   }
@@ -2444,7 +2486,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move,
2444 2486
       #if HAS_DIST_MM_ARG
2445 2487
         cart_dist_mm
2446 2488
       #else
2447
-        LOGICAL_AXIS_ARRAY(steps_dist_mm.e, steps_dist_mm.x, steps_dist_mm.y, steps_dist_mm.z)
2489
+        LOGICAL_AXIS_ARRAY(steps_dist_mm.e, steps_dist_mm.x, steps_dist_mm.y, steps_dist_mm.z, steps_dist_mm.i, steps_dist_mm.j, steps_dist_mm.k)
2448 2490
       #endif
2449 2491
     ;
2450 2492
 
@@ -2467,7 +2509,10 @@ bool Planner::_populate_block(block_t * const block, bool split_move,
2467 2509
                                  + (-prev_unit_vec.e * unit_vec.e),
2468 2510
                                    (-prev_unit_vec.x * unit_vec.x),
2469 2511
                                  + (-prev_unit_vec.y * unit_vec.y),
2470
-                                 + (-prev_unit_vec.z * unit_vec.z)
2512
+                                 + (-prev_unit_vec.z * unit_vec.z),
2513
+                                 + (-prev_unit_vec.i * unit_vec.i),
2514
+                                 + (-prev_unit_vec.j * unit_vec.j),
2515
+                                 + (-prev_unit_vec.k * unit_vec.k)
2471 2516
                                );
2472 2517
 
2473 2518
       // NOTE: Computed without any expensive trig, sin() or acos(), by trig half angle identity of cos(theta).
@@ -2783,10 +2828,9 @@ void Planner::buffer_sync_block(TERN_(LASER_SYNCHRONOUS_M106_M107, uint8_t sync_
2783 2828
  *
2784 2829
  * Return 'false' if no segment was queued due to cleaning, cold extrusion, full queue, etc.
2785 2830
  */
2786
-bool Planner::buffer_segment(
2787
-  LOGICAL_AXIS_LIST(const_float_t e, const_float_t a, const_float_t b, const_float_t c)
2831
+bool Planner::buffer_segment(const abce_pos_t &abce
2788 2832
   OPTARG(HAS_DIST_MM_ARG, const xyze_float_t &cart_dist_mm)
2789
-  , const_feedRate_t fr_mm_s, const uint8_t extruder, const_float_t millimeters/*=0.0*/
2833
+  , const_feedRate_t fr_mm_s, const uint8_t extruder/*=active_extruder*/, const_float_t millimeters/*=0.0*/
2790 2834
 ) {
2791 2835
 
2792 2836
   // If we are cleaning, do not accept queuing of movements
@@ -2804,54 +2848,70 @@ bool Planner::buffer_segment(
2804 2848
   // Calculate target position in absolute steps
2805 2849
   const abce_long_t target = {
2806 2850
      LOGICAL_AXIS_LIST(
2807
-      int32_t(LROUND(e * settings.axis_steps_per_mm[E_AXIS_N(extruder)])),
2808
-      int32_t(LROUND(a * settings.axis_steps_per_mm[A_AXIS])),
2809
-      int32_t(LROUND(b * settings.axis_steps_per_mm[B_AXIS])),
2810
-      int32_t(LROUND(c * settings.axis_steps_per_mm[C_AXIS]))
2851
+      int32_t(LROUND(abce.e * settings.axis_steps_per_mm[E_AXIS_N(extruder)])),
2852
+      int32_t(LROUND(abce.a * settings.axis_steps_per_mm[A_AXIS])),
2853
+      int32_t(LROUND(abce.b * settings.axis_steps_per_mm[B_AXIS])),
2854
+      int32_t(LROUND(abce.c * settings.axis_steps_per_mm[C_AXIS])),
2855
+      int32_t(LROUND(abce.i * settings.axis_steps_per_mm[I_AXIS])), // FIXME (DerAndere): Multiplication by 4.0 is a work-around for issue with wrong internal steps per mm
2856
+      int32_t(LROUND(abce.j * settings.axis_steps_per_mm[J_AXIS])),
2857
+      int32_t(LROUND(abce.k * settings.axis_steps_per_mm[K_AXIS]))
2811 2858
     )
2812 2859
   };
2813 2860
 
2814 2861
   #if HAS_POSITION_FLOAT
2815
-    const xyze_pos_t target_float = LOGICAL_AXIS_ARRAY(e, a, b, c);
2862
+    const xyze_pos_t target_float = abce;
2816 2863
   #endif
2817 2864
 
2818 2865
   #if HAS_EXTRUDERS
2819 2866
     // DRYRUN prevents E moves from taking place
2820 2867
     if (DEBUGGING(DRYRUN) || TERN0(CANCEL_OBJECTS, cancelable.skipping)) {
2821 2868
       position.e = target.e;
2822
-      TERN_(HAS_POSITION_FLOAT, position_float.e = e);
2869
+      TERN_(HAS_POSITION_FLOAT, position_float.e = abce.e);
2823 2870
     }
2824 2871
   #endif
2825 2872
 
2826 2873
   /* <-- add a slash to enable
2827 2874
     SERIAL_ECHOPAIR("  buffer_segment FR:", fr_mm_s);
2828 2875
     #if IS_KINEMATIC
2829
-      SERIAL_ECHOPAIR(" A:", a);
2830
-      SERIAL_ECHOPAIR(" (", position.a);
2831
-      SERIAL_ECHOPAIR("->", target.a);
2832
-      SERIAL_ECHOPAIR(") B:", b);
2876
+      SERIAL_ECHOPAIR(" A:", abce.a, " (", position.a, "->", target.a, ") B:", abce.b);
2833 2877
     #else
2834
-      SERIAL_ECHOPAIR_P(SP_X_LBL, a);
2835
-      SERIAL_ECHOPAIR(" (", position.x);
2836
-      SERIAL_ECHOPAIR("->", target.x);
2878
+      SERIAL_ECHOPAIR_P(SP_X_LBL, abce.a);
2879
+      SERIAL_ECHOPAIR(" (", position.x, "->", target.x);
2837 2880
       SERIAL_CHAR(')');
2838
-      SERIAL_ECHOPAIR_P(SP_Y_LBL, b);
2881
+      SERIAL_ECHOPAIR_P(SP_Y_LBL, abce.b);
2839 2882
     #endif
2840
-    SERIAL_ECHOPAIR(" (", position.y);
2841
-    SERIAL_ECHOPAIR("->", target.y);
2842
-    #if ENABLED(DELTA)
2843
-      SERIAL_ECHOPAIR(") C:", c);
2844
-    #else
2883
+    SERIAL_ECHOPAIR(" (", position.y, "->", target.y);
2884
+    #if LINEAR_AXES >= ABC
2885
+      #if ENABLED(DELTA)
2886
+        SERIAL_ECHOPAIR(") C:", abce.c);
2887
+      #else
2888
+        SERIAL_CHAR(')');
2889
+        SERIAL_ECHOPAIR_P(SP_Z_LBL, abce.c);
2890
+      #endif
2891
+      SERIAL_ECHOPAIR(" (", position.z, "->", target.z);
2892
+      SERIAL_CHAR(')');
2893
+    #endif
2894
+    #if LINEAR_AXES >= 4
2895
+      SERIAL_ECHOPAIR_P(SP_I_LBL, abce.i);
2896
+      SERIAL_ECHOPAIR(" (", position.i, "->", target.i); // FIXME (DerAndere): Introduce work-around for issue with wrong internal steps per mm and feedrate for I_AXIS
2845 2897
       SERIAL_CHAR(')');
2846
-      SERIAL_ECHOPAIR_P(SP_Z_LBL, c);
2847 2898
     #endif
2848
-    SERIAL_ECHOPAIR(" (", position.z);
2849
-    SERIAL_ECHOPAIR("->", target.z);
2850
-    SERIAL_CHAR(')');
2851
-    SERIAL_ECHOPAIR_P(SP_E_LBL, e);
2852
-    SERIAL_ECHOPAIR(" (", position.e);
2853
-    SERIAL_ECHOPAIR("->", target.e);
2854
-    SERIAL_ECHOLNPGM(")");
2899
+    #if LINEAR_AXES >= 5
2900
+      SERIAL_ECHOPAIR_P(SP_J_LBL, abce.j);
2901
+      SERIAL_ECHOPAIR(" (", position.j, "->", target.j);
2902
+      SERIAL_CHAR(')');
2903
+    #endif
2904
+    #if LINEAR_AXES >= 6
2905
+      SERIAL_ECHOPAIR_P(SP_K_LBL, abce.k);
2906
+      SERIAL_ECHOPAIR(" (", position.k, "->", target.k);
2907
+      SERIAL_CHAR(')');
2908
+    #endif
2909
+    #if HAS_EXTRUDERS
2910
+      SERIAL_ECHOPAIR_P(SP_E_LBL, abce.e);
2911
+      SERIAL_ECHOLNPAIR(" (", position.e, "->", target.e, ")");
2912
+    #else
2913
+      SERIAL_EOL();
2914
+    #endif
2855 2915
   //*/
2856 2916
 
2857 2917
   // Queue the movement. Return 'false' if the move was not queued.
@@ -2874,34 +2934,34 @@ bool Planner::buffer_segment(
2874 2934
  * The target is cartesian. It's translated to
2875 2935
  * delta/scara if needed.
2876 2936
  *
2877
- *  rx,ry,rz,e   - target position in mm or degrees
2878
- *  fr_mm_s      - (target) speed of the move (mm/s)
2879
- *  extruder     - target extruder
2880
- *  millimeters  - the length of the movement, if known
2881
- *  inv_duration - the reciprocal if the duration of the movement, if known (kinematic only if feeedrate scaling is enabled)
2937
+ *  cart            - target position in mm or degrees
2938
+ *  fr_mm_s         - (target) speed of the move (mm/s)
2939
+ *  extruder        - target extruder
2940
+ *  millimeters     - the length of the movement, if known
2941
+ *  inv_duration    - the reciprocal if the duration of the movement, if known (kinematic only if feeedrate scaling is enabled)
2882 2942
  */
2883
-bool Planner::buffer_line(
2884
-  LOGICAL_AXIS_LIST(const_float_t e, const_float_t rx, const_float_t ry, const_float_t rz)
2885
-  , const feedRate_t &fr_mm_s, const uint8_t extruder, const float millimeters
2886
-  OPTARG(SCARA_FEEDRATE_SCALING, const_float_t inv_duration)
2943
+bool Planner::buffer_line(const xyze_pos_t &cart, const_feedRate_t fr_mm_s, const uint8_t extruder/*=active_extruder*/, const float millimeters/*=0.0*/
2944
+  OPTARG(SCARA_FEEDRATE_SCALING, const_float_t inv_duration/*=0.0*/)
2887 2945
 ) {
2888
-  xyze_pos_t machine = LOGICAL_AXIS_ARRAY(e, rx, ry, rz);
2946
+  xyze_pos_t machine = cart;
2889 2947
   TERN_(HAS_POSITION_MODIFIERS, apply_modifiers(machine));
2890 2948
 
2891 2949
   #if IS_KINEMATIC
2892 2950
 
2893 2951
     #if HAS_JUNCTION_DEVIATION
2894
-      const xyze_pos_t cart_dist_mm = {
2895
-        rx - position_cart.x, ry - position_cart.y,
2896
-        rz - position_cart.z, e  - position_cart.e
2897
-      };
2952
+      const xyze_pos_t cart_dist_mm = LOGICAL_AXIS_ARRAY(
2953
+        cart.e - position_cart.e,
2954
+        cart.x - position_cart.x, cart.y - position_cart.y, cart.z - position_cart.z,
2955
+        cart.i - position_cart.i, cart.j - position_cart.j, cart.j - position_cart.k
2956
+      );
2898 2957
     #else
2899
-      const xyz_pos_t cart_dist_mm = { rx - position_cart.x, ry - position_cart.y, rz - position_cart.z };
2958
+      const xyz_pos_t cart_dist_mm = LINEAR_AXIS_ARRAY(
2959
+        cart.x - position_cart.x, cart.y - position_cart.y, cart.z - position_cart.z,
2960
+        cart.i - position_cart.i, cart.j - position_cart.j, cart.j - position_cart.k
2961
+      );
2900 2962
     #endif
2901 2963
 
2902
-    float mm = millimeters;
2903
-    if (mm == 0.0)
2904
-      mm = (cart_dist_mm.x != 0.0 || cart_dist_mm.y != 0.0) ? cart_dist_mm.magnitude() : ABS(cart_dist_mm.z);
2964
+    const float mm = millimeters ?: (cart_dist_mm.x || cart_dist_mm.y) ? cart_dist_mm.magnitude() : TERN0(HAS_Z_AXIS, ABS(cart_dist_mm.z));
2905 2965
 
2906 2966
     // Cartesian XYZ to kinematic ABC, stored in global 'delta'
2907 2967
     inverse_kinematics(machine);
@@ -2915,17 +2975,12 @@ bool Planner::buffer_line(
2915 2975
     #else
2916 2976
       const feedRate_t feedrate = fr_mm_s;
2917 2977
     #endif
2918
-    if (buffer_segment(delta.a, delta.b, delta.c, machine.e
2919
-      #if HAS_JUNCTION_DEVIATION
2920
-        , cart_dist_mm
2921
-      #endif
2922
-      , feedrate, extruder, mm
2923
-    )) {
2924
-      position_cart.set(rx, ry, rz, e);
2978
+    delta.e = machine.e;
2979
+    if (buffer_segment(delta OPTARG(HAS_DIST_MM_ARG, cart_dist_mm), feedrate, extruder, mm)) {
2980
+      position_cart = cart;
2925 2981
       return true;
2926 2982
     }
2927
-    else
2928
-      return false;
2983
+    return false;
2929 2984
   #else
2930 2985
     return buffer_segment(machine, fr_mm_s, extruder, millimeters);
2931 2986
   #endif
@@ -2991,23 +3046,23 @@ bool Planner::buffer_line(
2991 3046
 #endif // DIRECT_STEPPING
2992 3047
 
2993 3048
 /**
2994
- * Directly set the planner ABC position (and stepper positions)
3049
+ * Directly set the planner ABCE position (and stepper positions)
2995 3050
  * converting mm (or angles for SCARA) into steps.
2996 3051
  *
2997
- * The provided ABC position is in machine units.
3052
+ * The provided ABCE position is in machine units.
2998 3053
  */
2999
-
3000
-void Planner::set_machine_position_mm(
3001
-  LOGICAL_AXIS_LIST(const_float_t e, const_float_t a, const_float_t b, const_float_t c)
3002
-) {
3054
+void Planner::set_machine_position_mm(const abce_pos_t &abce) {
3003 3055
   TERN_(DISTINCT_E_FACTORS, last_extruder = active_extruder);
3004
-  TERN_(HAS_POSITION_FLOAT, position_float.set(LOGICAL_AXIS_LIST(e, a, b, c)));
3056
+  TERN_(HAS_POSITION_FLOAT, position_float = abce);
3005 3057
   position.set(
3006 3058
     LOGICAL_AXIS_LIST(
3007
-      LROUND(e * settings.axis_steps_per_mm[E_AXIS_N(active_extruder)]),
3008
-      LROUND(a * settings.axis_steps_per_mm[A_AXIS]),
3009
-      LROUND(b * settings.axis_steps_per_mm[B_AXIS]),
3010
-      LROUND(c * settings.axis_steps_per_mm[C_AXIS])
3059
+      LROUND(abce.e * settings.axis_steps_per_mm[E_AXIS_N(active_extruder)]),
3060
+      LROUND(abce.a * settings.axis_steps_per_mm[A_AXIS]),
3061
+      LROUND(abce.b * settings.axis_steps_per_mm[B_AXIS]),
3062
+      LROUND(abce.c * settings.axis_steps_per_mm[C_AXIS]),
3063
+      LROUND(abce.i * settings.axis_steps_per_mm[I_AXIS]),
3064
+      LROUND(abce.j * settings.axis_steps_per_mm[J_AXIS]),
3065
+      LROUND(abce.k * settings.axis_steps_per_mm[K_AXIS])
3011 3066
     )
3012 3067
   );
3013 3068
   if (has_blocks_queued()) {
@@ -3019,15 +3074,14 @@ void Planner::set_machine_position_mm(
3019 3074
     stepper.set_position(position);
3020 3075
 }
3021 3076
 
3022
-void Planner::set_position_mm(
3023
-  LOGICAL_AXIS_LIST(const_float_t e, const_float_t rx, const_float_t ry, const_float_t rz)
3024
-) {
3025
-  xyze_pos_t machine = LOGICAL_AXIS_ARRAY(e, rx, ry, rz);
3077
+void Planner::set_position_mm(const xyze_pos_t &xyze) {
3078
+  xyze_pos_t machine = xyze;
3026 3079
   TERN_(HAS_POSITION_MODIFIERS, apply_modifiers(machine, true));
3027 3080
   #if IS_KINEMATIC
3028
-    position_cart.set(rx, ry, rz, e);
3081
+    position_cart = xyze;
3029 3082
     inverse_kinematics(machine);
3030
-    set_machine_position_mm(delta.a, delta.b, delta.c, machine.e);
3083
+    delta.e = machine.e;
3084
+    set_machine_position_mm(delta);
3031 3085
   #else
3032 3086
     set_machine_position_mm(machine);
3033 3087
   #endif
@@ -3045,7 +3099,7 @@ void Planner::set_position_mm(
3045 3099
     const float e_new = DIFF_TERN(FWRETRACT, e, fwretract.current_retract[active_extruder]);
3046 3100
     position.e = LROUND(settings.axis_steps_per_mm[axis_index] * e_new);
3047 3101
     TERN_(HAS_POSITION_FLOAT, position_float.e = e_new);
3048
-    TERN_(IS_KINEMATIC, position_cart.e = e);
3102
+    TERN_(IS_KINEMATIC, TERN_(HAS_EXTRUDERS, position_cart.e = e));
3049 3103
 
3050 3104
     if (has_blocks_queued())
3051 3105
       buffer_sync_block();
@@ -3057,15 +3111,11 @@ void Planner::set_position_mm(
3057 3111
 
3058 3112
 // Recalculate the steps/s^2 acceleration rates, based on the mm/s^2
3059 3113
 void Planner::reset_acceleration_rates() {
3060
-  #if ENABLED(DISTINCT_E_FACTORS)
3061
-    #define AXIS_CONDITION (i < E_AXIS || i == E_AXIS_N(active_extruder))
3062
-  #else
3063
-    #define AXIS_CONDITION true
3064
-  #endif
3065 3114
   uint32_t highest_rate = 1;
3066 3115
   LOOP_DISTINCT_AXES(i) {
3067 3116
     max_acceleration_steps_per_s2[i] = settings.max_acceleration_mm_per_s2[i] * settings.axis_steps_per_mm[i];
3068
-    if (AXIS_CONDITION) NOLESS(highest_rate, max_acceleration_steps_per_s2[i]);
3117
+    if (TERN1(DISTINCT_E_FACTORS, i < E_AXIS || i == E_AXIS_N(active_extruder)))
3118
+      NOLESS(highest_rate, max_acceleration_steps_per_s2[i]);
3069 3119
   }
3070 3120
   acceleration_long_cutoff = 4294967295UL / highest_rate; // 0xFFFFFFFFUL
3071 3121
   TERN_(HAS_LINEAR_E_JERK, recalculate_max_e_jerk());

+ 11
- 42
Marlin/src/module/planner.h View File

@@ -76,7 +76,9 @@
76 76
 // Feedrate for manual moves
77 77
 #ifdef MANUAL_FEEDRATE
78 78
   constexpr xyze_feedrate_t _mf = MANUAL_FEEDRATE,
79
-           manual_feedrate_mm_s = LOGICAL_AXIS_ARRAY(_mf.e / 60.0f, _mf.x / 60.0f, _mf.y / 60.0f, _mf.z / 60.0f);
79
+           manual_feedrate_mm_s = LOGICAL_AXIS_ARRAY(_mf.e / 60.0f,
80
+                                                     _mf.x / 60.0f, _mf.y / 60.0f, _mf.z / 60.0f,
81
+                                                     _mf.i / 60.0f, _mf.j / 60.0f, _mf.k / 60.0f);
80 82
 #endif
81 83
 
82 84
 #if IS_KINEMATIC && HAS_JUNCTION_DEVIATION
@@ -758,23 +760,11 @@ class Planner {
758 760
      *  extruder    - target extruder
759 761
      *  millimeters - the length of the movement, if known
760 762
      */
761
-    static bool buffer_segment(
762
-      LOGICAL_AXIS_LIST(const_float_t e, const_float_t a, const_float_t b, const_float_t c)
763
+    static bool buffer_segment(const abce_pos_t &abce
763 764
       OPTARG(HAS_DIST_MM_ARG, const xyze_float_t &cart_dist_mm)
764
-      , const_feedRate_t fr_mm_s, const uint8_t extruder, const_float_t millimeters=0.0
765
+      , const_feedRate_t fr_mm_s, const uint8_t extruder=active_extruder, const_float_t millimeters=0.0
765 766
     );
766 767
 
767
-    FORCE_INLINE static bool buffer_segment(abce_pos_t &abce
768
-      OPTARG(HAS_DIST_MM_ARG, const xyze_float_t &cart_dist_mm)
769
-      , const_feedRate_t fr_mm_s, const uint8_t extruder, const_float_t millimeters=0.0
770
-    ) {
771
-      return buffer_segment(
772
-        LOGICAL_AXIS_LIST(abce.e, abce.a, abce.b, abce.c)
773
-        OPTARG(HAS_DIST_MM_ARG, cart_dist_mm)
774
-        , fr_mm_s, extruder, millimeters
775
-      );
776
-    }
777
-
778 768
   public:
779 769
 
780 770
     /**
@@ -782,28 +772,16 @@ class Planner {
782 772
      * The target is cartesian. It's translated to
783 773
      * delta/scara if needed.
784 774
      *
785
-     *  rx,ry,rz,e   - target position in mm or degrees
775
+     *  cart         - target position in mm or degrees
786 776
      *  fr_mm_s      - (target) speed of the move (mm/s)
787 777
      *  extruder     - target extruder
788 778
      *  millimeters  - the length of the movement, if known
789 779
      *  inv_duration - the reciprocal if the duration of the movement, if known (kinematic only if feeedrate scaling is enabled)
790 780
      */
791
-    static bool buffer_line(
792
-      LOGICAL_AXIS_LIST(const_float_t e, const_float_t rx, const_float_t ry, const_float_t rz)
793
-      , const feedRate_t &fr_mm_s, const uint8_t extruder, const float millimeters=0.0
781
+    static bool buffer_line(const xyze_pos_t &cart, const_feedRate_t fr_mm_s, const uint8_t extruder=active_extruder, const float millimeters=0.0
794 782
       OPTARG(SCARA_FEEDRATE_SCALING, const_float_t inv_duration=0.0)
795 783
     );
796 784
 
797
-    FORCE_INLINE static bool buffer_line(const xyze_pos_t &cart, const_feedRate_t fr_mm_s, const uint8_t extruder, const float millimeters=0.0
798
-      OPTARG(SCARA_FEEDRATE_SCALING, const_float_t inv_duration=0.0)
799
-    ) {
800
-      return buffer_line(
801
-        LOGICAL_AXIS_LIST(cart.e, cart.x, cart.y, cart.z)
802
-        , fr_mm_s, extruder, millimeters
803
-        OPTARG(SCARA_FEEDRATE_SCALING, inv_duration)
804
-      );
805
-    }
806
-
807 785
     #if ENABLED(DIRECT_STEPPING)
808 786
       static void buffer_page(const page_idx_t page_idx, const uint8_t extruder, const uint16_t num_steps);
809 787
     #endif
@@ -821,12 +799,7 @@ class Planner {
821 799
      *
822 800
      * Clears previous speed values.
823 801
      */
824
-    static void set_position_mm(
825
-      LOGICAL_AXIS_LIST(const_float_t e, const_float_t rx, const_float_t ry, const_float_t rz)
826
-    );
827
-    FORCE_INLINE static void set_position_mm(const xyze_pos_t &cart) {
828
-      set_position_mm(LOGICAL_AXIS_LIST(cart.e, cart.x, cart.y, cart.z, cart.i, cart.j, cart.k));
829
-    }
802
+    static void set_position_mm(const xyze_pos_t &xyze);
830 803
 
831 804
     #if HAS_EXTRUDERS
832 805
       static void set_e_position_mm(const_float_t e);
@@ -838,12 +811,7 @@ class Planner {
838 811
      * The supplied position is in machine space, and no additional
839 812
      * conversions are applied.
840 813
      */
841
-    static void set_machine_position_mm(
842
-      LOGICAL_AXIS_LIST(const_float_t e, const_float_t a, const_float_t b, const_float_t c)
843
-    );
844
-    FORCE_INLINE static void set_machine_position_mm(const abce_pos_t &abce) {
845
-      set_machine_position_mm(LOGICAL_AXIS_LIST(abce.e, abce.a, abce.b, abce.c));
846
-    }
814
+    static void set_machine_position_mm(const abce_pos_t &abce);
847 815
 
848 816
     /**
849 817
      * Get an axis position according to stepper position(s)
@@ -854,7 +822,8 @@ class Planner {
854 822
     static inline abce_pos_t get_axis_positions_mm() {
855 823
       const abce_pos_t out = LOGICAL_AXIS_ARRAY(
856 824
         get_axis_position_mm(E_AXIS),
857
-        get_axis_position_mm(A_AXIS), get_axis_position_mm(B_AXIS), get_axis_position_mm(C_AXIS)
825
+        get_axis_position_mm(A_AXIS), get_axis_position_mm(B_AXIS), get_axis_position_mm(C_AXIS),
826
+        get_axis_position_mm(I_AXIS), get_axis_position_mm(J_AXIS), get_axis_position_mm(K_AXIS)
858 827
       );
859 828
       return out;
860 829
     }

+ 7
- 3
Marlin/src/module/planner_bezier.cpp View File

@@ -182,9 +182,13 @@ void cubic_b_spline(
182 182
 
183 183
     // Compute and send new position
184 184
     xyze_pos_t new_bez = LOGICAL_AXIS_ARRAY(
185
-      interp(position.e, target.e, t),  // FIXME. These two are wrong, since the parameter t is not linear in the distance.
186
-      new_pos0, new_pos1,
187
-      interp(position.z, target.z, t)
185
+      interp(position.e, target.e, t),  // FIXME. Wrong, since t is not linear in the distance.
186
+      new_pos0,
187
+      new_pos1,
188
+      interp(position.z, target.z, t),  // FIXME. Wrong, since t is not linear in the distance.
189
+      interp(position.i, target.i, t),  // FIXME. Wrong, since t is not linear in the distance.
190
+      interp(position.j, target.j, t),  // FIXME. Wrong, since t is not linear in the distance.
191
+      interp(position.k, target.k, t)   // FIXME. Wrong, since t is not linear in the distance.
188 192
     );
189 193
     apply_motion_limits(new_bez);
190 194
     bez_target = new_bez;

+ 10
- 10
Marlin/src/module/probe.h View File

@@ -110,7 +110,7 @@ public:
110 110
 
111 111
   #else
112 112
 
113
-    static constexpr xyz_pos_t offset = xyz_pos_t({ 0, 0, 0 }); // See #16767
113
+    static constexpr xyz_pos_t offset = xyz_pos_t(LINEAR_AXIS_ARRAY(0, 0, 0, 0, 0, 0)); // See #16767
114 114
 
115 115
     static bool set_deployed(const bool) { return false; }
116 116
 
@@ -222,20 +222,20 @@ public:
222 222
           #define VALIDATE_PROBE_PT(N) static_assert(Probe::build_time::can_reach(xy_pos_t{PROBE_PT_##N##_X, PROBE_PT_##N##_Y}), \
223 223
             "PROBE_PT_" STRINGIFY(N) "_(X|Y) is unreachable using default NOZZLE_TO_PROBE_OFFSET and PROBING_MARGIN");
224 224
           VALIDATE_PROBE_PT(1); VALIDATE_PROBE_PT(2); VALIDATE_PROBE_PT(3);
225
-          points[0].set(PROBE_PT_1_X, PROBE_PT_1_Y);
226
-          points[1].set(PROBE_PT_2_X, PROBE_PT_2_Y);
227
-          points[2].set(PROBE_PT_3_X, PROBE_PT_3_Y);
225
+          points[0] = xy_float_t({ PROBE_PT_1_X, PROBE_PT_1_Y });
226
+          points[1] = xy_float_t({ PROBE_PT_2_X, PROBE_PT_2_Y });
227
+          points[2] = xy_float_t({ PROBE_PT_3_X, PROBE_PT_3_Y });
228 228
         #else
229 229
           #if IS_KINEMATIC
230 230
             constexpr float SIN0 = 0.0, SIN120 = 0.866025, SIN240 = -0.866025,
231 231
                             COS0 = 1.0, COS120 = -0.5    , COS240 = -0.5;
232
-            points[0].set((X_CENTER) + probe_radius() * COS0,   (Y_CENTER) + probe_radius() * SIN0);
233
-            points[1].set((X_CENTER) + probe_radius() * COS120, (Y_CENTER) + probe_radius() * SIN120);
234
-            points[2].set((X_CENTER) + probe_radius() * COS240, (Y_CENTER) + probe_radius() * SIN240);
232
+            points[0] = xy_float_t({ (X_CENTER) + probe_radius() * COS0,   (Y_CENTER) + probe_radius() * SIN0 });
233
+            points[1] = xy_float_t({ (X_CENTER) + probe_radius() * COS120, (Y_CENTER) + probe_radius() * SIN120 });
234
+            points[2] = xy_float_t({ (X_CENTER) + probe_radius() * COS240, (Y_CENTER) + probe_radius() * SIN240 });
235 235
           #else
236
-            points[0].set(min_x(), min_y());
237
-            points[1].set(max_x(), min_y());
238
-            points[2].set((min_x() + max_x()) / 2, max_y());
236
+            points[0] = xy_float_t({ min_x(), min_y() });
237
+            points[1] = xy_float_t({ max_x(), min_y() });
238
+            points[2] = xy_float_t({ (min_x() + max_x()) / 2, max_y() });
239 239
           #endif
240 240
         #endif
241 241
       }

+ 265
- 310
Marlin/src/module/settings.cpp View File

@@ -168,10 +168,14 @@
168 168
   void M554_report();
169 169
 #endif
170 170
 
171
-typedef struct { uint16_t LINEAR_AXIS_LIST(X, Y, Z), X2, Y2, Z2, Z3, Z4, E0, E1, E2, E3, E4, E5, E6, E7; } tmc_stepper_current_t;
172
-typedef struct { uint32_t LINEAR_AXIS_LIST(X, Y, Z), X2, Y2, Z2, Z3, Z4, E0, E1, E2, E3, E4, E5, E6, E7; } tmc_hybrid_threshold_t;
173
-typedef struct {  int16_t LINEAR_AXIS_LIST(X, Y, Z), X2, Y2, Z2, Z3, Z4;                                 } tmc_sgt_t;
174
-typedef struct {     bool LINEAR_AXIS_LIST(X, Y, Z), X2, Y2, Z2, Z3, Z4, E0, E1, E2, E3, E4, E5, E6, E7; } tmc_stealth_enabled_t;
171
+#define _EN_ITEM(N) , E##N
172
+
173
+typedef struct { uint16_t LINEAR_AXIS_LIST(X, Y, Z, I, J, K), X2, Y2, Z2, Z3, Z4 REPEAT(E_STEPPERS, _EN_ITEM); } tmc_stepper_current_t;
174
+typedef struct { uint32_t LINEAR_AXIS_LIST(X, Y, Z, I, J, K), X2, Y2, Z2, Z3, Z4 REPEAT(E_STEPPERS, _EN_ITEM); } tmc_hybrid_threshold_t;
175
+typedef struct {  int16_t LINEAR_AXIS_LIST(X, Y, Z, I, J, K), X2, Y2, Z2, Z3, Z4;                              } tmc_sgt_t;
176
+typedef struct {     bool LINEAR_AXIS_LIST(X, Y, Z, I, J, K), X2, Y2, Z2, Z3, Z4 REPEAT(E_STEPPERS, _EN_ITEM); } tmc_stealth_enabled_t;
177
+
178
+#undef _EN_ITEM
175 179
 
176 180
 // Limit an index to an array size
177 181
 #define ALIM(I,ARR) _MIN(I, (signed)COUNT(ARR) - 1)
@@ -387,7 +391,7 @@ typedef struct SettingsDataStruct {
387 391
   #ifndef MOTOR_CURRENT_COUNT
388 392
     #define MOTOR_CURRENT_COUNT LINEAR_AXES
389 393
   #endif
390
-  uint32_t motor_current_setting[MOTOR_CURRENT_COUNT];  // M907 X Z E
394
+  uint32_t motor_current_setting[MOTOR_CURRENT_COUNT];  // M907 X Z E ...
391 395
 
392 396
   //
393 397
   // CNC_COORDINATE_SYSTEMS
@@ -654,7 +658,7 @@ void MarlinSettings::postprocess() {
654 658
           EEPROM_WRITE(dummyf);
655 659
         #endif
656 660
       #else
657
-        const xyze_pos_t planner_max_jerk = LOGICAL_AXIS_ARRAY(float(DEFAULT_EJERK), 10, 10, 0.4);
661
+        const xyze_pos_t planner_max_jerk = LOGICAL_AXIS_ARRAY(float(DEFAULT_EJERK), 10, 10, 0.4, 0.4, 0.4, 0.4);
658 662
         EEPROM_WRITE(planner_max_jerk);
659 663
       #endif
660 664
 
@@ -1087,6 +1091,15 @@ void MarlinSettings::postprocess() {
1087 1091
         #if AXIS_IS_TMC(Z)
1088 1092
           tmc_stepper_current.Z = stepperZ.getMilliamps();
1089 1093
         #endif
1094
+        #if AXIS_IS_TMC(I)
1095
+          tmc_stepper_current.I = stepperI.getMilliamps();
1096
+        #endif
1097
+        #if AXIS_IS_TMC(J)
1098
+          tmc_stepper_current.J = stepperJ.getMilliamps();
1099
+        #endif
1100
+        #if AXIS_IS_TMC(K)
1101
+          tmc_stepper_current.K = stepperK.getMilliamps();
1102
+        #endif
1090 1103
         #if AXIS_IS_TMC(X2)
1091 1104
           tmc_stepper_current.X2 = stepperX2.getMilliamps();
1092 1105
         #endif
@@ -1138,61 +1151,33 @@ void MarlinSettings::postprocess() {
1138 1151
 
1139 1152
       #if ENABLED(HYBRID_THRESHOLD)
1140 1153
         tmc_hybrid_threshold_t tmc_hybrid_threshold{0};
1141
-        #if AXIS_HAS_STEALTHCHOP(X)
1142
-          tmc_hybrid_threshold.X = stepperX.get_pwm_thrs();
1143
-        #endif
1144
-        #if AXIS_HAS_STEALTHCHOP(Y)
1145
-          tmc_hybrid_threshold.Y = stepperY.get_pwm_thrs();
1146
-        #endif
1147
-        #if AXIS_HAS_STEALTHCHOP(Z)
1148
-          tmc_hybrid_threshold.Z = stepperZ.get_pwm_thrs();
1149
-        #endif
1150
-        #if AXIS_HAS_STEALTHCHOP(X2)
1151
-          tmc_hybrid_threshold.X2 = stepperX2.get_pwm_thrs();
1152
-        #endif
1153
-        #if AXIS_HAS_STEALTHCHOP(Y2)
1154
-          tmc_hybrid_threshold.Y2 = stepperY2.get_pwm_thrs();
1155
-        #endif
1156
-        #if AXIS_HAS_STEALTHCHOP(Z2)
1157
-          tmc_hybrid_threshold.Z2 = stepperZ2.get_pwm_thrs();
1158
-        #endif
1159
-        #if AXIS_HAS_STEALTHCHOP(Z3)
1160
-          tmc_hybrid_threshold.Z3 = stepperZ3.get_pwm_thrs();
1161
-        #endif
1162
-        #if AXIS_HAS_STEALTHCHOP(Z4)
1163
-          tmc_hybrid_threshold.Z4 = stepperZ4.get_pwm_thrs();
1164
-        #endif
1165
-        #if AXIS_HAS_STEALTHCHOP(E0)
1166
-          tmc_hybrid_threshold.E0 = stepperE0.get_pwm_thrs();
1167
-        #endif
1168
-        #if AXIS_HAS_STEALTHCHOP(E1)
1169
-          tmc_hybrid_threshold.E1 = stepperE1.get_pwm_thrs();
1170
-        #endif
1171
-        #if AXIS_HAS_STEALTHCHOP(E2)
1172
-          tmc_hybrid_threshold.E2 = stepperE2.get_pwm_thrs();
1173
-        #endif
1174
-        #if AXIS_HAS_STEALTHCHOP(E3)
1175
-          tmc_hybrid_threshold.E3 = stepperE3.get_pwm_thrs();
1176
-        #endif
1177
-        #if AXIS_HAS_STEALTHCHOP(E4)
1178
-          tmc_hybrid_threshold.E4 = stepperE4.get_pwm_thrs();
1179
-        #endif
1180
-        #if AXIS_HAS_STEALTHCHOP(E5)
1181
-          tmc_hybrid_threshold.E5 = stepperE5.get_pwm_thrs();
1182
-        #endif
1183
-        #if AXIS_HAS_STEALTHCHOP(E6)
1184
-          tmc_hybrid_threshold.E6 = stepperE6.get_pwm_thrs();
1185
-        #endif
1186
-        #if AXIS_HAS_STEALTHCHOP(E7)
1187
-          tmc_hybrid_threshold.E7 = stepperE7.get_pwm_thrs();
1188
-        #endif
1154
+        TERN_(X_HAS_STEALTHCHOP,  tmc_hybrid_threshold.X =  stepperX.get_pwm_thrs());
1155
+        TERN_(Y_HAS_STEALTHCHOP,  tmc_hybrid_threshold.Y =  stepperY.get_pwm_thrs());
1156
+        TERN_(Z_HAS_STEALTHCHOP,  tmc_hybrid_threshold.Z =  stepperZ.get_pwm_thrs());
1157
+        TERN_(I_HAS_STEALTHCHOP,  tmc_hybrid_threshold.I =  stepperI.get_pwm_thrs());
1158
+        TERN_(J_HAS_STEALTHCHOP,  tmc_hybrid_threshold.J =  stepperJ.get_pwm_thrs());
1159
+        TERN_(K_HAS_STEALTHCHOP,  tmc_hybrid_threshold.K =  stepperK.get_pwm_thrs());
1160
+        TERN_(X2_HAS_STEALTHCHOP, tmc_hybrid_threshold.X2 = stepperX2.get_pwm_thrs());
1161
+        TERN_(Y2_HAS_STEALTHCHOP, tmc_hybrid_threshold.Y2 = stepperY2.get_pwm_thrs());
1162
+        TERN_(Z2_HAS_STEALTHCHOP, tmc_hybrid_threshold.Z2 = stepperZ2.get_pwm_thrs());
1163
+        TERN_(Z3_HAS_STEALTHCHOP, tmc_hybrid_threshold.Z3 = stepperZ3.get_pwm_thrs());
1164
+        TERN_(Z4_HAS_STEALTHCHOP, tmc_hybrid_threshold.Z4 = stepperZ4.get_pwm_thrs());
1165
+        TERN_(E0_HAS_STEALTHCHOP, tmc_hybrid_threshold.E0 = stepperE0.get_pwm_thrs());
1166
+        TERN_(E1_HAS_STEALTHCHOP, tmc_hybrid_threshold.E1 = stepperE1.get_pwm_thrs());
1167
+        TERN_(E2_HAS_STEALTHCHOP, tmc_hybrid_threshold.E2 = stepperE2.get_pwm_thrs());
1168
+        TERN_(E3_HAS_STEALTHCHOP, tmc_hybrid_threshold.E3 = stepperE3.get_pwm_thrs());
1169
+        TERN_(E4_HAS_STEALTHCHOP, tmc_hybrid_threshold.E4 = stepperE4.get_pwm_thrs());
1170
+        TERN_(E5_HAS_STEALTHCHOP, tmc_hybrid_threshold.E5 = stepperE5.get_pwm_thrs());
1171
+        TERN_(E6_HAS_STEALTHCHOP, tmc_hybrid_threshold.E6 = stepperE6.get_pwm_thrs());
1172
+        TERN_(E7_HAS_STEALTHCHOP, tmc_hybrid_threshold.E7 = stepperE7.get_pwm_thrs());
1189 1173
       #else
1174
+        #define _EN_ITEM(N) , .E##N =  30
1190 1175
         const tmc_hybrid_threshold_t tmc_hybrid_threshold = {
1191
-          LINEAR_AXIS_LIST(.X = 100, .Y = 100, .Z = 3),
1192
-          .X2 = 100, .Y2 = 100, .Z2 =   3, .Z3 =   3, .Z4 = 3,
1193
-          .E0 =  30, .E1 =  30, .E2 =  30, .E3 =  30,
1194
-          .E4 =  30, .E5 =  30, .E6 =  30, .E7 =  30
1176
+          LINEAR_AXIS_LIST(.X = 100, .Y = 100, .Z = 3, .I = 3, .J = 3, .K = 3),
1177
+          .X2 = 100, .Y2 = 100, .Z2 = 3, .Z3 = 3, .Z4 = 3
1178
+          REPEAT(EXTRUDERS, _EN_ITEM)
1195 1179
         };
1180
+        #undef _EN_ITEM
1196 1181
       #endif
1197 1182
       EEPROM_WRITE(tmc_hybrid_threshold);
1198 1183
     }
@@ -1203,11 +1188,16 @@ void MarlinSettings::postprocess() {
1203 1188
     {
1204 1189
       tmc_sgt_t tmc_sgt{0};
1205 1190
       #if USE_SENSORLESS
1206
-        TERN_(X_SENSORLESS,  tmc_sgt.X  = stepperX.homing_threshold());
1191
+        LINEAR_AXIS_CODE(
1192
+          TERN_(X_SENSORLESS, tmc_sgt.X = stepperX.homing_threshold()),
1193
+          TERN_(Y_SENSORLESS, tmc_sgt.Y = stepperY.homing_threshold()),
1194
+          TERN_(Z_SENSORLESS, tmc_sgt.Z = stepperZ.homing_threshold()),
1195
+          TERN_(I_SENSORLESS, tmc_sgt.I = stepperI.homing_threshold()),
1196
+          TERN_(J_SENSORLESS, tmc_sgt.J = stepperJ.homing_threshold()),
1197
+          TERN_(K_SENSORLESS, tmc_sgt.K = stepperK.homing_threshold())
1198
+        );
1207 1199
         TERN_(X2_SENSORLESS, tmc_sgt.X2 = stepperX2.homing_threshold());
1208
-        TERN_(Y_SENSORLESS,  tmc_sgt.Y  = stepperY.homing_threshold());
1209 1200
         TERN_(Y2_SENSORLESS, tmc_sgt.Y2 = stepperY2.homing_threshold());
1210
-        TERN_(Z_SENSORLESS,  tmc_sgt.Z  = stepperZ.homing_threshold());
1211 1201
         TERN_(Z2_SENSORLESS, tmc_sgt.Z2 = stepperZ2.homing_threshold());
1212 1202
         TERN_(Z3_SENSORLESS, tmc_sgt.Z3 = stepperZ3.homing_threshold());
1213 1203
         TERN_(Z4_SENSORLESS, tmc_sgt.Z4 = stepperZ4.homing_threshold());
@@ -1222,54 +1212,25 @@ void MarlinSettings::postprocess() {
1222 1212
       _FIELD_TEST(tmc_stealth_enabled);
1223 1213
 
1224 1214
       tmc_stealth_enabled_t tmc_stealth_enabled = { false };
1225
-      #if AXIS_HAS_STEALTHCHOP(X)
1226
-        tmc_stealth_enabled.X = stepperX.get_stored_stealthChop();
1227
-      #endif
1228
-      #if AXIS_HAS_STEALTHCHOP(Y)
1229
-        tmc_stealth_enabled.Y = stepperY.get_stored_stealthChop();
1230
-      #endif
1231
-      #if AXIS_HAS_STEALTHCHOP(Z)
1232
-        tmc_stealth_enabled.Z = stepperZ.get_stored_stealthChop();
1233
-      #endif
1234
-      #if AXIS_HAS_STEALTHCHOP(X2)
1235
-        tmc_stealth_enabled.X2 = stepperX2.get_stored_stealthChop();
1236
-      #endif
1237
-      #if AXIS_HAS_STEALTHCHOP(Y2)
1238
-        tmc_stealth_enabled.Y2 = stepperY2.get_stored_stealthChop();
1239
-      #endif
1240
-      #if AXIS_HAS_STEALTHCHOP(Z2)
1241
-        tmc_stealth_enabled.Z2 = stepperZ2.get_stored_stealthChop();
1242
-      #endif
1243
-      #if AXIS_HAS_STEALTHCHOP(Z3)
1244
-        tmc_stealth_enabled.Z3 = stepperZ3.get_stored_stealthChop();
1245
-      #endif
1246
-      #if AXIS_HAS_STEALTHCHOP(Z4)
1247
-        tmc_stealth_enabled.Z4 = stepperZ4.get_stored_stealthChop();
1248
-      #endif
1249
-      #if AXIS_HAS_STEALTHCHOP(E0)
1250
-        tmc_stealth_enabled.E0 = stepperE0.get_stored_stealthChop();
1251
-      #endif
1252
-      #if AXIS_HAS_STEALTHCHOP(E1)
1253
-        tmc_stealth_enabled.E1 = stepperE1.get_stored_stealthChop();
1254
-      #endif
1255
-      #if AXIS_HAS_STEALTHCHOP(E2)
1256
-        tmc_stealth_enabled.E2 = stepperE2.get_stored_stealthChop();
1257
-      #endif
1258
-      #if AXIS_HAS_STEALTHCHOP(E3)
1259
-        tmc_stealth_enabled.E3 = stepperE3.get_stored_stealthChop();
1260
-      #endif
1261
-      #if AXIS_HAS_STEALTHCHOP(E4)
1262
-        tmc_stealth_enabled.E4 = stepperE4.get_stored_stealthChop();
1263
-      #endif
1264
-      #if AXIS_HAS_STEALTHCHOP(E5)
1265
-        tmc_stealth_enabled.E5 = stepperE5.get_stored_stealthChop();
1266
-      #endif
1267
-      #if AXIS_HAS_STEALTHCHOP(E6)
1268
-        tmc_stealth_enabled.E6 = stepperE6.get_stored_stealthChop();
1269
-      #endif
1270
-      #if AXIS_HAS_STEALTHCHOP(E7)
1271
-        tmc_stealth_enabled.E7 = stepperE7.get_stored_stealthChop();
1272
-      #endif
1215
+      TERN_(X_HAS_STEALTHCHOP,  tmc_stealth_enabled.X  = stepperX.get_stored_stealthChop());
1216
+      TERN_(Y_HAS_STEALTHCHOP,  tmc_stealth_enabled.Y  = stepperY.get_stored_stealthChop());
1217
+      TERN_(Z_HAS_STEALTHCHOP,  tmc_stealth_enabled.Z  = stepperZ.get_stored_stealthChop());
1218
+      TERN_(I_HAS_STEALTHCHOP,  tmc_stealth_enabled.I  = stepperI.get_stored_stealthChop());
1219
+      TERN_(J_HAS_STEALTHCHOP,  tmc_stealth_enabled.J  = stepperJ.get_stored_stealthChop());
1220
+      TERN_(K_HAS_STEALTHCHOP,  tmc_stealth_enabled.K  = stepperK.get_stored_stealthChop());
1221
+      TERN_(X2_HAS_STEALTHCHOP, tmc_stealth_enabled.X2 = stepperX2.get_stored_stealthChop());
1222
+      TERN_(Y2_HAS_STEALTHCHOP, tmc_stealth_enabled.Y2 = stepperY2.get_stored_stealthChop());
1223
+      TERN_(Z2_HAS_STEALTHCHOP, tmc_stealth_enabled.Z2 = stepperZ2.get_stored_stealthChop());
1224
+      TERN_(Z3_HAS_STEALTHCHOP, tmc_stealth_enabled.Z3 = stepperZ3.get_stored_stealthChop());
1225
+      TERN_(Z4_HAS_STEALTHCHOP, tmc_stealth_enabled.Z4 = stepperZ4.get_stored_stealthChop());
1226
+      TERN_(E0_HAS_STEALTHCHOP, tmc_stealth_enabled.E0 = stepperE0.get_stored_stealthChop());
1227
+      TERN_(E1_HAS_STEALTHCHOP, tmc_stealth_enabled.E1 = stepperE1.get_stored_stealthChop());
1228
+      TERN_(E2_HAS_STEALTHCHOP, tmc_stealth_enabled.E2 = stepperE2.get_stored_stealthChop());
1229
+      TERN_(E3_HAS_STEALTHCHOP, tmc_stealth_enabled.E3 = stepperE3.get_stored_stealthChop());
1230
+      TERN_(E4_HAS_STEALTHCHOP, tmc_stealth_enabled.E4 = stepperE4.get_stored_stealthChop());
1231
+      TERN_(E5_HAS_STEALTHCHOP, tmc_stealth_enabled.E5 = stepperE5.get_stored_stealthChop());
1232
+      TERN_(E6_HAS_STEALTHCHOP, tmc_stealth_enabled.E6 = stepperE6.get_stored_stealthChop());
1233
+      TERN_(E7_HAS_STEALTHCHOP, tmc_stealth_enabled.E7 = stepperE7.get_stored_stealthChop());
1273 1234
       EEPROM_WRITE(tmc_stealth_enabled);
1274 1235
     }
1275 1236
 
@@ -1992,6 +1953,15 @@ void MarlinSettings::postprocess() {
1992 1953
             #if AXIS_IS_TMC(Z4)
1993 1954
               SET_CURR(Z4);
1994 1955
             #endif
1956
+            #if AXIS_IS_TMC(I)
1957
+              SET_CURR(I);
1958
+            #endif
1959
+            #if AXIS_IS_TMC(J)
1960
+              SET_CURR(J);
1961
+            #endif
1962
+            #if AXIS_IS_TMC(K)
1963
+              SET_CURR(K);
1964
+            #endif
1995 1965
             #if AXIS_IS_TMC(E0)
1996 1966
               SET_CURR(E0);
1997 1967
             #endif
@@ -2028,54 +1998,25 @@ void MarlinSettings::postprocess() {
2028 1998
 
2029 1999
         #if ENABLED(HYBRID_THRESHOLD)
2030 2000
           if (!validating) {
2031
-            #if AXIS_HAS_STEALTHCHOP(X)
2032
-              stepperX.set_pwm_thrs(tmc_hybrid_threshold.X);
2033
-            #endif
2034
-            #if AXIS_HAS_STEALTHCHOP(Y)
2035
-              stepperY.set_pwm_thrs(tmc_hybrid_threshold.Y);
2036
-            #endif
2037
-            #if AXIS_HAS_STEALTHCHOP(Z)
2038
-              stepperZ.set_pwm_thrs(tmc_hybrid_threshold.Z);
2039
-            #endif
2040
-            #if AXIS_HAS_STEALTHCHOP(X2)
2041
-              stepperX2.set_pwm_thrs(tmc_hybrid_threshold.X2);
2042
-            #endif
2043
-            #if AXIS_HAS_STEALTHCHOP(Y2)
2044
-              stepperY2.set_pwm_thrs(tmc_hybrid_threshold.Y2);
2045
-            #endif
2046
-            #if AXIS_HAS_STEALTHCHOP(Z2)
2047
-              stepperZ2.set_pwm_thrs(tmc_hybrid_threshold.Z2);
2048
-            #endif
2049
-            #if AXIS_HAS_STEALTHCHOP(Z3)
2050
-              stepperZ3.set_pwm_thrs(tmc_hybrid_threshold.Z3);
2051
-            #endif
2052
-            #if AXIS_HAS_STEALTHCHOP(Z4)
2053
-              stepperZ4.set_pwm_thrs(tmc_hybrid_threshold.Z4);
2054
-            #endif
2055
-            #if AXIS_HAS_STEALTHCHOP(E0)
2056
-              stepperE0.set_pwm_thrs(tmc_hybrid_threshold.E0);
2057
-            #endif
2058
-            #if AXIS_HAS_STEALTHCHOP(E1)
2059
-              stepperE1.set_pwm_thrs(tmc_hybrid_threshold.E1);
2060
-            #endif
2061
-            #if AXIS_HAS_STEALTHCHOP(E2)
2062
-              stepperE2.set_pwm_thrs(tmc_hybrid_threshold.E2);
2063
-            #endif
2064
-            #if AXIS_HAS_STEALTHCHOP(E3)
2065
-              stepperE3.set_pwm_thrs(tmc_hybrid_threshold.E3);
2066
-            #endif
2067
-            #if AXIS_HAS_STEALTHCHOP(E4)
2068
-              stepperE4.set_pwm_thrs(tmc_hybrid_threshold.E4);
2069
-            #endif
2070
-            #if AXIS_HAS_STEALTHCHOP(E5)
2071
-              stepperE5.set_pwm_thrs(tmc_hybrid_threshold.E5);
2072
-            #endif
2073
-            #if AXIS_HAS_STEALTHCHOP(E6)
2074
-              stepperE6.set_pwm_thrs(tmc_hybrid_threshold.E6);
2075
-            #endif
2076
-            #if AXIS_HAS_STEALTHCHOP(E7)
2077
-              stepperE7.set_pwm_thrs(tmc_hybrid_threshold.E7);
2078
-            #endif
2001
+            TERN_(X_HAS_STEALTHCHOP,  stepperX.set_pwm_thrs(tmc_hybrid_threshold.X));
2002
+            TERN_(Y_HAS_STEALTHCHOP,  stepperY.set_pwm_thrs(tmc_hybrid_threshold.Y));
2003
+            TERN_(Z_HAS_STEALTHCHOP,  stepperZ.set_pwm_thrs(tmc_hybrid_threshold.Z));
2004
+            TERN_(X2_HAS_STEALTHCHOP, stepperX2.set_pwm_thrs(tmc_hybrid_threshold.X2));
2005
+            TERN_(Y2_HAS_STEALTHCHOP, stepperY2.set_pwm_thrs(tmc_hybrid_threshold.Y2));
2006
+            TERN_(Z2_HAS_STEALTHCHOP, stepperZ2.set_pwm_thrs(tmc_hybrid_threshold.Z2));
2007
+            TERN_(Z3_HAS_STEALTHCHOP, stepperZ3.set_pwm_thrs(tmc_hybrid_threshold.Z3));
2008
+            TERN_(Z4_HAS_STEALTHCHOP, stepperZ4.set_pwm_thrs(tmc_hybrid_threshold.Z4));
2009
+            TERN_(I_HAS_STEALTHCHOP,  stepperI.set_pwm_thrs(tmc_hybrid_threshold.I));
2010
+            TERN_(J_HAS_STEALTHCHOP,  stepperJ.set_pwm_thrs(tmc_hybrid_threshold.J));
2011
+            TERN_(K_HAS_STEALTHCHOP,  stepperK.set_pwm_thrs(tmc_hybrid_threshold.K));
2012
+            TERN_(E0_HAS_STEALTHCHOP, stepperE0.set_pwm_thrs(tmc_hybrid_threshold.E0));
2013
+            TERN_(E1_HAS_STEALTHCHOP, stepperE1.set_pwm_thrs(tmc_hybrid_threshold.E1));
2014
+            TERN_(E2_HAS_STEALTHCHOP, stepperE2.set_pwm_thrs(tmc_hybrid_threshold.E2));
2015
+            TERN_(E3_HAS_STEALTHCHOP, stepperE3.set_pwm_thrs(tmc_hybrid_threshold.E3));
2016
+            TERN_(E4_HAS_STEALTHCHOP, stepperE4.set_pwm_thrs(tmc_hybrid_threshold.E4));
2017
+            TERN_(E5_HAS_STEALTHCHOP, stepperE5.set_pwm_thrs(tmc_hybrid_threshold.E5));
2018
+            TERN_(E6_HAS_STEALTHCHOP, stepperE6.set_pwm_thrs(tmc_hybrid_threshold.E6));
2019
+            TERN_(E7_HAS_STEALTHCHOP, stepperE7.set_pwm_thrs(tmc_hybrid_threshold.E7));
2079 2020
           }
2080 2021
         #endif
2081 2022
       }
@@ -2089,11 +2030,16 @@ void MarlinSettings::postprocess() {
2089 2030
         EEPROM_READ(tmc_sgt);
2090 2031
         #if USE_SENSORLESS
2091 2032
           if (!validating) {
2092
-            TERN_(X_SENSORLESS,  stepperX.homing_threshold(tmc_sgt.X));
2033
+            LINEAR_AXIS_CODE(
2034
+              TERN_(X_SENSORLESS, stepperX.homing_threshold(tmc_sgt.X)),
2035
+              TERN_(Y_SENSORLESS, stepperY.homing_threshold(tmc_sgt.Y)),
2036
+              TERN_(Z_SENSORLESS, stepperZ.homing_threshold(tmc_sgt.Z)),
2037
+              TERN_(I_SENSORLESS, stepperI.homing_threshold(tmc_sgt.I)),
2038
+              TERN_(J_SENSORLESS, stepperJ.homing_threshold(tmc_sgt.J)),
2039
+              TERN_(K_SENSORLESS, stepperK.homing_threshold(tmc_sgt.K))
2040
+            );
2093 2041
             TERN_(X2_SENSORLESS, stepperX2.homing_threshold(tmc_sgt.X2));
2094
-            TERN_(Y_SENSORLESS,  stepperY.homing_threshold(tmc_sgt.Y));
2095 2042
             TERN_(Y2_SENSORLESS, stepperY2.homing_threshold(tmc_sgt.Y2));
2096
-            TERN_(Z_SENSORLESS,  stepperZ.homing_threshold(tmc_sgt.Z));
2097 2043
             TERN_(Z2_SENSORLESS, stepperZ2.homing_threshold(tmc_sgt.Z2));
2098 2044
             TERN_(Z3_SENSORLESS, stepperZ3.homing_threshold(tmc_sgt.Z3));
2099 2045
             TERN_(Z4_SENSORLESS, stepperZ4.homing_threshold(tmc_sgt.Z4));
@@ -2112,54 +2058,25 @@ void MarlinSettings::postprocess() {
2112 2058
 
2113 2059
           #define SET_STEPPING_MODE(ST) stepper##ST.stored.stealthChop_enabled = tmc_stealth_enabled.ST; stepper##ST.refresh_stepping_mode();
2114 2060
           if (!validating) {
2115
-            #if AXIS_HAS_STEALTHCHOP(X)
2116
-              SET_STEPPING_MODE(X);
2117
-            #endif
2118
-            #if AXIS_HAS_STEALTHCHOP(Y)
2119
-              SET_STEPPING_MODE(Y);
2120
-            #endif
2121
-            #if AXIS_HAS_STEALTHCHOP(Z)
2122
-              SET_STEPPING_MODE(Z);
2123
-            #endif
2124
-            #if AXIS_HAS_STEALTHCHOP(X2)
2125
-              SET_STEPPING_MODE(X2);
2126
-            #endif
2127
-            #if AXIS_HAS_STEALTHCHOP(Y2)
2128
-              SET_STEPPING_MODE(Y2);
2129
-            #endif
2130
-            #if AXIS_HAS_STEALTHCHOP(Z2)
2131
-              SET_STEPPING_MODE(Z2);
2132
-            #endif
2133
-            #if AXIS_HAS_STEALTHCHOP(Z3)
2134
-              SET_STEPPING_MODE(Z3);
2135
-            #endif
2136
-            #if AXIS_HAS_STEALTHCHOP(Z4)
2137
-              SET_STEPPING_MODE(Z4);
2138
-            #endif
2139
-            #if AXIS_HAS_STEALTHCHOP(E0)
2140
-              SET_STEPPING_MODE(E0);
2141
-            #endif
2142
-            #if AXIS_HAS_STEALTHCHOP(E1)
2143
-              SET_STEPPING_MODE(E1);
2144
-            #endif
2145
-            #if AXIS_HAS_STEALTHCHOP(E2)
2146
-              SET_STEPPING_MODE(E2);
2147
-            #endif
2148
-            #if AXIS_HAS_STEALTHCHOP(E3)
2149
-              SET_STEPPING_MODE(E3);
2150
-            #endif
2151
-            #if AXIS_HAS_STEALTHCHOP(E4)
2152
-              SET_STEPPING_MODE(E4);
2153
-            #endif
2154
-            #if AXIS_HAS_STEALTHCHOP(E5)
2155
-              SET_STEPPING_MODE(E5);
2156
-            #endif
2157
-            #if AXIS_HAS_STEALTHCHOP(E6)
2158
-              SET_STEPPING_MODE(E6);
2159
-            #endif
2160
-            #if AXIS_HAS_STEALTHCHOP(E7)
2161
-              SET_STEPPING_MODE(E7);
2162
-            #endif
2061
+            TERN_(X_HAS_STEALTHCHOP,  SET_STEPPING_MODE(X));
2062
+            TERN_(Y_HAS_STEALTHCHOP,  SET_STEPPING_MODE(Y));
2063
+            TERN_(Z_HAS_STEALTHCHOP,  SET_STEPPING_MODE(Z));
2064
+            TERN_(I_HAS_STEALTHCHOP,  SET_STEPPING_MODE(I));
2065
+            TERN_(J_HAS_STEALTHCHOP,  SET_STEPPING_MODE(J));
2066
+            TERN_(K_HAS_STEALTHCHOP,  SET_STEPPING_MODE(K));
2067
+            TERN_(X2_HAS_STEALTHCHOP, SET_STEPPING_MODE(X2));
2068
+            TERN_(Y2_HAS_STEALTHCHOP, SET_STEPPING_MODE(Y2));
2069
+            TERN_(Z2_HAS_STEALTHCHOP, SET_STEPPING_MODE(Z2));
2070
+            TERN_(Z3_HAS_STEALTHCHOP, SET_STEPPING_MODE(Z3));
2071
+            TERN_(Z4_HAS_STEALTHCHOP, SET_STEPPING_MODE(Z4));
2072
+            TERN_(E0_HAS_STEALTHCHOP, SET_STEPPING_MODE(E0));
2073
+            TERN_(E1_HAS_STEALTHCHOP, SET_STEPPING_MODE(E1));
2074
+            TERN_(E2_HAS_STEALTHCHOP, SET_STEPPING_MODE(E2));
2075
+            TERN_(E3_HAS_STEALTHCHOP, SET_STEPPING_MODE(E3));
2076
+            TERN_(E4_HAS_STEALTHCHOP, SET_STEPPING_MODE(E4));
2077
+            TERN_(E5_HAS_STEALTHCHOP, SET_STEPPING_MODE(E5));
2078
+            TERN_(E6_HAS_STEALTHCHOP, SET_STEPPING_MODE(E6));
2079
+            TERN_(E7_HAS_STEALTHCHOP, SET_STEPPING_MODE(E7));
2163 2080
           }
2164 2081
         #endif
2165 2082
       }
@@ -2598,14 +2515,25 @@ void MarlinSettings::reset() {
2598 2515
     #ifndef DEFAULT_XJERK
2599 2516
       #define DEFAULT_XJERK 0
2600 2517
     #endif
2601
-    #ifndef DEFAULT_YJERK
2518
+    #if HAS_Y_AXIS && !defined(DEFAULT_YJERK)
2602 2519
       #define DEFAULT_YJERK 0
2603 2520
     #endif
2604
-    #ifndef DEFAULT_ZJERK
2521
+    #if HAS_Z_AXIS && !defined(DEFAULT_ZJERK)
2605 2522
       #define DEFAULT_ZJERK 0
2606 2523
     #endif
2607
-    planner.max_jerk.set(LINEAR_AXIS_LIST(DEFAULT_XJERK, DEFAULT_YJERK, DEFAULT_ZJERK));
2608
-    TERN_(HAS_CLASSIC_E_JERK, planner.max_jerk.e = DEFAULT_EJERK;);
2524
+    #if LINEAR_AXES >= 4 && !defined(DEFAULT_IJERK)
2525
+      #define DEFAULT_IJERK 0
2526
+    #endif
2527
+    #if LINEAR_AXES >= 5 && !defined(DEFAULT_JJERK)
2528
+      #define DEFAULT_JJERK 0
2529
+    #endif
2530
+    #if LINEAR_AXES >= 6 && !defined(DEFAULT_KJERK)
2531
+      #define DEFAULT_KJERK 0
2532
+    #endif
2533
+    planner.max_jerk.set(
2534
+      LINEAR_AXIS_LIST(DEFAULT_XJERK, DEFAULT_YJERK, DEFAULT_ZJERK, DEFAULT_IJERK, DEFAULT_JJERK, DEFAULT_KJERK)
2535
+    );
2536
+    TERN_(HAS_CLASSIC_E_JERK, planner.max_jerk.e = DEFAULT_EJERK);
2609 2537
   #endif
2610 2538
 
2611 2539
   #if HAS_JUNCTION_DEVIATION
@@ -2703,11 +2631,11 @@ void MarlinSettings::reset() {
2703 2631
 
2704 2632
   #if HAS_BED_PROBE
2705 2633
     constexpr float dpo[] = NOZZLE_TO_PROBE_OFFSET;
2706
-    static_assert(COUNT(dpo) == 3, "NOZZLE_TO_PROBE_OFFSET must contain offsets for X, Y, and Z.");
2634
+    static_assert(COUNT(dpo) == LINEAR_AXES, "NOZZLE_TO_PROBE_OFFSET must contain offsets for each linear axis X, Y, Z....");
2707 2635
     #if HAS_PROBE_XY_OFFSET
2708 2636
       LOOP_LINEAR_AXES(a) probe.offset[a] = dpo[a];
2709 2637
     #else
2710
-      probe.offset.set(0, 0, dpo[Z_AXIS]);
2638
+      probe.offset.set(LINEAR_AXIS_LIST(0, 0, dpo[Z_AXIS], 0, 0, 0));
2711 2639
     #endif
2712 2640
   #endif
2713 2641
 
@@ -3145,7 +3073,10 @@ void MarlinSettings::reset() {
3145 3073
       LIST_N(DOUBLE(LINEAR_AXES),
3146 3074
         PSTR("  M203 X"), LINEAR_UNIT(planner.settings.max_feedrate_mm_s[X_AXIS]),
3147 3075
         SP_Y_STR, LINEAR_UNIT(planner.settings.max_feedrate_mm_s[Y_AXIS]),
3148
-        SP_Z_STR, LINEAR_UNIT(planner.settings.max_feedrate_mm_s[Z_AXIS])
3076
+        SP_Z_STR, LINEAR_UNIT(planner.settings.max_feedrate_mm_s[Z_AXIS]),
3077
+        SP_I_STR, LINEAR_UNIT(planner.settings.max_feedrate_mm_s[I_AXIS]),
3078
+        SP_J_STR, LINEAR_UNIT(planner.settings.max_feedrate_mm_s[J_AXIS]),
3079
+        SP_K_STR, LINEAR_UNIT(planner.settings.max_feedrate_mm_s[K_AXIS])
3149 3080
       )
3150 3081
       #if HAS_EXTRUDERS && DISABLED(DISTINCT_E_FACTORS)
3151 3082
         , SP_E_STR, VOLUMETRIC_UNIT(planner.settings.max_feedrate_mm_s[E_AXIS])
@@ -3167,7 +3098,10 @@ void MarlinSettings::reset() {
3167 3098
       LIST_N(DOUBLE(LINEAR_AXES),
3168 3099
         PSTR("  M201 X"), LINEAR_UNIT(planner.settings.max_acceleration_mm_per_s2[X_AXIS]),
3169 3100
         SP_Y_STR, LINEAR_UNIT(planner.settings.max_acceleration_mm_per_s2[Y_AXIS]),
3170
-        SP_Z_STR, LINEAR_UNIT(planner.settings.max_acceleration_mm_per_s2[Z_AXIS])
3101
+        SP_Z_STR, LINEAR_UNIT(planner.settings.max_acceleration_mm_per_s2[Z_AXIS]),
3102
+        SP_I_STR, LINEAR_UNIT(planner.settings.max_acceleration_mm_per_s2[I_AXIS]),
3103
+        SP_J_STR, LINEAR_UNIT(planner.settings.max_acceleration_mm_per_s2[J_AXIS]),
3104
+        SP_K_STR, LINEAR_UNIT(planner.settings.max_acceleration_mm_per_s2[K_AXIS])
3171 3105
       )
3172 3106
       #if HAS_EXTRUDERS && DISABLED(DISTINCT_E_FACTORS)
3173 3107
         , SP_E_STR, VOLUMETRIC_UNIT(planner.settings.max_acceleration_mm_per_s2[E_AXIS])
@@ -3210,9 +3144,14 @@ void MarlinSettings::reset() {
3210 3144
         , PSTR(" J"), LINEAR_UNIT(planner.junction_deviation_mm)
3211 3145
       #endif
3212 3146
       #if HAS_CLASSIC_JERK
3213
-        , SP_X_STR, LINEAR_UNIT(planner.max_jerk.x)
3214
-        , SP_Y_STR, LINEAR_UNIT(planner.max_jerk.y)
3215
-        , SP_Z_STR, LINEAR_UNIT(planner.max_jerk.z)
3147
+        , LIST_N(DOUBLE(LINEAR_AXES),
3148
+          SP_X_STR, LINEAR_UNIT(planner.max_jerk.x),
3149
+          SP_Y_STR, LINEAR_UNIT(planner.max_jerk.y),
3150
+          SP_Z_STR, LINEAR_UNIT(planner.max_jerk.z),
3151
+          SP_I_STR, LINEAR_UNIT(planner.max_jerk.i),
3152
+          SP_J_STR, LINEAR_UNIT(planner.max_jerk.j),
3153
+          SP_K_STR, LINEAR_UNIT(planner.max_jerk.k)
3154
+        )
3216 3155
         #if HAS_CLASSIC_E_JERK
3217 3156
           , SP_E_STR, LINEAR_UNIT(planner.max_jerk.e)
3218 3157
         #endif
@@ -3224,13 +3163,17 @@ void MarlinSettings::reset() {
3224 3163
       CONFIG_ECHO_START();
3225 3164
       SERIAL_ECHOLNPAIR_P(
3226 3165
         #if IS_CARTESIAN
3227
-            PSTR("  M206 X"), LINEAR_UNIT(home_offset.x)
3228
-          , SP_Y_STR, LINEAR_UNIT(home_offset.y)
3229
-          , SP_Z_STR
3166
+          LIST_N(LINEAR_AXES,
3167
+            PSTR("  M206 X"), LINEAR_UNIT(home_offset.x),
3168
+            SP_Y_STR, LINEAR_UNIT(home_offset.y),
3169
+            SP_Z_STR, LINEAR_UNIT(home_offset.z),
3170
+            SP_I_STR, LINEAR_UNIT(home_offset.i),
3171
+            SP_J_STR, LINEAR_UNIT(home_offset.j),
3172
+            SP_K_STR, LINEAR_UNIT(home_offset.k)
3173
+          )
3230 3174
         #else
3231
-          PSTR("  M206 Z")
3175
+          PSTR("  M206 Z"), LINEAR_UNIT(home_offset.z)
3232 3176
         #endif
3233
-        , LINEAR_UNIT(home_offset.z)
3234 3177
       );
3235 3178
     #endif
3236 3179
 
@@ -3582,6 +3525,19 @@ void MarlinSettings::reset() {
3582 3525
         SERIAL_ECHOLNPAIR(" I3 Z", stepperZ4.getMilliamps());
3583 3526
       #endif
3584 3527
 
3528
+      #if AXIS_IS_TMC(I)
3529
+        say_M906(forReplay);
3530
+        SERIAL_ECHOLNPAIR_P(SP_I_STR, stepperI.getMilliamps());
3531
+      #endif
3532
+      #if AXIS_IS_TMC(J)
3533
+        say_M906(forReplay);
3534
+        SERIAL_ECHOLNPAIR_P(SP_J_STR, stepperJ.getMilliamps());
3535
+      #endif
3536
+      #if AXIS_IS_TMC(K)
3537
+        say_M906(forReplay);
3538
+        SERIAL_ECHOLNPAIR_P(SP_K_STR, stepperK.getMilliamps());
3539
+      #endif
3540
+
3585 3541
       #if AXIS_IS_TMC(E0)
3586 3542
         say_M906(forReplay);
3587 3543
         SERIAL_ECHOLNPAIR(" T0 E", stepperE0.getMilliamps());
@@ -3621,74 +3577,87 @@ void MarlinSettings::reset() {
3621 3577
        */
3622 3578
       #if ENABLED(HYBRID_THRESHOLD)
3623 3579
         CONFIG_ECHO_HEADING("Hybrid Threshold:");
3624
-        #if AXIS_HAS_STEALTHCHOP(X) || AXIS_HAS_STEALTHCHOP(Y) || AXIS_HAS_STEALTHCHOP(Z)
3580
+        #if X_HAS_STEALTHCHOP || Y_HAS_STEALTHCHOP || Z_HAS_STEALTHCHOP
3625 3581
           say_M913(forReplay);
3626
-          #if AXIS_HAS_STEALTHCHOP(X)
3582
+          #if X_HAS_STEALTHCHOP
3627 3583
             SERIAL_ECHOPAIR_P(SP_X_STR, stepperX.get_pwm_thrs());
3628 3584
           #endif
3629
-          #if AXIS_HAS_STEALTHCHOP(Y)
3585
+          #if Y_HAS_STEALTHCHOP
3630 3586
             SERIAL_ECHOPAIR_P(SP_Y_STR, stepperY.get_pwm_thrs());
3631 3587
           #endif
3632
-          #if AXIS_HAS_STEALTHCHOP(Z)
3588
+          #if Z_HAS_STEALTHCHOP
3633 3589
             SERIAL_ECHOPAIR_P(SP_Z_STR, stepperZ.get_pwm_thrs());
3634 3590
           #endif
3635 3591
           SERIAL_EOL();
3636 3592
         #endif
3637 3593
 
3638
-        #if AXIS_HAS_STEALTHCHOP(X2) || AXIS_HAS_STEALTHCHOP(Y2) || AXIS_HAS_STEALTHCHOP(Z2)
3594
+        #if X2_HAS_STEALTHCHOP || Y2_HAS_STEALTHCHOP || Z2_HAS_STEALTHCHOP
3639 3595
           say_M913(forReplay);
3640 3596
           SERIAL_ECHOPGM(" I1");
3641
-          #if AXIS_HAS_STEALTHCHOP(X2)
3597
+          #if X2_HAS_STEALTHCHOP
3642 3598
             SERIAL_ECHOPAIR_P(SP_X_STR, stepperX2.get_pwm_thrs());
3643 3599
           #endif
3644
-          #if AXIS_HAS_STEALTHCHOP(Y2)
3600
+          #if Y2_HAS_STEALTHCHOP
3645 3601
             SERIAL_ECHOPAIR_P(SP_Y_STR, stepperY2.get_pwm_thrs());
3646 3602
           #endif
3647
-          #if AXIS_HAS_STEALTHCHOP(Z2)
3603
+          #if Z2_HAS_STEALTHCHOP
3648 3604
             SERIAL_ECHOPAIR_P(SP_Z_STR, stepperZ2.get_pwm_thrs());
3649 3605
           #endif
3650 3606
           SERIAL_EOL();
3651 3607
         #endif
3652 3608
 
3653
-        #if AXIS_HAS_STEALTHCHOP(Z3)
3609
+        #if Z3_HAS_STEALTHCHOP
3654 3610
           say_M913(forReplay);
3655 3611
           SERIAL_ECHOLNPAIR(" I2 Z", stepperZ3.get_pwm_thrs());
3656 3612
         #endif
3657 3613
 
3658
-        #if AXIS_HAS_STEALTHCHOP(Z4)
3614
+        #if Z4_HAS_STEALTHCHOP
3659 3615
           say_M913(forReplay);
3660 3616
           SERIAL_ECHOLNPAIR(" I3 Z", stepperZ4.get_pwm_thrs());
3661 3617
         #endif
3662 3618
 
3663
-        #if AXIS_HAS_STEALTHCHOP(E0)
3619
+        #if I_HAS_STEALTHCHOP
3620
+          say_M913(forReplay);
3621
+          SERIAL_ECHOLNPAIR_P(SP_I_STR, stepperI.get_pwm_thrs());
3622
+        #endif
3623
+        #if J_HAS_STEALTHCHOP
3624
+          say_M913(forReplay);
3625
+          SERIAL_ECHOLNPAIR_P(SP_J_STR, stepperJ.get_pwm_thrs());
3626
+        #endif
3627
+        #if K_HAS_STEALTHCHOP
3628
+          say_M913(forReplay);
3629
+          SERIAL_ECHOLNPAIR_P(SP_K_STR, stepperK.get_pwm_thrs());
3630
+        #endif
3631
+
3632
+        #if E0_HAS_STEALTHCHOP
3664 3633
           say_M913(forReplay);
3665 3634
           SERIAL_ECHOLNPAIR(" T0 E", stepperE0.get_pwm_thrs());
3666 3635
         #endif
3667
-        #if AXIS_HAS_STEALTHCHOP(E1)
3636
+        #if E1_HAS_STEALTHCHOP
3668 3637
           say_M913(forReplay);
3669 3638
           SERIAL_ECHOLNPAIR(" T1 E", stepperE1.get_pwm_thrs());
3670 3639
         #endif
3671
-        #if AXIS_HAS_STEALTHCHOP(E2)
3640
+        #if E2_HAS_STEALTHCHOP
3672 3641
           say_M913(forReplay);
3673 3642
           SERIAL_ECHOLNPAIR(" T2 E", stepperE2.get_pwm_thrs());
3674 3643
         #endif
3675
-        #if AXIS_HAS_STEALTHCHOP(E3)
3644
+        #if E3_HAS_STEALTHCHOP
3676 3645
           say_M913(forReplay);
3677 3646
           SERIAL_ECHOLNPAIR(" T3 E", stepperE3.get_pwm_thrs());
3678 3647
         #endif
3679
-        #if AXIS_HAS_STEALTHCHOP(E4)
3648
+        #if E4_HAS_STEALTHCHOP
3680 3649
           say_M913(forReplay);
3681 3650
           SERIAL_ECHOLNPAIR(" T4 E", stepperE4.get_pwm_thrs());
3682 3651
         #endif
3683
-        #if AXIS_HAS_STEALTHCHOP(E5)
3652
+        #if E5_HAS_STEALTHCHOP
3684 3653
           say_M913(forReplay);
3685 3654
           SERIAL_ECHOLNPAIR(" T5 E", stepperE5.get_pwm_thrs());
3686 3655
         #endif
3687
-        #if AXIS_HAS_STEALTHCHOP(E6)
3656
+        #if E6_HAS_STEALTHCHOP
3688 3657
           say_M913(forReplay);
3689 3658
           SERIAL_ECHOLNPAIR(" T6 E", stepperE6.get_pwm_thrs());
3690 3659
         #endif
3691
-        #if AXIS_HAS_STEALTHCHOP(E7)
3660
+        #if E7_HAS_STEALTHCHOP
3692 3661
           say_M913(forReplay);
3693 3662
           SERIAL_ECHOLNPAIR(" T7 E", stepperE7.get_pwm_thrs());
3694 3663
         #endif
@@ -3743,6 +3712,22 @@ void MarlinSettings::reset() {
3743 3712
           SERIAL_ECHOLNPAIR(" I3 Z", stepperZ4.homing_threshold());
3744 3713
         #endif
3745 3714
 
3715
+        #if I_SENSORLESS
3716
+          CONFIG_ECHO_START();
3717
+          say_M914();
3718
+          SERIAL_ECHOLNPAIR_P(SP_I_STR, stepperI.homing_threshold());
3719
+        #endif
3720
+        #if J_SENSORLESS
3721
+          CONFIG_ECHO_START();
3722
+          say_M914();
3723
+          SERIAL_ECHOLNPAIR_P(SP_J_STR, stepperJ.homing_threshold());
3724
+        #endif
3725
+        #if K_SENSORLESS
3726
+          CONFIG_ECHO_START();
3727
+          say_M914();
3728
+          SERIAL_ECHOLNPAIR_P(SP_K_STR, stepperK.homing_threshold());
3729
+        #endif
3730
+
3746 3731
       #endif // USE_SENSORLESS
3747 3732
 
3748 3733
       /**
@@ -3750,45 +3735,29 @@ void MarlinSettings::reset() {
3750 3735
        */
3751 3736
       #if HAS_STEALTHCHOP
3752 3737
         CONFIG_ECHO_HEADING("Driver stepping mode:");
3753
-        #if AXIS_HAS_STEALTHCHOP(X)
3754
-          const bool chop_x = stepperX.get_stored_stealthChop();
3755
-        #else
3756
-          constexpr bool chop_x = false;
3757
-        #endif
3758
-        #if AXIS_HAS_STEALTHCHOP(Y)
3759
-          const bool chop_y = stepperY.get_stored_stealthChop();
3760
-        #else
3761
-          constexpr bool chop_y = false;
3762
-        #endif
3763
-        #if AXIS_HAS_STEALTHCHOP(Z)
3764
-          const bool chop_z = stepperZ.get_stored_stealthChop();
3765
-        #else
3766
-          constexpr bool chop_z = false;
3767
-        #endif
3768
-
3769
-        if (chop_x || chop_y || chop_z) {
3738
+        const bool chop_x = TERN0(X_HAS_STEALTHCHOP, stepperX.get_stored_stealthChop()),
3739
+                   chop_y = TERN0(Y_HAS_STEALTHCHOP, stepperY.get_stored_stealthChop()),
3740
+                   chop_z = TERN0(Z_HAS_STEALTHCHOP, stepperZ.get_stored_stealthChop()),
3741
+                   chop_i = TERN0(I_HAS_STEALTHCHOP, stepperI.get_stored_stealthChop()),
3742
+                   chop_j = TERN0(J_HAS_STEALTHCHOP, stepperJ.get_stored_stealthChop()),
3743
+                   chop_k = TERN0(K_HAS_STEALTHCHOP, stepperK.get_stored_stealthChop());
3744
+
3745
+        if (chop_x || chop_y || chop_z || chop_i || chop_j || chop_k) {
3770 3746
           say_M569(forReplay);
3771
-          if (chop_x) SERIAL_ECHOPGM_P(SP_X_STR);
3772
-          if (chop_y) SERIAL_ECHOPGM_P(SP_Y_STR);
3773
-          if (chop_z) SERIAL_ECHOPGM_P(SP_Z_STR);
3747
+          LINEAR_AXIS_CODE(
3748
+            if (chop_x) SERIAL_ECHOPGM_P(SP_X_STR),
3749
+            if (chop_y) SERIAL_ECHOPGM_P(SP_Y_STR),
3750
+            if (chop_z) SERIAL_ECHOPGM_P(SP_Z_STR),
3751
+            if (chop_i) SERIAL_ECHOPGM_P(SP_I_STR),
3752
+            if (chop_j) SERIAL_ECHOPGM_P(SP_J_STR),
3753
+            if (chop_k) SERIAL_ECHOPGM_P(SP_K_STR)
3754
+          );
3774 3755
           SERIAL_EOL();
3775 3756
         }
3776 3757
 
3777
-        #if AXIS_HAS_STEALTHCHOP(X2)
3778
-          const bool chop_x2 = stepperX2.get_stored_stealthChop();
3779
-        #else
3780
-          constexpr bool chop_x2 = false;
3781
-        #endif
3782
-        #if AXIS_HAS_STEALTHCHOP(Y2)
3783
-          const bool chop_y2 = stepperY2.get_stored_stealthChop();
3784
-        #else
3785
-          constexpr bool chop_y2 = false;
3786
-        #endif
3787
-        #if AXIS_HAS_STEALTHCHOP(Z2)
3788
-          const bool chop_z2 = stepperZ2.get_stored_stealthChop();
3789
-        #else
3790
-          constexpr bool chop_z2 = false;
3791
-        #endif
3758
+        const bool chop_x2 = TERN0(X2_HAS_STEALTHCHOP, stepperX2.get_stored_stealthChop()),
3759
+                   chop_y2 = TERN0(Y2_HAS_STEALTHCHOP, stepperY2.get_stored_stealthChop()),
3760
+                   chop_z2 = TERN0(Z2_HAS_STEALTHCHOP, stepperZ2.get_stored_stealthChop());
3792 3761
 
3793 3762
         if (chop_x2 || chop_y2 || chop_z2) {
3794 3763
           say_M569(forReplay, PSTR("I1"));
@@ -3798,38 +3767,21 @@ void MarlinSettings::reset() {
3798 3767
           SERIAL_EOL();
3799 3768
         }
3800 3769
 
3801
-        #if AXIS_HAS_STEALTHCHOP(Z3)
3802
-          if (stepperZ3.get_stored_stealthChop()) { say_M569(forReplay, PSTR("I2 Z"), true); }
3803
-        #endif
3770
+        if (TERN0(Z3_HAS_STEALTHCHOP, stepperZ3.get_stored_stealthChop())) { say_M569(forReplay, PSTR("I2 Z"), true); }
3771
+        if (TERN0(Z4_HAS_STEALTHCHOP, stepperZ4.get_stored_stealthChop())) { say_M569(forReplay, PSTR("I3 Z"), true); }
3804 3772
 
3805
-        #if AXIS_HAS_STEALTHCHOP(Z4)
3806
-          if (stepperZ4.get_stored_stealthChop()) { say_M569(forReplay, PSTR("I3 Z"), true); }
3807
-        #endif
3773
+        if (TERN0( I_HAS_STEALTHCHOP, stepperI.get_stored_stealthChop()))  { say_M569(forReplay, SP_I_STR, true); }
3774
+        if (TERN0( J_HAS_STEALTHCHOP, stepperJ.get_stored_stealthChop()))  { say_M569(forReplay, SP_J_STR, true); }
3775
+        if (TERN0( K_HAS_STEALTHCHOP, stepperK.get_stored_stealthChop()))  { say_M569(forReplay, SP_K_STR, true); }
3808 3776
 
3809
-        #if AXIS_HAS_STEALTHCHOP(E0)
3810
-          if (stepperE0.get_stored_stealthChop()) { say_M569(forReplay, PSTR("T0 E"), true); }
3811
-        #endif
3812
-        #if AXIS_HAS_STEALTHCHOP(E1)
3813
-          if (stepperE1.get_stored_stealthChop()) { say_M569(forReplay, PSTR("T1 E"), true); }
3814
-        #endif
3815
-        #if AXIS_HAS_STEALTHCHOP(E2)
3816
-          if (stepperE2.get_stored_stealthChop()) { say_M569(forReplay, PSTR("T2 E"), true); }
3817
-        #endif
3818
-        #if AXIS_HAS_STEALTHCHOP(E3)
3819
-          if (stepperE3.get_stored_stealthChop()) { say_M569(forReplay, PSTR("T3 E"), true); }
3820
-        #endif
3821
-        #if AXIS_HAS_STEALTHCHOP(E4)
3822
-          if (stepperE4.get_stored_stealthChop()) { say_M569(forReplay, PSTR("T4 E"), true); }
3823
-        #endif
3824
-        #if AXIS_HAS_STEALTHCHOP(E5)
3825
-          if (stepperE5.get_stored_stealthChop()) { say_M569(forReplay, PSTR("T5 E"), true); }
3826
-        #endif
3827
-        #if AXIS_HAS_STEALTHCHOP(E6)
3828
-          if (stepperE6.get_stored_stealthChop()) { say_M569(forReplay, PSTR("T6 E"), true); }
3829
-        #endif
3830
-        #if AXIS_HAS_STEALTHCHOP(E7)
3831
-          if (stepperE7.get_stored_stealthChop()) { say_M569(forReplay, PSTR("T7 E"), true); }
3832
-        #endif
3777
+        if (TERN0(E0_HAS_STEALTHCHOP, stepperE0.get_stored_stealthChop())) { say_M569(forReplay, PSTR("T0 E"), true); }
3778
+        if (TERN0(E1_HAS_STEALTHCHOP, stepperE1.get_stored_stealthChop())) { say_M569(forReplay, PSTR("T1 E"), true); }
3779
+        if (TERN0(E2_HAS_STEALTHCHOP, stepperE2.get_stored_stealthChop())) { say_M569(forReplay, PSTR("T2 E"), true); }
3780
+        if (TERN0(E3_HAS_STEALTHCHOP, stepperE3.get_stored_stealthChop())) { say_M569(forReplay, PSTR("T3 E"), true); }
3781
+        if (TERN0(E4_HAS_STEALTHCHOP, stepperE4.get_stored_stealthChop())) { say_M569(forReplay, PSTR("T4 E"), true); }
3782
+        if (TERN0(E5_HAS_STEALTHCHOP, stepperE5.get_stored_stealthChop())) { say_M569(forReplay, PSTR("T5 E"), true); }
3783
+        if (TERN0(E6_HAS_STEALTHCHOP, stepperE6.get_stored_stealthChop())) { say_M569(forReplay, PSTR("T6 E"), true); }
3784
+        if (TERN0(E7_HAS_STEALTHCHOP, stepperE7.get_stored_stealthChop())) { say_M569(forReplay, PSTR("T7 E"), true); }
3833 3785
 
3834 3786
       #endif // HAS_STEALTHCHOP
3835 3787
 
@@ -3859,7 +3811,7 @@ void MarlinSettings::reset() {
3859 3811
         );
3860 3812
       #elif HAS_MOTOR_CURRENT_SPI
3861 3813
         SERIAL_ECHOPGM("  M907");                              // SPI-based has 5 values:
3862
-        LOOP_LOGICAL_AXES(q) {                                 // X Y Z E (map to X Y Z E0 by default)
3814
+        LOOP_LOGICAL_AXES(q) {                                 // X Y Z (I J K) E (map to X Y Z (I J K) E0 by default)
3863 3815
           SERIAL_CHAR(' ', axis_codes[q]);
3864 3816
           SERIAL_ECHO(stepper.motor_current_setting[q]);
3865 3817
         }
@@ -3869,7 +3821,7 @@ void MarlinSettings::reset() {
3869 3821
     #elif ENABLED(HAS_MOTOR_CURRENT_I2C)                       // i2c-based has any number of values
3870 3822
       // Values sent over i2c are not stored.
3871 3823
       // Indexes map directly to drivers, not axes.
3872
-    #elif ENABLED(HAS_MOTOR_CURRENT_DAC)                       // DAC-based has 4 values, for X Y Z E
3824
+    #elif ENABLED(HAS_MOTOR_CURRENT_DAC)                       // DAC-based has 4 values, for X Y Z (I J K) E
3873 3825
       // Values sent over i2c are not stored. Uses indirect mapping.
3874 3826
     #endif
3875 3827
 
@@ -3901,7 +3853,10 @@ void MarlinSettings::reset() {
3901 3853
         , LIST_N(DOUBLE(LINEAR_AXES),
3902 3854
             SP_X_STR, LINEAR_UNIT(backlash.distance_mm.x),
3903 3855
             SP_Y_STR, LINEAR_UNIT(backlash.distance_mm.y),
3904
-            SP_Z_STR, LINEAR_UNIT(backlash.distance_mm.z)
3856
+            SP_Z_STR, LINEAR_UNIT(backlash.distance_mm.z),
3857
+            SP_I_STR, LINEAR_UNIT(backlash.distance_mm.i),
3858
+            SP_J_STR, LINEAR_UNIT(backlash.distance_mm.j),
3859
+            SP_K_STR, LINEAR_UNIT(backlash.distance_mm.k)
3905 3860
           )
3906 3861
         #ifdef BACKLASH_SMOOTHING_MM
3907 3862
           , PSTR(" S"), LINEAR_UNIT(backlash.smoothing_mm)

+ 246
- 57
Marlin/src/module/stepper.cpp View File

@@ -378,7 +378,7 @@ xyze_int8_t Stepper::count_direction{0};
378 378
   #else
379 379
     #define Y_APPLY_STEP(v,Q) do{ Y_STEP_WRITE(v); Y2_STEP_WRITE(v); }while(0)
380 380
   #endif
381
-#else
381
+#elif HAS_Y_AXIS
382 382
   #define Y_APPLY_DIR(v,Q) Y_DIR_WRITE(v)
383 383
   #define Y_APPLY_STEP(v,Q) Y_STEP_WRITE(v)
384 384
 #endif
@@ -415,11 +415,24 @@ xyze_int8_t Stepper::count_direction{0};
415 415
   #else
416 416
     #define Z_APPLY_STEP(v,Q) do{ Z_STEP_WRITE(v); Z2_STEP_WRITE(v); }while(0)
417 417
   #endif
418
-#else
418
+#elif HAS_Z_AXIS
419 419
   #define Z_APPLY_DIR(v,Q) Z_DIR_WRITE(v)
420 420
   #define Z_APPLY_STEP(v,Q) Z_STEP_WRITE(v)
421 421
 #endif
422 422
 
423
+#if LINEAR_AXES >= 4
424
+  #define I_APPLY_DIR(v,Q) I_DIR_WRITE(v)
425
+  #define I_APPLY_STEP(v,Q) I_STEP_WRITE(v)
426
+#endif
427
+#if LINEAR_AXES >= 5
428
+  #define J_APPLY_DIR(v,Q) J_DIR_WRITE(v)
429
+  #define J_APPLY_STEP(v,Q) J_STEP_WRITE(v)
430
+#endif
431
+#if LINEAR_AXES >= 6
432
+  #define K_APPLY_DIR(v,Q) K_DIR_WRITE(v)
433
+  #define K_APPLY_STEP(v,Q) K_STEP_WRITE(v)
434
+#endif
435
+
423 436
 #if DISABLED(MIXING_EXTRUDER)
424 437
   #define E_APPLY_STEP(v,Q) E_STEP_WRITE(stepper_extruder, v)
425 438
 #endif
@@ -486,6 +499,18 @@ void Stepper::set_directions() {
486 499
     SET_STEP_DIR(Z); // C
487 500
   #endif
488 501
 
502
+  #if HAS_I_DIR
503
+    SET_STEP_DIR(I); // I
504
+  #endif
505
+
506
+  #if HAS_J_DIR
507
+    SET_STEP_DIR(J); // J
508
+  #endif
509
+
510
+  #if HAS_K_DIR
511
+    SET_STEP_DIR(K); // K
512
+  #endif
513
+
489 514
   #if DISABLED(LIN_ADVANCE)
490 515
     #if ENABLED(MIXING_EXTRUDER)
491 516
        // Because this is valid for the whole block we don't know
@@ -1584,7 +1609,7 @@ void Stepper::pulse_phase_isr() {
1584 1609
     const bool is_page = IS_PAGE(current_block);
1585 1610
 
1586 1611
     #if ENABLED(DIRECT_STEPPING)
1587
-
1612
+      // TODO (DerAndere): Add support for LINEAR_AXES >= 4
1588 1613
       if (is_page) {
1589 1614
 
1590 1615
         #if STEPPER_PAGE_FORMAT == SP_4x4D_128
@@ -1700,6 +1725,15 @@ void Stepper::pulse_phase_isr() {
1700 1725
       #if HAS_Z_STEP
1701 1726
         PULSE_PREP(Z);
1702 1727
       #endif
1728
+      #if HAS_I_STEP
1729
+        PULSE_PREP(I);
1730
+      #endif
1731
+      #if HAS_J_STEP
1732
+        PULSE_PREP(J);
1733
+      #endif
1734
+      #if HAS_K_STEP
1735
+        PULSE_PREP(K);
1736
+      #endif
1703 1737
 
1704 1738
       #if EITHER(LIN_ADVANCE, MIXING_EXTRUDER)
1705 1739
         delta_error.e += advance_dividend.e;
@@ -1735,6 +1769,15 @@ void Stepper::pulse_phase_isr() {
1735 1769
     #if HAS_Z_STEP
1736 1770
       PULSE_START(Z);
1737 1771
     #endif
1772
+    #if HAS_I_STEP
1773
+      PULSE_START(I);
1774
+    #endif
1775
+    #if HAS_J_STEP
1776
+      PULSE_START(J);
1777
+    #endif
1778
+    #if HAS_K_STEP
1779
+      PULSE_START(K);
1780
+    #endif
1738 1781
 
1739 1782
     #if DISABLED(LIN_ADVANCE)
1740 1783
       #if ENABLED(MIXING_EXTRUDER)
@@ -1764,6 +1807,15 @@ void Stepper::pulse_phase_isr() {
1764 1807
     #if HAS_Z_STEP
1765 1808
       PULSE_STOP(Z);
1766 1809
     #endif
1810
+    #if HAS_I_STEP
1811
+      PULSE_STOP(I);
1812
+    #endif
1813
+    #if HAS_J_STEP
1814
+      PULSE_STOP(J);
1815
+    #endif
1816
+    #if HAS_K_STEP
1817
+      PULSE_STOP(K);
1818
+    #endif
1767 1819
 
1768 1820
     #if DISABLED(LIN_ADVANCE)
1769 1821
       #if ENABLED(MIXING_EXTRUDER)
@@ -1798,6 +1850,7 @@ uint32_t Stepper::block_phase_isr() {
1798 1850
     // If current block is finished, reset pointer and finalize state
1799 1851
     if (step_events_completed >= step_event_count) {
1800 1852
       #if ENABLED(DIRECT_STEPPING)
1853
+        // TODO (DerAndere): Add support for LINEAR_AXES >= 4
1801 1854
         #if STEPPER_PAGE_FORMAT == SP_4x4D_128
1802 1855
           #define PAGE_SEGMENT_UPDATE_POS(AXIS) \
1803 1856
             count_position[_AXIS(AXIS)] += page_step_state.bd[_AXIS(AXIS)] - 128 * 7;
@@ -2104,9 +2157,12 @@ uint32_t Stepper::block_phase_isr() {
2104 2157
 
2105 2158
       uint8_t axis_bits = 0;
2106 2159
       LINEAR_AXIS_CODE(
2107
-        if (X_MOVE_TEST) SBI(axis_bits, A_AXIS),
2108
-        if (Y_MOVE_TEST) SBI(axis_bits, B_AXIS),
2109
-        if (Z_MOVE_TEST) SBI(axis_bits, C_AXIS)
2160
+        if (X_MOVE_TEST)            SBI(axis_bits, A_AXIS),
2161
+        if (Y_MOVE_TEST)            SBI(axis_bits, B_AXIS),
2162
+        if (Z_MOVE_TEST)            SBI(axis_bits, C_AXIS),
2163
+        if (current_block->steps.i) SBI(axis_bits, I_AXIS),
2164
+        if (current_block->steps.j) SBI(axis_bits, J_AXIS),
2165
+        if (current_block->steps.k) SBI(axis_bits, K_AXIS)
2110 2166
       );
2111 2167
       //if (current_block->steps.e) SBI(axis_bits, E_AXIS);
2112 2168
       //if (current_block->steps.a) SBI(axis_bits, X_HEAD);
@@ -2441,6 +2497,15 @@ void Stepper::init() {
2441 2497
       Z4_DIR_INIT();
2442 2498
     #endif
2443 2499
   #endif
2500
+  #if HAS_I_DIR
2501
+    I_DIR_INIT();
2502
+  #endif
2503
+  #if HAS_J_DIR
2504
+    J_DIR_INIT();
2505
+  #endif
2506
+  #if HAS_K_DIR
2507
+    K_DIR_INIT();
2508
+  #endif
2444 2509
   #if HAS_E0_DIR
2445 2510
     E0_DIR_INIT();
2446 2511
   #endif
@@ -2499,6 +2564,18 @@ void Stepper::init() {
2499 2564
       if (!Z_ENABLE_ON) Z4_ENABLE_WRITE(HIGH);
2500 2565
     #endif
2501 2566
   #endif
2567
+  #if HAS_I_ENABLE
2568
+    I_ENABLE_INIT();
2569
+    if (!I_ENABLE_ON) I_ENABLE_WRITE(HIGH);
2570
+  #endif
2571
+  #if HAS_J_ENABLE
2572
+    J_ENABLE_INIT();
2573
+    if (!J_ENABLE_ON) J_ENABLE_WRITE(HIGH);
2574
+  #endif
2575
+  #if HAS_K_ENABLE
2576
+    K_ENABLE_INIT();
2577
+    if (!K_ENABLE_ON) K_ENABLE_WRITE(HIGH);
2578
+  #endif
2502 2579
   #if HAS_E0_ENABLE
2503 2580
     E0_ENABLE_INIT();
2504 2581
     if (!E_ENABLE_ON) E0_ENABLE_WRITE(HIGH);
@@ -2575,6 +2652,15 @@ void Stepper::init() {
2575 2652
     #endif
2576 2653
     AXIS_INIT(Z, Z);
2577 2654
   #endif
2655
+  #if HAS_I_STEP
2656
+    AXIS_INIT(I, I);
2657
+  #endif
2658
+  #if HAS_J_STEP
2659
+    AXIS_INIT(J, J);
2660
+  #endif
2661
+  #if HAS_K_STEP
2662
+    AXIS_INIT(K, K);
2663
+  #endif
2578 2664
 
2579 2665
   #if E_STEPPERS && HAS_E0_STEP
2580 2666
     E_AXIS_INIT(0);
@@ -2612,7 +2698,10 @@ void Stepper::init() {
2612 2698
     LINEAR_AXIS_GANG(
2613 2699
       | TERN0(INVERT_X_DIR, _BV(X_AXIS)),
2614 2700
       | TERN0(INVERT_Y_DIR, _BV(Y_AXIS)),
2615
-      | TERN0(INVERT_Z_DIR, _BV(Z_AXIS))
2701
+      | TERN0(INVERT_Z_DIR, _BV(Z_AXIS)),
2702
+      | TERN0(INVERT_I_DIR, _BV(I_AXIS)),
2703
+      | TERN0(INVERT_J_DIR, _BV(J_AXIS)),
2704
+      | TERN0(INVERT_K_DIR, _BV(K_AXIS))
2616 2705
     )
2617 2706
   );
2618 2707
 
@@ -2625,32 +2714,32 @@ void Stepper::init() {
2625 2714
 /**
2626 2715
  * Set the stepper positions directly in steps
2627 2716
  *
2628
- * The input is based on the typical per-axis XYZ steps.
2717
+ * The input is based on the typical per-axis XYZE steps.
2629 2718
  * For CORE machines XYZ needs to be translated to ABC.
2630 2719
  *
2631 2720
  * This allows get_axis_position_mm to correctly
2632
- * derive the current XYZ position later on.
2721
+ * derive the current XYZE position later on.
2633 2722
  */
2634
-void Stepper::_set_position(
2635
-  LOGICAL_AXIS_LIST(const int32_t &e, const int32_t &a, const int32_t &b, const int32_t &c)
2636
-) {
2637
-  #if CORE_IS_XY
2638
-    // corexy positioning
2639
-    // these equations follow the form of the dA and dB equations on https://www.corexy.com/theory.html
2640
-    count_position.set(a + b, CORESIGN(a - b), c);
2641
-  #elif CORE_IS_XZ
2642
-    // corexz planning
2643
-    count_position.set(a + c, b, CORESIGN(a - c));
2644
-  #elif CORE_IS_YZ
2645
-    // coreyz planning
2646
-    count_position.set(a, b + c, CORESIGN(b - c));
2647
-  #elif ENABLED(MARKFORGED_XY)
2648
-    count_position.set(a - b, b, c);
2723
+void Stepper::_set_position(const abce_long_t &spos) {
2724
+  #if EITHER(IS_CORE, MARKFORGED_XY)
2725
+    #if CORE_IS_XY
2726
+      // corexy positioning
2727
+      // these equations follow the form of the dA and dB equations on https://www.corexy.com/theory.html
2728
+      count_position.set(spos.a + spos.b, CORESIGN(spos.a - spos.b), spos.c);
2729
+    #elif CORE_IS_XZ
2730
+      // corexz planning
2731
+      count_position.set(spos.a + spos.c, spos.b, CORESIGN(spos.a - spos.c));
2732
+    #elif CORE_IS_YZ
2733
+      // coreyz planning
2734
+      count_position.set(spos.a, spos.b + spos.c, CORESIGN(spos.b - spos.c));
2735
+    #elif ENABLED(MARKFORGED_XY)
2736
+      count_position.set(spos.a - spos.b, spos.b, spos.c);
2737
+    #endif
2738
+    TERN_(HAS_EXTRUDERS, count_position.e = spos.e);
2649 2739
   #else
2650 2740
     // default non-h-bot planning
2651
-    count_position.set(LINEAR_AXIS_LIST(a, b, c));
2741
+    count_position = spos;
2652 2742
   #endif
2653
-  TERN_(HAS_EXTRUDERS, count_position.e = e);
2654 2743
 }
2655 2744
 
2656 2745
 /**
@@ -2673,13 +2762,10 @@ int32_t Stepper::position(const AxisEnum axis) {
2673 2762
 }
2674 2763
 
2675 2764
 // Set the current position in steps
2676
-//TODO: Test for LINEAR_AXES >= 4
2677
-void Stepper::set_position(
2678
-  LOGICAL_AXIS_LIST(const int32_t &e, const int32_t &a, const int32_t &b, const int32_t &c)
2679
-) {
2765
+void Stepper::set_position(const xyze_long_t &spos) {
2680 2766
   planner.synchronize();
2681 2767
   const bool was_enabled = suspend();
2682
-  _set_position(LOGICAL_AXIS_LIST(e, a, b, c));
2768
+  _set_position(spos);
2683 2769
   if (was_enabled) wake_up();
2684 2770
 }
2685 2771
 
@@ -2747,18 +2833,24 @@ int32_t Stepper::triggered_position(const AxisEnum axis) {
2747 2833
   return v;
2748 2834
 }
2749 2835
 
2836
+#if ANY(CORE_IS_XZ, CORE_IS_YZ, DELTA)
2837
+  #define USES_ABC 1
2838
+#endif
2839
+#if ANY(USES_ABC, MARKFORGED_XY, IS_SCARA)
2840
+  #define USES_AB 1
2841
+#endif
2842
+
2750 2843
 void Stepper::report_a_position(const xyz_long_t &pos) {
2751
-  #if ANY(CORE_IS_XY, CORE_IS_XZ, MARKFORGED_XY, DELTA, IS_SCARA)
2752
-    SERIAL_ECHOPAIR(STR_COUNT_A, pos.x, " B:", pos.y);
2753
-  #else
2754
-    SERIAL_ECHOPAIR_P(PSTR(STR_COUNT_X), pos.x, SP_Y_LBL, pos.y);
2755
-  #endif
2756
-  #if ANY(CORE_IS_XZ, CORE_IS_YZ, DELTA)
2757
-    SERIAL_ECHOPAIR(" C:", pos.z);
2758
-  #elif LINEAR_AXES >= 3
2759
-    SERIAL_ECHOPAIR_P(SP_Z_LBL, pos.z);
2760
-  #endif
2761
-  SERIAL_EOL();
2844
+  SERIAL_ECHOLNPAIR_P(
2845
+    LIST_N(DOUBLE(LINEAR_AXES),
2846
+      TERN(USES_AB,  PSTR(STR_COUNT_A), PSTR(STR_COUNT_X)), pos.x,
2847
+      TERN(USES_AB,  PSTR("B:"), SP_Y_LBL), pos.y,
2848
+      TERN(USES_ABC, PSTR("C:"), SP_Z_LBL), pos.z,
2849
+      SP_I_LBL, pos.i,
2850
+      SP_J_LBL, pos.j,
2851
+      SP_K_LBL, pos.k
2852
+    )
2853
+  );
2762 2854
 }
2763 2855
 
2764 2856
 void Stepper::report_positions() {
@@ -2866,9 +2958,7 @@ void Stepper::report_positions() {
2866 2958
   // No other ISR should ever interrupt this!
2867 2959
   void Stepper::do_babystep(const AxisEnum axis, const bool direction) {
2868 2960
 
2869
-    #if DISABLED(INTEGRATED_BABYSTEPPING)
2870
-      cli();
2871
-    #endif
2961
+    IF_DISABLED(INTEGRATED_BABYSTEPPING, cli());
2872 2962
 
2873 2963
     switch (axis) {
2874 2964
 
@@ -2912,35 +3002,90 @@ void Stepper::report_positions() {
2912 3002
           ENABLE_AXIS_X();
2913 3003
           ENABLE_AXIS_Y();
2914 3004
           ENABLE_AXIS_Z();
3005
+          ENABLE_AXIS_I();
3006
+          ENABLE_AXIS_J();
3007
+          ENABLE_AXIS_K();
2915 3008
 
2916 3009
           DIR_WAIT_BEFORE();
2917 3010
 
2918
-          const xyz_byte_t old_dir = LINEAR_AXIS_ARRAY(X_DIR_READ(), Y_DIR_READ(), Z_DIR_READ());
3011
+          const xyz_byte_t old_dir = LINEAR_AXIS_ARRAY(X_DIR_READ(), Y_DIR_READ(), Z_DIR_READ(), I_DIR_READ(), J_DIR_READ(), K_DIR_READ());
2919 3012
 
2920 3013
           X_DIR_WRITE(INVERT_X_DIR ^ z_direction);
2921
-          Y_DIR_WRITE(INVERT_Y_DIR ^ z_direction);
2922
-          Z_DIR_WRITE(INVERT_Z_DIR ^ z_direction);
3014
+          #ifdef Y_DIR_WRITE
3015
+            Y_DIR_WRITE(INVERT_Y_DIR ^ z_direction);
3016
+          #endif
3017
+          #ifdef Z_DIR_WRITE
3018
+            Z_DIR_WRITE(INVERT_Z_DIR ^ z_direction);
3019
+          #endif
3020
+          #ifdef I_DIR_WRITE
3021
+            I_DIR_WRITE(INVERT_I_DIR ^ z_direction);
3022
+          #endif
3023
+          #ifdef J_DIR_WRITE
3024
+            J_DIR_WRITE(INVERT_J_DIR ^ z_direction);
3025
+          #endif
3026
+          #ifdef K_DIR_WRITE
3027
+            K_DIR_WRITE(INVERT_K_DIR ^ z_direction);
3028
+          #endif
2923 3029
 
2924 3030
           DIR_WAIT_AFTER();
2925 3031
 
2926 3032
           _SAVE_START();
2927 3033
 
2928 3034
           X_STEP_WRITE(!INVERT_X_STEP_PIN);
2929
-          Y_STEP_WRITE(!INVERT_Y_STEP_PIN);
2930
-          Z_STEP_WRITE(!INVERT_Z_STEP_PIN);
3035
+          #ifdef Y_STEP_WRITE
3036
+            Y_STEP_WRITE(!INVERT_Y_STEP_PIN);
3037
+          #endif
3038
+          #ifdef Z_STEP_WRITE
3039
+            Z_STEP_WRITE(!INVERT_Z_STEP_PIN);
3040
+          #endif
3041
+          #ifdef I_STEP_WRITE
3042
+            I_STEP_WRITE(!INVERT_I_STEP_PIN);
3043
+          #endif
3044
+          #ifdef J_STEP_WRITE
3045
+            J_STEP_WRITE(!INVERT_J_STEP_PIN);
3046
+          #endif
3047
+          #ifdef K_STEP_WRITE
3048
+            K_STEP_WRITE(!INVERT_K_STEP_PIN);
3049
+          #endif
2931 3050
 
2932 3051
           _PULSE_WAIT();
2933 3052
 
2934 3053
           X_STEP_WRITE(INVERT_X_STEP_PIN);
2935
-          Y_STEP_WRITE(INVERT_Y_STEP_PIN);
2936
-          Z_STEP_WRITE(INVERT_Z_STEP_PIN);
3054
+          #ifdef Y_STEP_WRITE
3055
+            Y_STEP_WRITE(INVERT_Y_STEP_PIN);
3056
+          #endif
3057
+          #ifdef Z_STEP_WRITE
3058
+            Z_STEP_WRITE(INVERT_Z_STEP_PIN);
3059
+          #endif
3060
+          #ifdef I_STEP_WRITE
3061
+            I_STEP_WRITE(INVERT_I_STEP_PIN);
3062
+          #endif
3063
+          #ifdef J_STEP_WRITE
3064
+            J_STEP_WRITE(INVERT_J_STEP_PIN);
3065
+          #endif
3066
+          #ifdef K_STEP_WRITE
3067
+            K_STEP_WRITE(INVERT_K_STEP_PIN);
3068
+          #endif
2937 3069
 
2938 3070
           // Restore direction bits
2939 3071
           EXTRA_DIR_WAIT_BEFORE();
2940 3072
 
2941 3073
           X_DIR_WRITE(old_dir.x);
2942
-          Y_DIR_WRITE(old_dir.y);
2943
-          Z_DIR_WRITE(old_dir.z);
3074
+          #ifdef Y_DIR_WRITE
3075
+            Y_DIR_WRITE(old_dir.y);
3076
+          #endif
3077
+          #ifdef Z_DIR_WRITE
3078
+            Z_DIR_WRITE(old_dir.z);
3079
+          #endif
3080
+          #ifdef I_DIR_WRITE
3081
+            I_DIR_WRITE(old_dir.i);
3082
+          #endif
3083
+          #ifdef J_DIR_WRITE
3084
+            J_DIR_WRITE(old_dir.j);
3085
+          #endif
3086
+          #ifdef K_DIR_WRITE
3087
+            K_DIR_WRITE(old_dir.k);
3088
+          #endif
2944 3089
 
2945 3090
           EXTRA_DIR_WAIT_AFTER();
2946 3091
 
@@ -2948,12 +3093,20 @@ void Stepper::report_positions() {
2948 3093
 
2949 3094
       } break;
2950 3095
 
3096
+      #if LINEAR_AXES >= 4
3097
+        case I_AXIS: BABYSTEP_AXIS(I, 0, direction); break;
3098
+      #endif
3099
+      #if LINEAR_AXES >= 5
3100
+        case J_AXIS: BABYSTEP_AXIS(J, 0, direction); break;
3101
+      #endif
3102
+      #if LINEAR_AXES >= 6
3103
+        case K_AXIS: BABYSTEP_AXIS(K, 0, direction); break;
3104
+      #endif
3105
+
2951 3106
       default: break;
2952 3107
     }
2953 3108
 
2954
-    #if DISABLED(INTEGRATED_BABYSTEPPING)
2955
-      sei();
2956
-    #endif
3109
+    IF_DISABLED(INTEGRATED_BABYSTEPPING, sei());
2957 3110
   }
2958 3111
 
2959 3112
 #endif // BABYSTEPPING
@@ -3288,6 +3441,15 @@ void Stepper::report_positions() {
3288 3441
       #if HAS_E7_MS_PINS
3289 3442
         case 10: WRITE(E7_MS1_PIN, ms1); break;
3290 3443
       #endif
3444
+      #if HAS_I_MICROSTEPS
3445
+        case 11: WRITE(I_MS1_PIN, ms1); break
3446
+      #endif
3447
+      #if HAS_J_MICROSTEPS
3448
+        case 12: WRITE(J_MS1_PIN, ms1); break
3449
+      #endif
3450
+      #if HAS_K_MICROSTEPS
3451
+        case 13: WRITE(K_MS1_PIN, ms1); break
3452
+      #endif
3291 3453
     }
3292 3454
     if (ms2 >= 0) switch (driver) {
3293 3455
       #if HAS_X_MS_PINS || HAS_X2_MS_PINS
@@ -3350,6 +3512,15 @@ void Stepper::report_positions() {
3350 3512
       #if HAS_E7_MS_PINS
3351 3513
         case 10: WRITE(E7_MS2_PIN, ms2); break;
3352 3514
       #endif
3515
+      #if HAS_I_M_PINS
3516
+        case 11: WRITE(I_MS2_PIN, ms2); break
3517
+      #endif
3518
+      #if HAS_J_M_PINS
3519
+        case 12: WRITE(J_MS2_PIN, ms2); break
3520
+      #endif
3521
+      #if HAS_K_M_PINS
3522
+        case 13: WRITE(K_MS2_PIN, ms2); break
3523
+      #endif
3353 3524
     }
3354 3525
     if (ms3 >= 0) switch (driver) {
3355 3526
       #if HAS_X_MS_PINS || HAS_X2_MS_PINS
@@ -3468,6 +3639,24 @@ void Stepper::report_positions() {
3468 3639
         PIN_CHAR(Z_MS3);
3469 3640
       #endif
3470 3641
     #endif
3642
+    #if HAS_I_MS_PINS
3643
+      MS_LINE(I);
3644
+      #if PIN_EXISTS(I_MS3)
3645
+        PIN_CHAR(I_MS3);
3646
+      #endif
3647
+    #endif
3648
+    #if HAS_J_MS_PINS
3649
+      MS_LINE(J);
3650
+      #if PIN_EXISTS(J_MS3)
3651
+        PIN_CHAR(J_MS3);
3652
+      #endif
3653
+    #endif
3654
+    #if HAS_K_MS_PINS
3655
+      MS_LINE(K);
3656
+      #if PIN_EXISTS(K_MS3)
3657
+        PIN_CHAR(K_MS3);
3658
+      #endif
3659
+    #endif
3471 3660
     #if HAS_E0_MS_PINS
3472 3661
       MS_LINE(E0);
3473 3662
       #if PIN_EXISTS(E0_MS3)

+ 24
- 32
Marlin/src/module/stepper.h View File

@@ -133,36 +133,38 @@
133 133
 
134 134
 #endif
135 135
 
136
+// If linear advance is disabled, the loop also handles them
137
+#if DISABLED(LIN_ADVANCE) && ENABLED(MIXING_EXTRUDER)
138
+  #define ISR_MIXING_STEPPER_CYCLES ((MIXING_STEPPERS) * (ISR_STEPPER_CYCLES))
139
+#else
140
+  #define ISR_MIXING_STEPPER_CYCLES  0UL
141
+#endif
142
+
136 143
 // Add time for each stepper
137 144
 #if HAS_X_STEP
138
-  #define ISR_X_STEPPER_CYCLES       ISR_STEPPER_CYCLES
139
-#else
140
-  #define ISR_X_STEPPER_CYCLES       0UL
145
+  #define ISR_X_STEPPER_CYCLES  ISR_STEPPER_CYCLES
141 146
 #endif
142 147
 #if HAS_Y_STEP
143
-  #define ISR_Y_STEPPER_CYCLES       ISR_STEPPER_CYCLES
144
-#else
145
-  #define ISR_START_Y_STEPPER_CYCLES 0UL
146
-  #define ISR_Y_STEPPER_CYCLES       0UL
148
+  #define ISR_Y_STEPPER_CYCLES  ISR_STEPPER_CYCLES
147 149
 #endif
148 150
 #if HAS_Z_STEP
149
-  #define ISR_Z_STEPPER_CYCLES       ISR_STEPPER_CYCLES
150
-#else
151
-  #define ISR_Z_STEPPER_CYCLES       0UL
151
+  #define ISR_Z_STEPPER_CYCLES  ISR_STEPPER_CYCLES
152 152
 #endif
153
-
154
-// E is always interpolated, even for mixing extruders
155
-#define ISR_E_STEPPER_CYCLES         ISR_STEPPER_CYCLES
156
-
157
-// If linear advance is disabled, the loop also handles them
158
-#if DISABLED(LIN_ADVANCE) && ENABLED(MIXING_EXTRUDER)
159
-  #define ISR_MIXING_STEPPER_CYCLES ((MIXING_STEPPERS) * (ISR_STEPPER_CYCLES))
160
-#else
161
-  #define ISR_MIXING_STEPPER_CYCLES  0UL
153
+#if HAS_I_STEP
154
+  #define ISR_I_STEPPER_CYCLES  ISR_STEPPER_CYCLES
155
+#endif
156
+#if HAS_J_STEP
157
+  #define ISR_J_STEPPER_CYCLES  ISR_STEPPER_CYCLES
158
+#endif
159
+#if HAS_K_STEP
160
+  #define ISR_K_STEPPER_CYCLES  ISR_STEPPER_CYCLES
161
+#endif
162
+#if HAS_EXTRUDERS
163
+  #define ISR_E_STEPPER_CYCLES  ISR_STEPPER_CYCLES    // E is always interpolated, even for mixing extruders
162 164
 #endif
163 165
 
164 166
 // And the total minimum loop time, not including the base
165
-#define MIN_ISR_LOOP_CYCLES (ISR_X_STEPPER_CYCLES + ISR_Y_STEPPER_CYCLES + ISR_Z_STEPPER_CYCLES + ISR_E_STEPPER_CYCLES + ISR_MIXING_STEPPER_CYCLES)
167
+#define MIN_ISR_LOOP_CYCLES (ISR_MIXING_STEPPER_CYCLES LOGICAL_AXIS_GANG(+ ISR_E_STEPPER_CYCLES, + ISR_X_STEPPER_CYCLES, + ISR_Y_STEPPER_CYCLES, + ISR_Z_STEPPER_CYCLES, + ISR_I_STEPPER_CYCLES, + ISR_J_STEPPER_CYCLES, + ISR_K_STEPPER_CYCLES))
166 168
 
167 169
 // Calculate the minimum MPU cycles needed per pulse to enforce, limited to the max stepper rate
168 170
 #define _MIN_STEPPER_PULSE_CYCLES(N) _MAX(uint32_t((F_CPU) / (MAXIMUM_STEPPER_RATE)), ((F_CPU) / 500000UL) * (N))
@@ -433,12 +435,7 @@ class Stepper {
433 435
     static int32_t position(const AxisEnum axis);
434 436
 
435 437
     // Set the current position in steps
436
-    static void set_position(
437
-      LOGICAL_AXIS_LIST(const int32_t &e, const int32_t &a, const int32_t &b, const int32_t &c)
438
-    );
439
-    static inline void set_position(const xyze_long_t &abce) {
440
-      set_position(LOGICAL_AXIS_LIST(abce.e, abce.a, abce.b, abce.c));
441
-    }
438
+    static void set_position(const xyze_long_t &spos);
442 439
     static void set_axis_position(const AxisEnum a, const int32_t &v);
443 440
 
444 441
     // Report the positions of the steppers, in steps
@@ -534,12 +531,7 @@ class Stepper {
534 531
   private:
535 532
 
536 533
     // Set the current position in steps
537
-    static void _set_position(
538
-      LOGICAL_AXIS_LIST(const int32_t &e, const int32_t &a, const int32_t &b, const int32_t &c)
539
-    );
540
-    FORCE_INLINE static void _set_position(const abce_long_t &spos) {
541
-      _set_position(LOGICAL_AXIS_LIST(spos.e, spos.a, spos.b, spos.c));
542
-    }
534
+    static void _set_position(const abce_long_t &spos);
543 535
 
544 536
     FORCE_INLINE static uint32_t calc_timer_interval(uint32_t step_rate, uint8_t *loops) {
545 537
       uint32_t timer;

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

@@ -55,6 +55,15 @@
55 55
 #if AXIS_IS_L64XX(Z4)
56 56
   L64XX_CLASS(Z4) stepperZ4(L6470_CHAIN_SS_PIN);
57 57
 #endif
58
+#if AXIS_IS_L64XX(I)
59
+  L64XX_CLASS(I) stepperI(L6470_CHAIN_SS_PIN);
60
+#endif
61
+#if AXIS_IS_L64XX(J)
62
+  L64XX_CLASS(J) stepperJ(L6470_CHAIN_SS_PIN);
63
+#endif
64
+#if AXIS_IS_L64XX(K)
65
+  L64XX_CLASS(K) stepperK(L6470_CHAIN_SS_PIN);
66
+#endif
58 67
 #if AXIS_IS_L64XX(E0)
59 68
   L64XX_CLASS(E0) stepperE0(L6470_CHAIN_SS_PIN);
60 69
 #endif
@@ -199,6 +208,15 @@ void L64XX_Marlin::init_to_defaults() {
199 208
   #if AXIS_IS_L64XX(Z4)
200 209
     L6470_INIT_CHIP(Z4);
201 210
   #endif
211
+  #if AXIS_IS_L64XX(I)
212
+    L6470_INIT_CHIP(I);
213
+  #endif
214
+  #if AXIS_IS_L64XX(J)
215
+    L6470_INIT_CHIP(J);
216
+  #endif
217
+  #if AXIS_IS_L64XX(K)
218
+    L6470_INIT_CHIP(K);
219
+  #endif
202 220
   #if AXIS_IS_L64XX(E0)
203 221
     L6470_INIT_CHIP(E0);
204 222
   #endif

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

@@ -206,6 +206,66 @@
206 206
   #define DISABLE_STEPPER_Z4() stepperZ4.free()
207 207
 #endif
208 208
 
209
+// I Stepper
210
+#if AXIS_IS_L64XX(I)
211
+  extern L64XX_CLASS(I)         stepperI;
212
+  #define I_ENABLE_INIT()       NOOP
213
+  #define I_ENABLE_WRITE(STATE) (STATE ? stepperI.hardStop() : stepperI.free())
214
+  #define I_ENABLE_READ()       (stepperI.getStatus() & STATUS_HIZ)
215
+  #if AXIS_DRIVER_TYPE_I(L6474)
216
+    #define I_DIR_INIT()        SET_OUTPUT(I_DIR_PIN)
217
+    #define I_DIR_WRITE(STATE)  L6474_DIR_WRITE(I, STATE)
218
+    #define I_DIR_READ()        READ(I_DIR_PIN)
219
+  #else
220
+    #define I_DIR_INIT()        NOOP
221
+    #define I_DIR_WRITE(STATE)  L64XX_DIR_WRITE(I, STATE)
222
+    #define I_DIR_READ()        (stepper##I.getStatus() & STATUS_DIR);
223
+    #if AXIS_DRIVER_TYPE_I(L6470)
224
+      #define DISABLE_STEPPER_I() stepperI.free()
225
+    #endif
226
+  #endif
227
+#endif
228
+
229
+// J Stepper
230
+#if AXIS_IS_L64XX(J)
231
+  extern L64XX_CLASS(J)         stepperJ;
232
+  #define J_ENABLE_INIT()       NOOP
233
+  #define J_ENABLE_WRITE(STATE) (STATE ? stepperJ.hardStop() : stepperJ.free())
234
+  #define J_ENABLE_READ()       (stepperJ.getStatus() & STATUS_HIZ)
235
+  #if AXIS_DRIVER_TYPE_J(L6474)
236
+    #define J_DIR_INIT()        SET_OUTPUT(J_DIR_PIN)
237
+    #define J_DIR_WRITE(STATE)  L6474_DIR_WRITE(J, STATE)
238
+    #define J_DIR_READ()        READ(J_DIR_PIN)
239
+  #else
240
+    #define J_DIR_INIT()        NOOP
241
+    #define J_DIR_WRITE(STATE)  L64XX_DIR_WRITE(J, STATE)
242
+    #define J_DIR_READ()        (stepper##J.getStatus() & STATUS_DIR);
243
+    #if AXIS_DRIVER_TYPE_J(L6470)
244
+      #define DISABLE_STEPPER_J() stepperJ.free()
245
+    #endif
246
+  #endif
247
+#endif
248
+
249
+// K Stepper
250
+#if AXIS_IS_L64XX(K)
251
+  extern L64XX_CLASS(K)         stepperK;
252
+  #define K_ENABLE_INIT()       NOOP
253
+  #define K_ENABLE_WRITE(STATE) (STATE ? stepperK.hardStop() : stepperK.free())
254
+  #define K_ENABLE_READ()       (stepperK.getStatus() & STATUS_HIZ)
255
+  #if AXIS_DRIVER_TYPE_K(L6474)
256
+    #define K_DIR_INIT()        SET_OUTPUT(K_DIR_PIN)
257
+    #define K_DIR_WRITE(STATE)  L6474_DIR_WRITE(K, STATE)
258
+    #define K_DIR_READ()        READ(K_DIR_PIN)
259
+  #else
260
+    #define K_DIR_INIT()        NOOP
261
+    #define K_DIR_WRITE(STATE)  L64XX_DIR_WRITE(K, STATE)
262
+    #define K_DIR_READ()        (stepper##K.getStatus() & STATUS_DIR);
263
+    #if AXIS_DRIVER_TYPE_K(L6470)
264
+      #define DISABLE_STEPPER_K() stepperK.free()
265
+    #endif
266
+  #endif
267
+#endif
268
+
209 269
 // E0 Stepper
210 270
 #if AXIS_IS_L64XX(E0)
211 271
   extern L64XX_CLASS(E0)         stepperE0;

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

@@ -60,6 +60,15 @@
60 60
 #if AXIS_DRIVER_TYPE_Z4(TMC26X)
61 61
   _TMC26X_DEFINE(Z4);
62 62
 #endif
63
+#if AXIS_DRIVER_TYPE_I(TMC26X)
64
+  _TMC26X_DEFINE(I);
65
+#endif
66
+#if AXIS_DRIVER_TYPE_J(TMC26X)
67
+  _TMC26X_DEFINE(J);
68
+#endif
69
+#if AXIS_DRIVER_TYPE_K(TMC26X)
70
+  _TMC26X_DEFINE(K);
71
+#endif
63 72
 #if AXIS_DRIVER_TYPE_E0(TMC26X)
64 73
   _TMC26X_DEFINE(E0);
65 74
 #endif
@@ -115,6 +124,15 @@ void tmc26x_init_to_defaults() {
115 124
   #if AXIS_DRIVER_TYPE_Z4(TMC26X)
116 125
     _TMC26X_INIT(Z4);
117 126
   #endif
127
+  #if AXIS_DRIVER_TYPE_I(TMC26X)
128
+     _TMC26X_INIT(I);
129
+  #endif
130
+  #if AXIS_DRIVER_TYPE_J(TMC26X)
131
+    _TMC26X_INIT(J);
132
+  #endif
133
+  #if AXIS_DRIVER_TYPE_K(TMC26X)
134
+    _TMC26X_INIT(K);
135
+  #endif
118 136
   #if AXIS_DRIVER_TYPE_E0(TMC26X)
119 137
     _TMC26X_INIT(E0);
120 138
   #endif

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

@@ -99,6 +99,30 @@ void tmc26x_init_to_defaults();
99 99
   #define Z4_ENABLE_READ() stepperZ4.isEnabled()
100 100
 #endif
101 101
 
102
+// I Stepper
103
+#if HAS_I_ENABLE && AXIS_DRIVER_TYPE_I(TMC26X)
104
+  extern TMC26XStepper stepperI;
105
+  #define I_ENABLE_INIT() NOOP
106
+  #define I_ENABLE_WRITE(STATE) stepperI.setEnabled(STATE)
107
+  #define I_ENABLE_READ() stepperI.isEnabled()
108
+#endif
109
+
110
+// J Stepper
111
+#if HAS_J_ENABLE && AXIS_DRIVER_TYPE_J(TMC26X)
112
+  extern TMC26XStepper stepperJ;
113
+  #define J_ENABLE_INIT() NOOP
114
+  #define J_ENABLE_WRITE(STATE) stepperJ.setEnabled(STATE)
115
+  #define J_ENABLE_READ() stepperJ.isEnabled()
116
+#endif
117
+
118
+// K Stepper
119
+#if HAS_K_ENABLE && AXIS_DRIVER_TYPE_K(TMC26X)
120
+  extern TMC26XStepper stepperK;
121
+  #define K_ENABLE_INIT() NOOP
122
+  #define K_ENABLE_WRITE(STATE) stepperK.setEnabled(STATE)
123
+  #define K_ENABLE_READ() stepperK.isEnabled()
124
+#endif
125
+
102 126
 // E0 Stepper
103 127
 #if AXIS_DRIVER_TYPE_E0(TMC26X)
104 128
   extern TMC26XStepper stepperE0;

+ 1
- 3
Marlin/src/module/stepper/indirection.cpp View File

@@ -37,9 +37,7 @@ void restore_stepper_drivers() {
37 37
 }
38 38
 
39 39
 void reset_stepper_drivers() {
40
-  #if HAS_DRIVER(TMC26X)
41
-    tmc26x_init_to_defaults();
42
-  #endif
40
+  TERN_(HAS_TMC26X, tmc26x_init_to_defaults());
43 41
   TERN_(HAS_L64XX, L64xxManager.init_to_defaults());
44 42
   TERN_(HAS_TRINAMIC_CONFIG, reset_trinamic_drivers());
45 43
 }

+ 173
- 33
Marlin/src/module/stepper/indirection.h View File

@@ -36,7 +36,7 @@
36 36
   #include "L64xx.h"
37 37
 #endif
38 38
 
39
-#if HAS_DRIVER(TMC26X)
39
+#if HAS_TMC26X
40 40
   #include "TMC26X.h"
41 41
 #endif
42 42
 
@@ -65,38 +65,42 @@ void reset_stepper_drivers();    // Called by settings.load / settings.reset
65 65
 #define X_STEP_READ() bool(READ(X_STEP_PIN))
66 66
 
67 67
 // Y Stepper
68
-#ifndef Y_ENABLE_INIT
69
-  #define Y_ENABLE_INIT() SET_OUTPUT(Y_ENABLE_PIN)
70
-  #define Y_ENABLE_WRITE(STATE) WRITE(Y_ENABLE_PIN,STATE)
71
-  #define Y_ENABLE_READ() bool(READ(Y_ENABLE_PIN))
72
-#endif
73
-#ifndef Y_DIR_INIT
74
-  #define Y_DIR_INIT() SET_OUTPUT(Y_DIR_PIN)
75
-  #define Y_DIR_WRITE(STATE) WRITE(Y_DIR_PIN,STATE)
76
-  #define Y_DIR_READ() bool(READ(Y_DIR_PIN))
77
-#endif
78
-#define Y_STEP_INIT() SET_OUTPUT(Y_STEP_PIN)
79
-#ifndef Y_STEP_WRITE
80
-  #define Y_STEP_WRITE(STATE) WRITE(Y_STEP_PIN,STATE)
68
+#if HAS_Y_AXIS
69
+  #ifndef Y_ENABLE_INIT
70
+    #define Y_ENABLE_INIT() SET_OUTPUT(Y_ENABLE_PIN)
71
+    #define Y_ENABLE_WRITE(STATE) WRITE(Y_ENABLE_PIN,STATE)
72
+    #define Y_ENABLE_READ() bool(READ(Y_ENABLE_PIN))
73
+  #endif
74
+  #ifndef Y_DIR_INIT
75
+    #define Y_DIR_INIT() SET_OUTPUT(Y_DIR_PIN)
76
+    #define Y_DIR_WRITE(STATE) WRITE(Y_DIR_PIN,STATE)
77
+    #define Y_DIR_READ() bool(READ(Y_DIR_PIN))
78
+  #endif
79
+  #define Y_STEP_INIT() SET_OUTPUT(Y_STEP_PIN)
80
+  #ifndef Y_STEP_WRITE
81
+    #define Y_STEP_WRITE(STATE) WRITE(Y_STEP_PIN,STATE)
82
+  #endif
83
+  #define Y_STEP_READ() bool(READ(Y_STEP_PIN))
81 84
 #endif
82
-#define Y_STEP_READ() bool(READ(Y_STEP_PIN))
83 85
 
84 86
 // Z Stepper
85
-#ifndef Z_ENABLE_INIT
86
-  #define Z_ENABLE_INIT() SET_OUTPUT(Z_ENABLE_PIN)
87
-  #define Z_ENABLE_WRITE(STATE) WRITE(Z_ENABLE_PIN,STATE)
88
-  #define Z_ENABLE_READ() bool(READ(Z_ENABLE_PIN))
89
-#endif
90
-#ifndef Z_DIR_INIT
91
-  #define Z_DIR_INIT() SET_OUTPUT(Z_DIR_PIN)
92
-  #define Z_DIR_WRITE(STATE) WRITE(Z_DIR_PIN,STATE)
93
-  #define Z_DIR_READ() bool(READ(Z_DIR_PIN))
94
-#endif
95
-#define Z_STEP_INIT() SET_OUTPUT(Z_STEP_PIN)
96
-#ifndef Z_STEP_WRITE
97
-  #define Z_STEP_WRITE(STATE) WRITE(Z_STEP_PIN,STATE)
87
+#if HAS_Z_AXIS
88
+  #ifndef Z_ENABLE_INIT
89
+    #define Z_ENABLE_INIT() SET_OUTPUT(Z_ENABLE_PIN)
90
+    #define Z_ENABLE_WRITE(STATE) WRITE(Z_ENABLE_PIN,STATE)
91
+    #define Z_ENABLE_READ() bool(READ(Z_ENABLE_PIN))
92
+  #endif
93
+  #ifndef Z_DIR_INIT
94
+    #define Z_DIR_INIT() SET_OUTPUT(Z_DIR_PIN)
95
+    #define Z_DIR_WRITE(STATE) WRITE(Z_DIR_PIN,STATE)
96
+    #define Z_DIR_READ() bool(READ(Z_DIR_PIN))
97
+  #endif
98
+  #define Z_STEP_INIT() SET_OUTPUT(Z_STEP_PIN)
99
+  #ifndef Z_STEP_WRITE
100
+    #define Z_STEP_WRITE(STATE) WRITE(Z_STEP_PIN,STATE)
101
+  #endif
102
+  #define Z_STEP_READ() bool(READ(Z_STEP_PIN))
98 103
 #endif
99
-#define Z_STEP_READ() bool(READ(Z_STEP_PIN))
100 104
 
101 105
 // X2 Stepper
102 106
 #if HAS_X2_ENABLE
@@ -201,6 +205,63 @@ void reset_stepper_drivers();    // Called by settings.load / settings.reset
201 205
   #define Z4_DIR_WRITE(STATE) NOOP
202 206
 #endif
203 207
 
208
+// I Stepper
209
+#if LINEAR_AXES >= 4
210
+  #ifndef I_ENABLE_INIT
211
+    #define I_ENABLE_INIT() SET_OUTPUT(I_ENABLE_PIN)
212
+    #define I_ENABLE_WRITE(STATE) WRITE(I_ENABLE_PIN,STATE)
213
+    #define I_ENABLE_READ() bool(READ(I_ENABLE_PIN))
214
+  #endif
215
+  #ifndef I_DIR_INIT
216
+    #define I_DIR_INIT() SET_OUTPUT(I_DIR_PIN)
217
+    #define I_DIR_WRITE(STATE) WRITE(I_DIR_PIN,STATE)
218
+    #define I_DIR_READ() bool(READ(I_DIR_PIN))
219
+  #endif
220
+  #define I_STEP_INIT() SET_OUTPUT(I_STEP_PIN)
221
+  #ifndef I_STEP_WRITE
222
+    #define I_STEP_WRITE(STATE) WRITE(I_STEP_PIN,STATE)
223
+  #endif
224
+  #define I_STEP_READ() bool(READ(I_STEP_PIN))
225
+#endif
226
+
227
+// J Stepper
228
+#if LINEAR_AXES >= 5
229
+  #ifndef J_ENABLE_INIT
230
+    #define J_ENABLE_INIT() SET_OUTPUT(J_ENABLE_PIN)
231
+    #define J_ENABLE_WRITE(STATE) WRITE(J_ENABLE_PIN,STATE)
232
+    #define J_ENABLE_READ() bool(READ(J_ENABLE_PIN))
233
+  #endif
234
+  #ifndef J_DIR_INIT
235
+    #define J_DIR_INIT() SET_OUTPUT(J_DIR_PIN)
236
+    #define J_DIR_WRITE(STATE) WRITE(J_DIR_PIN,STATE)
237
+    #define J_DIR_READ() bool(READ(J_DIR_PIN))
238
+  #endif
239
+  #define J_STEP_INIT() SET_OUTPUT(J_STEP_PIN)
240
+  #ifndef J_STEP_WRITE
241
+    #define J_STEP_WRITE(STATE) WRITE(J_STEP_PIN,STATE)
242
+  #endif
243
+  #define J_STEP_READ() bool(READ(J_STEP_PIN))
244
+#endif
245
+
246
+// K Stepper
247
+#if LINEAR_AXES >= 6
248
+  #ifndef K_ENABLE_INIT
249
+    #define K_ENABLE_INIT() SET_OUTPUT(K_ENABLE_PIN)
250
+    #define K_ENABLE_WRITE(STATE) WRITE(K_ENABLE_PIN,STATE)
251
+    #define K_ENABLE_READ() bool(READ(K_ENABLE_PIN))
252
+  #endif
253
+  #ifndef K_DIR_INIT
254
+    #define K_DIR_INIT() SET_OUTPUT(K_DIR_PIN)
255
+    #define K_DIR_WRITE(STATE) WRITE(K_DIR_PIN,STATE)
256
+    #define K_DIR_READ() bool(READ(K_DIR_PIN))
257
+  #endif
258
+  #define K_STEP_INIT() SET_OUTPUT(K_STEP_PIN)
259
+  #ifndef K_STEP_WRITE
260
+    #define K_STEP_WRITE(STATE) WRITE(K_STEP_PIN,STATE)
261
+  #endif
262
+  #define K_STEP_READ() bool(READ(K_STEP_PIN))
263
+#endif
264
+
204 265
 // E0 Stepper
205 266
 #ifndef E0_ENABLE_INIT
206 267
   #define E0_ENABLE_INIT() SET_OUTPUT(E0_ENABLE_PIN)
@@ -720,6 +781,51 @@ void reset_stepper_drivers();    // Called by settings.load / settings.reset
720 781
   #endif
721 782
 #endif
722 783
 
784
+#ifndef ENABLE_STEPPER_I
785
+  #if HAS_I_ENABLE
786
+    #define  ENABLE_STEPPER_I() I_ENABLE_WRITE( I_ENABLE_ON)
787
+  #else
788
+    #define  ENABLE_STEPPER_I() NOOP
789
+  #endif
790
+#endif
791
+#ifndef DISABLE_STEPPER_I
792
+  #if HAS_I_ENABLE
793
+    #define DISABLE_STEPPER_I() I_ENABLE_WRITE(!I_ENABLE_ON)
794
+  #else
795
+    #define DISABLE_STEPPER_I() NOOP
796
+  #endif
797
+#endif
798
+
799
+#ifndef ENABLE_STEPPER_J
800
+  #if HAS_J_ENABLE
801
+    #define  ENABLE_STEPPER_J() J_ENABLE_WRITE( J_ENABLE_ON)
802
+  #else
803
+    #define  ENABLE_STEPPER_J() NOOP
804
+  #endif
805
+#endif
806
+#ifndef DISABLE_STEPPER_J
807
+  #if HAS_J_ENABLE
808
+    #define DISABLE_STEPPER_J() J_ENABLE_WRITE(!J_ENABLE_ON)
809
+  #else
810
+    #define DISABLE_STEPPER_J() NOOP
811
+  #endif
812
+#endif
813
+
814
+#ifndef ENABLE_STEPPER_K
815
+  #if HAS_K_ENABLE
816
+    #define  ENABLE_STEPPER_K() K_ENABLE_WRITE( K_ENABLE_ON)
817
+  #else
818
+    #define  ENABLE_STEPPER_K() NOOP
819
+  #endif
820
+#endif
821
+#ifndef DISABLE_STEPPER_K
822
+  #if HAS_K_ENABLE
823
+    #define DISABLE_STEPPER_K() K_ENABLE_WRITE(!K_ENABLE_ON)
824
+  #else
825
+    #define DISABLE_STEPPER_K() NOOP
826
+  #endif
827
+#endif
828
+
723 829
 #ifndef ENABLE_STEPPER_E0
724 830
   #if HAS_E0_ENABLE
725 831
     #define  ENABLE_STEPPER_E0() E0_ENABLE_WRITE( E_ENABLE_ON)
@@ -857,10 +963,22 @@ void reset_stepper_drivers();    // Called by settings.load / settings.reset
857 963
 
858 964
 #define  ENABLE_AXIS_X() if (SHOULD_ENABLE(x))  {  ENABLE_STEPPER_X();  ENABLE_STEPPER_X2(); AFTER_CHANGE(x, true); }
859 965
 #define DISABLE_AXIS_X() if (SHOULD_DISABLE(x)) { DISABLE_STEPPER_X(); DISABLE_STEPPER_X2(); AFTER_CHANGE(x, false); set_axis_untrusted(X_AXIS); }
860
-#define  ENABLE_AXIS_Y() if (SHOULD_ENABLE(y))  {  ENABLE_STEPPER_Y();  ENABLE_STEPPER_Y2(); AFTER_CHANGE(y, true); }
861
-#define DISABLE_AXIS_Y() if (SHOULD_DISABLE(y)) { DISABLE_STEPPER_Y(); DISABLE_STEPPER_Y2(); AFTER_CHANGE(y, false); set_axis_untrusted(Y_AXIS); }
862
-#define  ENABLE_AXIS_Z() if (SHOULD_ENABLE(z))  {  ENABLE_STEPPER_Z();  ENABLE_STEPPER_Z2();  ENABLE_STEPPER_Z3();  ENABLE_STEPPER_Z4(); AFTER_CHANGE(z, true); }
863
-#define DISABLE_AXIS_Z() if (SHOULD_DISABLE(z)) { DISABLE_STEPPER_Z(); DISABLE_STEPPER_Z2(); DISABLE_STEPPER_Z3(); DISABLE_STEPPER_Z4(); AFTER_CHANGE(z, false); set_axis_untrusted(Z_AXIS); Z_RESET(); }
966
+
967
+#if HAS_Y_AXIS
968
+  #define  ENABLE_AXIS_Y() if (SHOULD_ENABLE(y))  {  ENABLE_STEPPER_Y();  ENABLE_STEPPER_Y2(); AFTER_CHANGE(y, true); }
969
+  #define DISABLE_AXIS_Y() if (SHOULD_DISABLE(y)) { DISABLE_STEPPER_Y(); DISABLE_STEPPER_Y2(); AFTER_CHANGE(y, false); set_axis_untrusted(Y_AXIS); }
970
+#else
971
+  #define  ENABLE_AXIS_Y() NOOP
972
+  #define DISABLE_AXIS_Y() NOOP
973
+#endif
974
+
975
+#if HAS_Z_AXIS
976
+  #define  ENABLE_AXIS_Z() if (SHOULD_ENABLE(z))  {  ENABLE_STEPPER_Z();  ENABLE_STEPPER_Z2();  ENABLE_STEPPER_Z3();  ENABLE_STEPPER_Z4(); AFTER_CHANGE(z, true); }
977
+  #define DISABLE_AXIS_Z() if (SHOULD_DISABLE(z)) { DISABLE_STEPPER_Z(); DISABLE_STEPPER_Z2(); DISABLE_STEPPER_Z3(); DISABLE_STEPPER_Z4(); AFTER_CHANGE(z, false); set_axis_untrusted(Z_AXIS); Z_RESET(); }
978
+#else
979
+  #define  ENABLE_AXIS_Z() NOOP
980
+  #define DISABLE_AXIS_Z() NOOP
981
+#endif
864 982
 
865 983
 #ifdef Z_IDLE_HEIGHT
866 984
   #define Z_RESET() do{ current_position.z = Z_IDLE_HEIGHT; sync_plan_position(); }while(0)
@@ -868,6 +986,28 @@ void reset_stepper_drivers();    // Called by settings.load / settings.reset
868 986
   #define Z_RESET()
869 987
 #endif
870 988
 
989
+#if LINEAR_AXES >= 4
990
+  #define  ENABLE_AXIS_I() if (SHOULD_ENABLE(i))  {  ENABLE_STEPPER_I();  AFTER_CHANGE(i, true); }
991
+  #define DISABLE_AXIS_I() if (SHOULD_DISABLE(i)) { DISABLE_STEPPER_I(); AFTER_CHANGE(i, false); set_axis_untrusted(I_AXIS); }
992
+#else
993
+  #define  ENABLE_AXIS_I() NOOP
994
+  #define DISABLE_AXIS_I() NOOP
995
+#endif
996
+#if LINEAR_AXES >= 5
997
+  #define  ENABLE_AXIS_J() if (SHOULD_ENABLE(j))  {  ENABLE_STEPPER_J();  AFTER_CHANGE(j, true); }
998
+  #define DISABLE_AXIS_J() if (SHOULD_DISABLE(j)) { DISABLE_STEPPER_J(); AFTER_CHANGE(j, false); set_axis_untrusted(J_AXIS); }
999
+#else
1000
+  #define  ENABLE_AXIS_J() NOOP
1001
+  #define DISABLE_AXIS_J() NOOP
1002
+#endif
1003
+#if LINEAR_AXES >= 6
1004
+  #define  ENABLE_AXIS_K() if (SHOULD_ENABLE(k))  {  ENABLE_STEPPER_K();  AFTER_CHANGE(k, true); }
1005
+  #define DISABLE_AXIS_K() if (SHOULD_DISABLE(k)) { DISABLE_STEPPER_K(); AFTER_CHANGE(k, false); set_axis_untrusted(K_AXIS); }
1006
+#else
1007
+  #define  ENABLE_AXIS_K() NOOP
1008
+  #define DISABLE_AXIS_K() NOOP
1009
+#endif
1010
+
871 1011
 //
872 1012
 // Extruder steppers enable / disable macros
873 1013
 //

+ 102
- 3
Marlin/src/module/stepper/trinamic.cpp View File

@@ -36,7 +36,7 @@
36 36
 #include <SPI.h>
37 37
 
38 38
 enum StealthIndex : uint8_t {
39
-  LOGICAL_AXIS_LIST(STEALTH_AXIS_E, STEALTH_AXIS_X, STEALTH_AXIS_Y, STEALTH_AXIS_Z)
39
+  LOGICAL_AXIS_LIST(STEALTH_AXIS_E, STEALTH_AXIS_X, STEALTH_AXIS_Y, STEALTH_AXIS_Z, STEALTH_AXIS_I, STEALTH_AXIS_J, STEALTH_AXIS_K)
40 40
 };
41 41
 #define TMC_INIT(ST, STEALTH_INDEX) tmc_init(stepper##ST, ST##_CURRENT, ST##_MICROSTEPS, ST##_HYBRID_THRESHOLD, stealthchop_by_axis[STEALTH_INDEX], chopper_timing_##ST, ST##_INTERPOLATE)
42 42
 
@@ -97,6 +97,15 @@ enum StealthIndex : uint8_t {
97 97
 #if AXIS_HAS_SPI(Z4)
98 98
   TMC_SPI_DEFINE(Z4, Z);
99 99
 #endif
100
+#if AXIS_HAS_SPI(I)
101
+  TMC_SPI_DEFINE(I, I);
102
+#endif
103
+#if AXIS_HAS_SPI(J)
104
+  TMC_SPI_DEFINE(J, J);
105
+#endif
106
+#if AXIS_HAS_SPI(K)
107
+  TMC_SPI_DEFINE(K, K);
108
+#endif
100 109
 #if AXIS_HAS_SPI(E0)
101 110
   TMC_SPI_DEFINE_E(0);
102 111
 #endif
@@ -329,6 +338,34 @@ enum StealthIndex : uint8_t {
329 338
       #define Z4_HAS_SW_SERIAL 1
330 339
     #endif
331 340
   #endif
341
+  #if AXIS_HAS_UART(I)
342
+    #ifdef I_HARDWARE_SERIAL
343
+      TMC_UART_DEFINE(HW, I, I);
344
+      #define I_HAS_HW_SERIAL 1
345
+    #else
346
+      TMC_UART_DEFINE(SW, I, I);
347
+      #define I_HAS_SW_SERIAL 1
348
+    #endif
349
+  #endif
350
+  #if AXIS_HAS_UART(J)
351
+    #ifdef J_HARDWARE_SERIAL
352
+      TMC_UART_DEFINE(HW, J, J);
353
+      #define J_HAS_HW_SERIAL 1
354
+    #else
355
+      TMC_UART_DEFINE(SW, J, J);
356
+      #define J_HAS_SW_SERIAL 1
357
+    #endif
358
+  #endif
359
+  #if AXIS_HAS_UART(K)
360
+    #ifdef K_HARDWARE_SERIAL
361
+      TMC_UART_DEFINE(HW, K, K);
362
+      #define K_HAS_HW_SERIAL 1
363
+    #else
364
+      TMC_UART_DEFINE(SW, K, K);
365
+      #define K_HAS_SW_SERIAL 1
366
+    #endif
367
+  #endif
368
+
332 369
   #if AXIS_HAS_UART(E0)
333 370
     #ifdef E0_HARDWARE_SERIAL
334 371
       TMC_UART_DEFINE_E(HW, 0);
@@ -402,7 +439,9 @@ enum StealthIndex : uint8_t {
402 439
     #endif
403 440
   #endif
404 441
 
405
-  enum TMCAxis : uint8_t { LINEAR_AXIS_LIST(X, Y, Z), X2, Y2, Z2, Z3, Z4, E0, E1, E2, E3, E4, E5, E6, E7, TOTAL };
442
+  #define _EN_ITEM(N) , E##N
443
+  enum TMCAxis : uint8_t { LINEAR_AXIS_LIST(X, Y, Z, I, J, K), X2, Y2, Z2, Z3, Z4 REPEAT(EXTRUDERS, _EN_ITEM), TOTAL };
444
+  #undef _EN_ITEM
406 445
 
407 446
   void tmc_serial_begin() {
408 447
     #if HAS_TMC_HW_SERIAL
@@ -474,6 +513,27 @@ enum StealthIndex : uint8_t {
474 513
         stepperZ4.beginSerial(TMC_BAUD_RATE);
475 514
       #endif
476 515
     #endif
516
+    #if AXIS_HAS_UART(I)
517
+      #ifdef I_HARDWARE_SERIAL
518
+        HW_SERIAL_BEGIN(I);
519
+      #else
520
+        stepperI.beginSerial(TMC_BAUD_RATE);
521
+      #endif
522
+    #endif
523
+    #if AXIS_HAS_UART(J)
524
+      #ifdef J_HARDWARE_SERIAL
525
+        HW_SERIAL_BEGIN(J);
526
+      #else
527
+        stepperJ.beginSerial(TMC_BAUD_RATE);
528
+      #endif
529
+    #endif
530
+    #if AXIS_HAS_UART(K)
531
+      #ifdef K_HARDWARE_SERIAL
532
+        HW_SERIAL_BEGIN(K);
533
+      #else
534
+        stepperK.beginSerial(TMC_BAUD_RATE);
535
+      #endif
536
+    #endif
477 537
     #if AXIS_HAS_UART(E0)
478 538
       #ifdef E0_HARDWARE_SERIAL
479 539
         HW_SERIAL_BEGIN(E0);
@@ -740,6 +800,15 @@ void restore_trinamic_drivers() {
740 800
   #if AXIS_IS_TMC(Z4)
741 801
     stepperZ4.push();
742 802
   #endif
803
+  #if AXIS_IS_TMC(I)
804
+    stepperI.push();
805
+  #endif
806
+  #if AXIS_IS_TMC(J)
807
+    stepperJ.push();
808
+  #endif
809
+  #if AXIS_IS_TMC(K)
810
+    stepperK.push();
811
+  #endif
743 812
   #if AXIS_IS_TMC(E0)
744 813
     stepperE0.push();
745 814
   #endif
@@ -771,7 +840,10 @@ void reset_trinamic_drivers() {
771 840
     ENABLED(STEALTHCHOP_E),
772 841
     ENABLED(STEALTHCHOP_XY),
773 842
     ENABLED(STEALTHCHOP_XY),
774
-    ENABLED(STEALTHCHOP_Z)
843
+    ENABLED(STEALTHCHOP_Z),
844
+    ENABLED(STEALTHCHOP_I),
845
+    ENABLED(STEALTHCHOP_J),
846
+    ENABLED(STEALTHCHOP_K)
775 847
   );
776 848
 
777 849
   #if AXIS_IS_TMC(X)
@@ -798,6 +870,15 @@ void reset_trinamic_drivers() {
798 870
   #if AXIS_IS_TMC(Z4)
799 871
     TMC_INIT(Z4, STEALTH_AXIS_Z);
800 872
   #endif
873
+  #if AXIS_IS_TMC(I)
874
+    TMC_INIT(I, STEALTH_AXIS_I);
875
+  #endif
876
+  #if AXIS_IS_TMC(J)
877
+    TMC_INIT(J, STEALTH_AXIS_J);
878
+  #endif
879
+  #if AXIS_IS_TMC(K)
880
+    TMC_INIT(K, STEALTH_AXIS_K);
881
+  #endif
801 882
   #if AXIS_IS_TMC(E0)
802 883
     TMC_INIT(E0, STEALTH_AXIS_E);
803 884
   #endif
@@ -848,6 +929,24 @@ void reset_trinamic_drivers() {
848 929
         stepperZ4.homing_threshold(CAT(TERN(Z4_SENSORLESS, Z4, Z), _STALL_SENSITIVITY));
849 930
       #endif
850 931
     #endif
932
+    #if I_SENSORLESS
933
+      stepperI.homing_threshold(I_STALL_SENSITIVITY);
934
+      #if AXIS_HAS_STALLGUARD(I)
935
+        stepperI.homing_threshold(CAT(TERN(I_SENSORLESS, I, I), _STALL_SENSITIVITY));
936
+      #endif
937
+    #endif
938
+    #if J_SENSORLESS
939
+      stepperJ.homing_threshold(J_STALL_SENSITIVITY);
940
+      #if AXIS_HAS_STALLGUARD(J)
941
+        stepperJ.homing_threshold(CAT(TERN(J_SENSORLESS, J, J), _STALL_SENSITIVITY));
942
+      #endif
943
+    #endif
944
+    #if K_SENSORLESS
945
+      stepperK.homing_threshold(K_STALL_SENSITIVITY);
946
+      #if AXIS_HAS_STALLGUARD(K)
947
+        stepperK.homing_threshold(CAT(TERN(K_SENSORLESS, K, K), _STALL_SENSITIVITY));
948
+      #endif
949
+    #endif
851 950
   #endif // USE SENSORLESS
852 951
 
853 952
   #ifdef TMC_ADV

+ 58
- 3
Marlin/src/module/stepper/trinamic.h View File

@@ -46,6 +46,10 @@
46 46
 #define TMC_Y_LABEL 'Y', '0'
47 47
 #define TMC_Z_LABEL 'Z', '0'
48 48
 
49
+#define TMC_I_LABEL 'I', '0'
50
+#define TMC_J_LABEL 'J', '0'
51
+#define TMC_K_LABEL 'K', '0'
52
+
49 53
 #define TMC_X2_LABEL 'X', '2'
50 54
 #define TMC_Y2_LABEL 'Y', '2'
51 55
 #define TMC_Z2_LABEL 'Z', '2'
@@ -79,13 +83,22 @@ typedef struct {
79 83
 #ifndef CHOPPER_TIMING_X
80 84
   #define CHOPPER_TIMING_X CHOPPER_TIMING
81 85
 #endif
82
-#ifndef CHOPPER_TIMING_Y
86
+#if HAS_Y_AXIS && !defined(CHOPPER_TIMING_Y)
83 87
   #define CHOPPER_TIMING_Y CHOPPER_TIMING
84 88
 #endif
85
-#ifndef CHOPPER_TIMING_Z
89
+#if HAS_Z_AXIS && !defined(CHOPPER_TIMING_Z)
86 90
   #define CHOPPER_TIMING_Z CHOPPER_TIMING
87 91
 #endif
88
-#ifndef CHOPPER_TIMING_E
92
+#if LINEAR_AXES >= 4 && !defined(CHOPPER_TIMING_I)
93
+  #define CHOPPER_TIMING_I CHOPPER_TIMING
94
+#endif
95
+#if LINEAR_AXES >= 5 && !defined(CHOPPER_TIMING_J)
96
+  #define CHOPPER_TIMING_J CHOPPER_TIMING
97
+#endif
98
+#if LINEAR_AXES >= 6 && !defined(CHOPPER_TIMING_K)
99
+  #define CHOPPER_TIMING_K CHOPPER_TIMING
100
+#endif
101
+#if HAS_EXTRUDERS && !defined(CHOPPER_TIMING_E)
89 102
   #define CHOPPER_TIMING_E CHOPPER_TIMING
90 103
 #endif
91 104
 
@@ -225,6 +238,48 @@ void reset_trinamic_drivers();
225 238
   #endif
226 239
 #endif
227 240
 
241
+// I Stepper
242
+#if AXIS_IS_TMC(I)
243
+  extern TMC_CLASS(I, I) stepperI;
244
+  static constexpr chopper_timing_t chopper_timing_I = CHOPPER_TIMING_I;
245
+  #if ENABLED(SOFTWARE_DRIVER_ENABLE)
246
+    #define I_ENABLE_INIT() NOOP
247
+    #define I_ENABLE_WRITE(STATE) stepperI.toff((STATE)==I_ENABLE_ON ? chopper_timing.toff : 0)
248
+    #define I_ENABLE_READ() stepperI.isEnabled()
249
+  #endif
250
+  #if AXIS_HAS_SQUARE_WAVE(I)
251
+    #define I_STEP_WRITE(STATE) do{ if (STATE) TOGGLE(I_STEP_PIN); }while(0)
252
+  #endif
253
+#endif
254
+
255
+// J Stepper
256
+#if AXIS_IS_TMC(J)
257
+  extern TMC_CLASS(J, J) stepperJ;
258
+  static constexpr chopper_timing_t chopper_timing_J = CHOPPER_TIMING_J;
259
+  #if ENABLED(SOFTWARE_DRIVER_ENABLE)
260
+    #define J_ENABLE_INIT() NOOP
261
+    #define J_ENABLE_WRITE(STATE) stepperJ.toff((STATE)==J_ENABLE_ON ? chopper_timing.toff : 0)
262
+    #define J_ENABLE_READ() stepperJ.isEnabled()
263
+  #endif
264
+  #if AXIS_HAS_SQUARE_WAVE(J)
265
+    #define J_STEP_WRITE(STATE) do{ if (STATE) TOGGLE(J_STEP_PIN); }while(0)
266
+  #endif
267
+#endif
268
+
269
+// K Stepper
270
+#if AXIS_IS_TMC(K)
271
+  extern TMC_CLASS(K, K) stepperK;
272
+  static constexpr chopper_timing_t chopper_timing_K = CHOPPER_TIMING_K;
273
+  #if ENABLED(SOFTWARE_DRIVER_ENABLE)
274
+    #define K_ENABLE_INIT() NOOP
275
+    #define K_ENABLE_WRITE(STATE) stepperK.toff((STATE)==K_ENABLE_ON ? chopper_timing.toff : 0)
276
+    #define K_ENABLE_READ() stepperK.isEnabled()
277
+  #endif
278
+  #if AXIS_HAS_SQUARE_WAVE(K)
279
+    #define K_STEP_WRITE(STATE) do{ if (STATE) TOGGLE(K_STEP_PIN); }while(0)
280
+  #endif
281
+#endif
282
+
228 283
 // E0 Stepper
229 284
 #if AXIS_IS_TMC(E0)
230 285
   extern TMC_CLASS_E(0) stepperE0;

+ 19
- 5
Marlin/src/module/tool_change.cpp View File

@@ -49,7 +49,9 @@
49 49
   bool toolchange_extruder_ready[EXTRUDERS];
50 50
 #endif
51 51
 
52
-#if EITHER(MAGNETIC_PARKING_EXTRUDER, TOOL_SENSOR) || defined(EVENT_GCODE_AFTER_TOOLCHANGE) || (ENABLED(PARKING_EXTRUDER) && PARKING_EXTRUDER_SOLENOIDS_DELAY > 0)
52
+#if EITHER(MAGNETIC_PARKING_EXTRUDER, TOOL_SENSOR) \
53
+  || defined(EVENT_GCODE_TOOLCHANGE_T0) || defined(EVENT_GCODE_TOOLCHANGE_T1) || defined(EVENT_GCODE_AFTER_TOOLCHANGE) \
54
+  || (ENABLED(PARKING_EXTRUDER) && PARKING_EXTRUDER_SOLENOIDS_DELAY > 0)
53 55
   #include "../gcode/gcode.h"
54 56
 #endif
55 57
 
@@ -1311,10 +1313,22 @@ void tool_change(const uint8_t new_tool, bool no_move/*=false*/) {
1311 1313
 
1312 1314
     TERN_(HAS_FANMUX, fanmux_switch(active_extruder));
1313 1315
 
1314
-    #ifdef EVENT_GCODE_AFTER_TOOLCHANGE
1315
-      if (!no_move && TERN1(DUAL_X_CARRIAGE, dual_x_carriage_mode == DXC_AUTO_PARK_MODE))
1316
-        gcode.process_subcommands_now_P(PSTR(EVENT_GCODE_AFTER_TOOLCHANGE));
1317
-    #endif
1316
+    if (!no_move) {
1317
+      #ifdef EVENT_GCODE_TOOLCHANGE_T0
1318
+        if (new_tool == 0)
1319
+          gcode.process_subcommands_now_P(PSTR(EVENT_GCODE_TOOLCHANGE_T0));
1320
+      #endif
1321
+
1322
+      #ifdef EVENT_GCODE_TOOLCHANGE_T1
1323
+        if (new_tool == 1)
1324
+          gcode.process_subcommands_now_P(PSTR(EVENT_GCODE_TOOLCHANGE_T1));
1325
+      #endif
1326
+
1327
+      #ifdef EVENT_GCODE_AFTER_TOOLCHANGE
1328
+        if (TERN1(DUAL_X_CARRIAGE, dual_x_carriage_mode == DXC_AUTO_PARK_MODE))
1329
+          gcode.process_subcommands_now_P(PSTR(EVENT_GCODE_AFTER_TOOLCHANGE));
1330
+      #endif
1331
+    }
1318 1332
 
1319 1333
     SERIAL_ECHO_MSG(STR_ACTIVE_EXTRUDER, active_extruder);
1320 1334
 

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

@@ -1319,6 +1319,105 @@
1319 1319
 #if PIN_EXISTS(Z_MIN_PROBE)
1320 1320
   REPORT_NAME_DIGITAL(__LINE__, Z_MIN_PROBE_PIN)
1321 1321
 #endif
1322
+#if PIN_EXISTS(I_ATT)
1323
+  REPORT_NAME_DIGITAL(__LINE__, I_ATT_PIN)
1324
+#endif
1325
+#if PIN_EXISTS(I_CS)
1326
+  REPORT_NAME_DIGITAL(__LINE__, I_CS_PIN)
1327
+#endif
1328
+#if PIN_EXISTS(I_DIR)
1329
+  REPORT_NAME_DIGITAL(__LINE__, I_DIR_PIN)
1330
+#endif
1331
+#if PIN_EXISTS(I_ENABLE)
1332
+  REPORT_NAME_DIGITAL(__LINE__, I_ENABLE_PIN)
1333
+#endif
1334
+#if PIN_EXISTS(I_MAX)
1335
+  REPORT_NAME_DIGITAL(__LINE__, I_MAX_PIN)
1336
+#endif
1337
+#if PIN_EXISTS(I_MIN)
1338
+  REPORT_NAME_DIGITAL(__LINE__, I_MIN_PIN)
1339
+#endif
1340
+#if PIN_EXISTS(I_MS1)
1341
+  REPORT_NAME_DIGITAL(__LINE__, I_MS1_PIN)
1342
+#endif
1343
+#if PIN_EXISTS(I_MS2)
1344
+  REPORT_NAME_DIGITAL(__LINE__, I_MS2_PIN)
1345
+#endif
1346
+#if PIN_EXISTS(I_MS3)
1347
+  REPORT_NAME_DIGITAL(__LINE__, I_MS3_PIN)
1348
+#endif
1349
+#if PIN_EXISTS(I_STEP)
1350
+  REPORT_NAME_DIGITAL(__LINE__, I_STEP_PIN)
1351
+#endif
1352
+#if PIN_EXISTS(I_STOP)
1353
+  REPORT_NAME_DIGITAL(__LINE__, I_STOP_PIN)
1354
+#endif
1355
+#if PIN_EXISTS(J_ATT)
1356
+  REPORT_NAME_DIGITAL(__LINE__, J_ATT_PIN)
1357
+#endif
1358
+#if PIN_EXISTS(J_CS)
1359
+  REPORT_NAME_DIGITAL(__LINE__, J_CS_PIN)
1360
+#endif
1361
+#if PIN_EXISTS(J_DIR)
1362
+  REPORT_NAME_DIGITAL(__LINE__, J_DIR_PIN)
1363
+#endif
1364
+#if PIN_EXISTS(J_ENABLE)
1365
+  REPORT_NAME_DIGITAL(__LINE__, J_ENABLE_PIN)
1366
+#endif
1367
+#if PIN_EXISTS(J_MAX)
1368
+  REPORT_NAME_DIGITAL(__LINE__, J_MAX_PIN)
1369
+#endif
1370
+#if PIN_EXISTS(J_MIN)
1371
+  REPORT_NAME_DIGITAL(__LINE__, J_MIN_PIN)
1372
+#endif
1373
+#if PIN_EXISTS(J_MS1)
1374
+  REPORT_NAME_DIGITAL(__LINE__, J_MS1_PIN)
1375
+#endif
1376
+#if PIN_EXISTS(J_MS2)
1377
+  REPORT_NAME_DIGITAL(__LINE__, J_MS2_PIN)
1378
+#endif
1379
+#if PIN_EXISTS(J_MS3)
1380
+  REPORT_NAME_DIGITAL(__LINE__, J_MS3_PIN)
1381
+#endif
1382
+#if PIN_EXISTS(J_STEP)
1383
+  REPORT_NAME_DIGITAL(__LINE__, J_STEP_PIN)
1384
+#endif
1385
+#if PIN_EXISTS(J_STOP)
1386
+  REPORT_NAME_DIGITAL(__LINE__, J_STOP_PIN)
1387
+#endif
1388
+#if PIN_EXISTS(K_ATT)
1389
+  REPORT_NAME_DIGITAL(__LINE__, K_ATT_PIN)
1390
+#endif
1391
+#if PIN_EXISTS(K_CS)
1392
+  REPORT_NAME_DIGITAL(__LINE__, K_CS_PIN)
1393
+#endif
1394
+#if PIN_EXISTS(K_DIR)
1395
+  REPORT_NAME_DIGITAL(__LINE__, K_DIR_PIN)
1396
+#endif
1397
+#if PIN_EXISTS(K_ENABLE)
1398
+  REPORT_NAME_DIGITAL(__LINE__, K_ENABLE_PIN)
1399
+#endif
1400
+#if PIN_EXISTS(K_MAX)
1401
+  REPORT_NAME_DIGITAL(__LINE__, K_MAX_PIN)
1402
+#endif
1403
+#if PIN_EXISTS(K_MIN)
1404
+  REPORT_NAME_DIGITAL(__LINE__, K_MIN_PIN)
1405
+#endif
1406
+#if PIN_EXISTS(K_MS1)
1407
+  REPORT_NAME_DIGITAL(__LINE__, K_MS1_PIN)
1408
+#endif
1409
+#if PIN_EXISTS(K_MS2)
1410
+  REPORT_NAME_DIGITAL(__LINE__, K_MS2_PIN)
1411
+#endif
1412
+#if PIN_EXISTS(K_MS3)
1413
+  REPORT_NAME_DIGITAL(__LINE__, K_MS3_PIN)
1414
+#endif
1415
+#if PIN_EXISTS(K_STEP)
1416
+  REPORT_NAME_DIGITAL(__LINE__, K_STEP_PIN)
1417
+#endif
1418
+#if PIN_EXISTS(K_STOP)
1419
+  REPORT_NAME_DIGITAL(__LINE__, K_STOP_PIN)
1420
+#endif
1322 1421
 #if PIN_EXISTS(ZRIB_V20_D6)
1323 1422
   REPORT_NAME_DIGITAL(__LINE__, ZRIB_V20_D6_PIN)
1324 1423
 #endif

+ 98
- 23
Marlin/src/pins/pins_postprocess.h View File

@@ -402,40 +402,89 @@
402 402
   #define X_STOP_PIN X_MAX_PIN
403 403
 #endif
404 404
 
405
-#ifdef Y_STOP_PIN
406
-  #if Y_HOME_TO_MIN
407
-    #define Y_MIN_PIN Y_STOP_PIN
408
-    #ifndef Y_MAX_PIN
409
-      #define Y_MAX_PIN -1
405
+#if HAS_Y_AXIS
406
+  #ifdef Y_STOP_PIN
407
+    #if Y_HOME_TO_MIN
408
+      #define Y_MIN_PIN Y_STOP_PIN
409
+      #ifndef Y_MAX_PIN
410
+        #define Y_MAX_PIN -1
411
+      #endif
412
+    #else
413
+      #define Y_MAX_PIN Y_STOP_PIN
414
+      #ifndef Y_MIN_PIN
415
+        #define Y_MIN_PIN -1
416
+      #endif
410 417
     #endif
418
+  #elif Y_HOME_TO_MIN
419
+    #define Y_STOP_PIN Y_MIN_PIN
411 420
   #else
412
-    #define Y_MAX_PIN Y_STOP_PIN
413
-    #ifndef Y_MIN_PIN
414
-      #define Y_MIN_PIN -1
421
+    #define Y_STOP_PIN Y_MAX_PIN
422
+  #endif
423
+#endif
424
+
425
+#if HAS_Z_AXIS
426
+  #ifdef Z_STOP_PIN
427
+    #if Z_HOME_TO_MIN
428
+      #define Z_MIN_PIN Z_STOP_PIN
429
+      #ifndef Z_MAX_PIN
430
+        #define Z_MAX_PIN -1
431
+      #endif
432
+    #else
433
+      #define Z_MAX_PIN Z_STOP_PIN
434
+      #ifndef Z_MIN_PIN
435
+        #define Z_MIN_PIN -1
436
+      #endif
437
+    #endif
438
+  #elif Z_HOME_TO_MIN
439
+    #define Z_STOP_PIN Z_MIN_PIN
440
+  #else
441
+    #define Z_STOP_PIN Z_MAX_PIN
442
+  #endif
443
+#endif
444
+
445
+#if LINEAR_AXES >= 4
446
+  #ifdef I_STOP_PIN
447
+    #if I_HOME_TO_MIN
448
+      #define I_MIN_PIN I_STOP_PIN
449
+      #define I_MAX_PIN -1
450
+    #else
451
+      #define I_MIN_PIN -1
452
+      #define I_MAX_PIN I_STOP_PIN
415 453
     #endif
416 454
   #endif
417
-#elif Y_HOME_TO_MIN
418
-  #define Y_STOP_PIN Y_MIN_PIN
419 455
 #else
420
-  #define Y_STOP_PIN Y_MAX_PIN
456
+  #undef I_MIN_PIN
457
+  #undef I_MAX_PIN
421 458
 #endif
422 459
 
423
-#ifdef Z_STOP_PIN
424
-  #if Z_HOME_TO_MIN
425
-    #define Z_MIN_PIN Z_STOP_PIN
426
-    #ifndef Z_MAX_PIN
427
-      #define Z_MAX_PIN -1
460
+#if LINEAR_AXES >= 5
461
+  #ifdef J_STOP_PIN
462
+    #if J_HOME_TO_MIN
463
+      #define J_MIN_PIN J_STOP_PIN
464
+      #define J_MAX_PIN -1
465
+    #else
466
+      #define J_MIN_PIN -1
467
+      #define J_MAX_PIN J_STOP_PIN
428 468
     #endif
429
-  #else
430
-    #define Z_MAX_PIN Z_STOP_PIN
431
-    #ifndef Z_MIN_PIN
432
-      #define Z_MIN_PIN -1
469
+  #endif
470
+#else
471
+  #undef J_MIN_PIN
472
+  #undef J_MAX_PIN
473
+#endif
474
+
475
+#if LINEAR_AXES >= 6
476
+  #ifdef K_STOP_PIN
477
+    #if K_HOME_TO_MIN
478
+      #define K_MIN_PIN K_STOP_PIN
479
+      #define K_MAX_PIN -1
480
+    #else
481
+      #define K_MIN_PIN -1
482
+      #define K_MAX_PIN K_STOP_PIN
433 483
     #endif
434 484
   #endif
435
-#elif Z_HOME_TO_MIN
436
-  #define Z_STOP_PIN Z_MIN_PIN
437 485
 #else
438
-  #define Z_STOP_PIN Z_MAX_PIN
486
+  #undef K_MIN_PIN
487
+  #undef K_MAX_PIN
439 488
 #endif
440 489
 
441 490
 // Filament Sensor first pin alias
@@ -863,6 +912,19 @@
863 912
   #undef Z_MAX_PIN
864 913
   #define Z_MAX_PIN          -1
865 914
 #endif
915
+#if DISABLED(USE_IMAX_PLUG)
916
+  #undef I_MAX_PIN
917
+  #define I_MAX_PIN          -1
918
+#endif
919
+#if DISABLED(USE_JMAX_PLUG)
920
+  #undef J_MAX_PIN
921
+  #define J_MAX_PIN          -1
922
+#endif
923
+#if DISABLED(USE_KMAX_PLUG)
924
+  #undef K_MAX_PIN
925
+  #define K_MAX_PIN          -1
926
+#endif
927
+
866 928
 #if DISABLED(USE_XMIN_PLUG)
867 929
   #undef X_MIN_PIN
868 930
   #define X_MIN_PIN          -1
@@ -906,6 +968,19 @@
906 968
   #undef Z4_MAX_PIN
907 969
 #endif
908 970
 
971
+#if DISABLED(USE_IMIN_PLUG)
972
+  #undef I_MIN_PIN
973
+  #define I_MIN_PIN          -1
974
+#endif
975
+#if DISABLED(USE_JMIN_PLUG)
976
+  #undef J_MIN_PIN
977
+  #define J_MIN_PIN          -1
978
+#endif
979
+#if DISABLED(USE_KMIN_PLUG)
980
+  #undef K_MIN_PIN
981
+  #define K_MIN_PIN          -1
982
+#endif
983
+
909 984
 //
910 985
 // Default DOGLCD SPI delays
911 986
 //

+ 204
- 64
Marlin/src/pins/sensitive_pins.h View File

@@ -63,81 +63,220 @@
63 63
 
64 64
 #define _X_PINS X_STEP_PIN, X_DIR_PIN, _X_ENABLE_PIN _X_MIN _X_MAX _X_MS1 _X_MS2 _X_MS3 _X_CS
65 65
 
66
-#if PIN_EXISTS(Y_MIN)
67
-  #define _Y_MIN Y_MIN_PIN,
68
-#else
69
-  #define _Y_MIN
70
-#endif
71
-#if PIN_EXISTS(Y_MAX)
72
-  #define _Y_MAX Y_MAX_PIN,
73
-#else
74
-  #define _Y_MAX
75
-#endif
76
-#if PIN_EXISTS(Y_CS) && AXIS_HAS_SPI(Y)
77
-  #define _Y_CS Y_CS_PIN,
78
-#else
79
-  #define _Y_CS
80
-#endif
81
-#if PIN_EXISTS(Y_MS1)
82
-  #define _Y_MS1 Y_MS1_PIN,
83
-#else
84
-  #define _Y_MS1
85
-#endif
86
-#if PIN_EXISTS(Y_MS2)
87
-  #define _Y_MS2 Y_MS2_PIN,
88
-#else
89
-  #define _Y_MS2
90
-#endif
91
-#if PIN_EXISTS(Y_MS3)
92
-  #define _Y_MS3 Y_MS3_PIN,
93
-#else
94
-  #define _Y_MS3
95
-#endif
96
-#if PIN_EXISTS(Y_ENABLE)
97
-  #define _Y_ENABLE_PIN Y_ENABLE_PIN,
98
-#else
99
-  #define _Y_ENABLE_PIN
100
-#endif
66
+#if HAS_Y_AXIS
101 67
 
102
-#define _Y_PINS Y_STEP_PIN, Y_DIR_PIN, _Y_ENABLE_PIN _Y_MIN _Y_MAX _Y_MS1 _Y_MS2 _Y_MS3 _Y_CS
68
+  #if PIN_EXISTS(Y_MIN)
69
+    #define _Y_MIN Y_MIN_PIN,
70
+  #else
71
+    #define _Y_MIN
72
+  #endif
73
+  #if PIN_EXISTS(Y_MAX)
74
+    #define _Y_MAX Y_MAX_PIN,
75
+  #else
76
+    #define _Y_MAX
77
+  #endif
78
+  #if PIN_EXISTS(Y_CS) && AXIS_HAS_SPI(Y)
79
+    #define _Y_CS Y_CS_PIN,
80
+  #else
81
+    #define _Y_CS
82
+  #endif
83
+  #if PIN_EXISTS(Y_MS1)
84
+    #define _Y_MS1 Y_MS1_PIN,
85
+  #else
86
+    #define _Y_MS1
87
+  #endif
88
+  #if PIN_EXISTS(Y_MS2)
89
+    #define _Y_MS2 Y_MS2_PIN,
90
+  #else
91
+    #define _Y_MS2
92
+  #endif
93
+  #if PIN_EXISTS(Y_MS3)
94
+    #define _Y_MS3 Y_MS3_PIN,
95
+  #else
96
+    #define _Y_MS3
97
+  #endif
98
+  #if PIN_EXISTS(Y_ENABLE)
99
+    #define _Y_ENABLE_PIN Y_ENABLE_PIN,
100
+  #else
101
+    #define _Y_ENABLE_PIN
102
+  #endif
103
+
104
+  #define _Y_PINS Y_STEP_PIN, Y_DIR_PIN, _Y_ENABLE_PIN _Y_MIN _Y_MAX _Y_MS1 _Y_MS2 _Y_MS3 _Y_CS
103 105
 
104
-#if PIN_EXISTS(Z_MIN)
105
-  #define _Z_MIN Z_MIN_PIN,
106
-#else
107
-  #define _Z_MIN
108
-#endif
109
-#if PIN_EXISTS(Z_MAX)
110
-  #define _Z_MAX Z_MAX_PIN,
111
-#else
112
-  #define _Z_MAX
113
-#endif
114
-#if PIN_EXISTS(Z_CS) && AXIS_HAS_SPI(Z)
115
-  #define _Z_CS Z_CS_PIN,
116 106
 #else
117
-  #define _Z_CS
107
+
108
+  #define _Y_PINS
109
+
118 110
 #endif
119
-#if PIN_EXISTS(Z_MS1)
120
-  #define _Z_MS1 Z_MS1_PIN,
111
+
112
+#if HAS_Z_AXIS
113
+
114
+  #if PIN_EXISTS(Z_MIN)
115
+    #define _Z_MIN Z_MIN_PIN,
116
+  #else
117
+    #define _Z_MIN
118
+  #endif
119
+  #if PIN_EXISTS(Z_MAX)
120
+    #define _Z_MAX Z_MAX_PIN,
121
+  #else
122
+    #define _Z_MAX
123
+  #endif
124
+  #if PIN_EXISTS(Z_CS) && AXIS_HAS_SPI(Z)
125
+    #define _Z_CS Z_CS_PIN,
126
+  #else
127
+    #define _Z_CS
128
+  #endif
129
+  #if PIN_EXISTS(Z_MS1)
130
+    #define _Z_MS1 Z_MS1_PIN,
131
+  #else
132
+    #define _Z_MS1
133
+  #endif
134
+  #if PIN_EXISTS(Z_MS2)
135
+    #define _Z_MS2 Z_MS2_PIN,
136
+  #else
137
+    #define _Z_MS2
138
+  #endif
139
+  #if PIN_EXISTS(Z_MS3)
140
+    #define _Z_MS3 Z_MS3_PIN,
141
+  #else
142
+    #define _Z_MS3
143
+  #endif
144
+  #if PIN_EXISTS(Z_ENABLE)
145
+    #define _Z_ENABLE_PIN Z_ENABLE_PIN,
146
+  #else
147
+    #define _Z_ENABLE_PIN
148
+  #endif
149
+
150
+  #define _Z_PINS Z_STEP_PIN, Z_DIR_PIN, _Z_ENABLE_PIN _Z_MIN _Z_MAX _Z_MS1 _Z_MS2 _Z_MS3 _Z_CS
151
+
121 152
 #else
122
-  #define _Z_MS1
153
+
154
+  #define _Z_PINS
155
+
123 156
 #endif
124
-#if PIN_EXISTS(Z_MS2)
125
-  #define _Z_MS2 Z_MS2_PIN,
157
+
158
+#if LINEAR_AXES >= 4
159
+
160
+  #if PIN_EXISTS(I_MIN)
161
+    #define _I_MIN I_MIN_PIN,
162
+  #else
163
+    #define _I_MIN
164
+  #endif
165
+  #if PIN_EXISTS(I_MAX)
166
+    #define _I_MAX I_MAX_PIN,
167
+  #else
168
+    #define _I_MAX
169
+  #endif
170
+  #if PIN_EXISTS(I_CS)
171
+    #define _I_CS I_CS_PIN,
172
+  #else
173
+    #define _I_CS
174
+  #endif
175
+  #if PIN_EXISTS(I_MS1)
176
+    #define _I_MS1 I_MS1_PIN,
177
+  #else
178
+    #define _I_MS1
179
+  #endif
180
+  #if PIN_EXISTS(I_MS2)
181
+    #define _I_MS2 I_MS2_PIN,
182
+  #else
183
+    #define _I_MS2
184
+  #endif
185
+  #if PIN_EXISTS(I_MS3)
186
+    #define _I_MS3 I_MS3_PIN,
187
+  #else
188
+    #define _I_MS3
189
+  #endif
190
+
191
+  #define _I_PINS I_STEP_PIN, I_DIR_PIN, I_ENABLE_PIN, _I_MIN _I_MAX _I_MS1 _I_MS2 _I_MS3 _I_CS
192
+
126 193
 #else
127
-  #define _Z_MS2
194
+
195
+  #define _I_PINS
196
+
128 197
 #endif
129
-#if PIN_EXISTS(Z_MS3)
130
-  #define _Z_MS3 Z_MS3_PIN,
198
+
199
+#if LINEAR_AXES >= 5
200
+
201
+  #if PIN_EXISTS(J_MIN)
202
+    #define _J_MIN J_MIN_PIN,
203
+  #else
204
+    #define _J_MIN
205
+  #endif
206
+  #if PIN_EXISTS(J_MAX)
207
+    #define _J_MAX J_MAX_PIN,
208
+  #else
209
+    #define _J_MAX
210
+  #endif
211
+  #if PIN_EXISTS(J_CS)
212
+    #define _J_CS J_CS_PIN,
213
+  #else
214
+    #define _J_CS
215
+  #endif
216
+  #if PIN_EXISTS(J_MS1)
217
+    #define _J_MS1 J_MS1_PIN,
218
+  #else
219
+    #define _J_MS1
220
+  #endif
221
+  #if PIN_EXISTS(J_MS2)
222
+    #define _J_MS2 J_MS2_PIN,
223
+  #else
224
+    #define _J_MS2
225
+  #endif
226
+  #if PIN_EXISTS(J_MS3)
227
+    #define _J_MS3 J_MS3_PIN,
228
+  #else
229
+    #define _J_MS3
230
+  #endif
231
+
232
+  #define _J_PINS J_STEP_PIN, J_DIR_PIN, J_ENABLE_PIN, _J_MIN _J_MAX _J_MS1 _J_MS2 _J_MS3 _J_CS
233
+
131 234
 #else
132
-  #define _Z_MS3
235
+
236
+  #define _J_PINS
237
+
133 238
 #endif
134
-#if PIN_EXISTS(Z_ENABLE)
135
-  #define _Z_ENABLE_PIN Z_ENABLE_PIN,
239
+
240
+#if LINEAR_AXES >= 6
241
+
242
+  #if PIN_EXISTS(K_MIN)
243
+    #define _K_MIN K_MIN_PIN,
244
+  #else
245
+    #define _K_MIN
246
+  #endif
247
+  #if PIN_EXISTS(K_MAX)
248
+    #define _K_MAX K_MAX_PIN,
249
+  #else
250
+    #define _K_MAX
251
+  #endif
252
+  #if PIN_EXISTS(K_CS)
253
+    #define _K_CS K_CS_PIN,
254
+  #else
255
+    #define _K_CS
256
+  #endif
257
+  #if PIN_EXISTS(K_MS1)
258
+    #define _K_MS1 K_MS1_PIN,
259
+  #else
260
+    #define _K_MS1
261
+  #endif
262
+  #if PIN_EXISTS(K_MS2)
263
+    #define _K_MS2 K_MS2_PIN,
264
+  #else
265
+    #define _K_MS2
266
+  #endif
267
+  #if PIN_EXISTS(K_MS3)
268
+    #define _K_MS3 K_MS3_PIN,
269
+  #else
270
+    #define _K_MS3
271
+  #endif
272
+
273
+  #define _K_PINS K_STEP_PIN, K_DIR_PIN, K_ENABLE_PIN, _K_MIN _K_MAX _K_MS1 _K_MS2 _K_MS3 _K_CS
274
+
136 275
 #else
137
-  #define _Z_ENABLE_PIN
138
-#endif
139 276
 
140
-#define _Z_PINS Z_STEP_PIN, Z_DIR_PIN, _Z_ENABLE_PIN _Z_MIN _Z_MAX _Z_MS1 _Z_MS2 _Z_MS3 _Z_CS
277
+  #define _K_PINS
278
+
279
+#endif
141 280
 
142 281
 //
143 282
 // Extruder Chip Select, Digital Micro-steps
@@ -714,7 +853,8 @@
714 853
 #endif
715 854
 
716 855
 #define SENSITIVE_PINS { \
717
-  _X_PINS _Y_PINS _Z_PINS _X2_PINS _Y2_PINS _Z2_PINS _Z3_PINS _Z4_PINS _Z_PROBE \
856
+  _X_PINS _Y_PINS _Z_PINS _I_PINS _J_PINS _K_PINS \
857
+  _X2_PINS _Y2_PINS _Z2_PINS _Z3_PINS _Z4_PINS _Z_PROBE \
718 858
   _E0_PINS _E1_PINS _E2_PINS _E3_PINS _E4_PINS _E5_PINS _E6_PINS _E7_PINS \
719 859
   _H0_PINS _H1_PINS _H2_PINS _H3_PINS _H4_PINS _H5_PINS _H6_PINS _H7_PINS \
720 860
   _PS_ON _FAN0 _FAN1 _FAN2 _FAN3 _FAN4 _FAN5 _FAN6 _FAN7 _FANC \

+ 1
- 0
Marlin/src/sd/cardreader.cpp View File

@@ -59,6 +59,7 @@
59 59
 
60 60
 // extern
61 61
 
62
+PGMSTR(M21_STR, "M21");
62 63
 PGMSTR(M23_STR, "M23 %s");
63 64
 PGMSTR(M24_STR, "M24");
64 65
 

Loading…
Cancel
Save