Browse Source

✨ Support for up to 9 axes (linear, rotary) (#23112)

Co-authored-by: Scott Lahteine <thinkyhead@users.noreply.github.com>
DerAndere 2 years ago
parent
commit
e5b651f407
No account linked to committer's email address
100 changed files with 3932 additions and 799 deletions
  1. 107
    31
      Marlin/Configuration.h
  2. 131
    14
      Marlin/Configuration_adv.h
  3. 45
    0
      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. 45
    0
      Marlin/src/HAL/SAMD51/endstop_interrupts.h
  8. 6
    0
      Marlin/src/HAL/STM32/endstop_interrupts.h
  9. 6
    0
      Marlin/src/HAL/STM32F1/endstop_interrupts.h
  10. 6
    0
      Marlin/src/HAL/TEENSY31_32/endstop_interrupts.h
  11. 6
    0
      Marlin/src/HAL/TEENSY35_36/endstop_interrupts.h
  12. 12
    0
      Marlin/src/MarlinCore.cpp
  13. 5
    0
      Marlin/src/core/drivers.h
  14. 48
    0
      Marlin/src/core/language.h
  15. 13
    1
      Marlin/src/core/macros.h
  16. 6
    2
      Marlin/src/core/serial.cpp
  17. 8
    13
      Marlin/src/core/serial.h
  18. 207
    177
      Marlin/src/core/types.h
  19. 1
    1
      Marlin/src/core/utility.cpp
  20. 6
    3
      Marlin/src/core/utility.h
  21. 4
    4
      Marlin/src/feature/backlash.cpp
  22. 36
    0
      Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp
  23. 2
    2
      Marlin/src/feature/encoder_i2c.cpp
  24. 1
    1
      Marlin/src/feature/joystick.cpp
  25. 3
    3
      Marlin/src/feature/powerloss.cpp
  26. 24
    18
      Marlin/src/feature/stepper_driver_safety.cpp
  27. 57
    0
      Marlin/src/feature/tmc_util.cpp
  28. 1
    1
      Marlin/src/feature/tmc_util.h
  29. 36
    0
      Marlin/src/gcode/bedlevel/abl/G29.cpp
  30. 37
    0
      Marlin/src/gcode/bedlevel/mbl/G29.cpp
  31. 80
    46
      Marlin/src/gcode/calibrate/G28.cpp
  32. 5
    5
      Marlin/src/gcode/calibrate/G33.cpp
  33. 130
    6
      Marlin/src/gcode/calibrate/G425.cpp
  34. 16
    10
      Marlin/src/gcode/calibrate/M425.cpp
  35. 1
    1
      Marlin/src/gcode/calibrate/M666.cpp
  36. 28
    15
      Marlin/src/gcode/config/M200-M205.cpp
  37. 27
    16
      Marlin/src/gcode/config/M217.cpp
  38. 9
    6
      Marlin/src/gcode/config/M92.cpp
  39. 20
    11
      Marlin/src/gcode/control/M17_M18_M84.cpp
  40. 1
    1
      Marlin/src/gcode/control/M605.cpp
  41. 16
    12
      Marlin/src/gcode/feature/digipot/M907-M910.cpp
  42. 6
    2
      Marlin/src/gcode/feature/pause/G60.cpp
  43. 2
    2
      Marlin/src/gcode/feature/pause/G61.cpp
  44. 13
    5
      Marlin/src/gcode/feature/pause/M125.cpp
  45. 18
    13
      Marlin/src/gcode/feature/pause/M600.cpp
  46. 25
    4
      Marlin/src/gcode/feature/trinamic/M569.cpp
  47. 33
    1
      Marlin/src/gcode/feature/trinamic/M906.cpp
  48. 79
    4
      Marlin/src/gcode/feature/trinamic/M911-M914.cpp
  49. 5
    2
      Marlin/src/gcode/gcode.cpp
  50. 3
    2
      Marlin/src/gcode/gcode.h
  51. 1
    1
      Marlin/src/gcode/geometry/G53-G59.cpp
  52. 5
    5
      Marlin/src/gcode/geometry/G92.cpp
  53. 20
    11
      Marlin/src/gcode/geometry/M206_M428.cpp
  54. 14
    2
      Marlin/src/gcode/host/M114.cpp
  55. 2
    2
      Marlin/src/gcode/host/M115.cpp
  56. 6
    3
      Marlin/src/gcode/motion/G0_G1.cpp
  57. 55
    19
      Marlin/src/gcode/motion/G2_G3.cpp
  58. 2
    2
      Marlin/src/gcode/motion/M290.cpp
  59. 1
    1
      Marlin/src/gcode/parser.cpp
  60. 19
    7
      Marlin/src/gcode/parser.h
  61. 2
    2
      Marlin/src/gcode/probe/G38.cpp
  62. 90
    13
      Marlin/src/inc/Conditionals_LCD.h
  63. 39
    24
      Marlin/src/inc/Conditionals_adv.h
  64. 254
    3
      Marlin/src/inc/Conditionals_post.h
  65. 233
    37
      Marlin/src/inc/SanityCheck.h
  66. 1
    1
      Marlin/src/inc/Version.h
  67. 157
    0
      Marlin/src/inc/Warnings.cpp
  68. 1
    1
      Marlin/src/lcd/extui/dgus_reloaded/DGUSTxHandler.cpp
  69. 30
    0
      Marlin/src/lcd/extui/ui_api.cpp
  70. 1
    1
      Marlin/src/lcd/extui/ui_api.h
  71. 27
    0
      Marlin/src/lcd/language/language_en.h
  72. 16
    12
      Marlin/src/lcd/menu/menu_advanced.cpp
  73. 9
    0
      Marlin/src/lcd/menu/menu_backlash.cpp
  74. 36
    0
      Marlin/src/lcd/menu/menu_motion.cpp
  75. 3
    0
      Marlin/src/lcd/menu/menu_tmc.cpp
  76. 3
    3
      Marlin/src/libs/L64XX/L64XX_Marlin.cpp
  77. 1
    1
      Marlin/src/libs/L64XX/L64XX_Marlin.h
  78. 6
    0
      Marlin/src/module/delta.cpp
  79. 272
    6
      Marlin/src/module/endstops.cpp
  80. 7
    1
      Marlin/src/module/endstops.h
  81. 208
    41
      Marlin/src/module/motion.cpp
  82. 52
    7
      Marlin/src/module/motion.h
  83. 205
    90
      Marlin/src/module/planner.cpp
  84. 4
    2
      Marlin/src/module/planner.h
  85. 4
    1
      Marlin/src/module/planner_bezier.cpp
  86. 4
    3
      Marlin/src/module/probe.cpp
  87. 1
    1
      Marlin/src/module/probe.h
  88. 1
    1
      Marlin/src/module/scara.cpp
  89. 70
    25
      Marlin/src/module/settings.cpp
  90. 212
    18
      Marlin/src/module/stepper.cpp
  91. 18
    9
      Marlin/src/module/stepper.h
  92. 18
    0
      Marlin/src/module/stepper/L64xx.cpp
  93. 66
    0
      Marlin/src/module/stepper/L64xx.h
  94. 18
    0
      Marlin/src/module/stepper/TMC26X.cpp
  95. 24
    0
      Marlin/src/module/stepper/TMC26X.h
  96. 124
    0
      Marlin/src/module/stepper/indirection.h
  97. 94
    7
      Marlin/src/module/stepper/trinamic.cpp
  98. 54
    0
      Marlin/src/module/stepper/trinamic.h
  99. 21
    1
      Marlin/src/module/tool_change.cpp
  100. 0
    0
      Marlin/src/module/tool_change.h

+ 107
- 31
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 02000903
38
+#define CONFIGURATION_H_VERSION 02010000
39 39
 
40 40
 //===========================================================================
41 41
 //============================= Getting Started =============================
@@ -150,9 +150,9 @@
150 150
 //#define MACHINE_UUID "00000000-0000-0000-0000-000000000000"
151 151
 
152 152
 /**
153
- * Define the number of coordinated linear axes.
153
+ * Define the number of coordinated axes.
154 154
  * See https://github.com/DerAndere1/Marlin/wiki
155
- * Each linear axis gets its own stepper control and endstop:
155
+ * Each axis gets its own stepper control and endstop:
156 156
  *
157 157
  *   Steppers: *_STEP_PIN, *_ENABLE_PIN, *_DIR_PIN, *_ENABLE_ON
158 158
  *   Endstops: *_STOP_PIN, USE_*MIN_PLUG, USE_*MAX_PLUG
@@ -161,31 +161,50 @@
161 161
  *             DEFAULT_MAX_ACCELERATION, AXIS_RELATIVE_MODES,
162 162
  *             MICROSTEP_MODES, MANUAL_FEEDRATE
163 163
  *
164
- * :[3, 4, 5, 6]
164
+ * :[3, 4, 5, 6, 7, 8, 9]
165 165
  */
166
-//#define LINEAR_AXES 3
166
+//#define NUM_AXES 3
167 167
 
168 168
 /**
169
- * Axis codes for additional axes:
170
- * This defines the axis code that is used in G-code commands to
171
- * reference a specific axis.
172
- * 'A' for rotational axis parallel to X
173
- * 'B' for rotational axis parallel to Y
174
- * 'C' for rotational axis parallel to Z
175
- * 'U' for secondary linear axis parallel to X
176
- * 'V' for secondary linear axis parallel to Y
177
- * 'W' for secondary linear axis parallel to Z
178
- * Regardless of the settings, firmware-internal axis IDs are
179
- * I (AXIS4), J (AXIS5), K (AXIS6).
169
+ * Additional Axis Settings
170
+ *
171
+ * Define AXISn_ROTATES for all axes that rotate or pivot.
172
+ * Rotational axis coordinates are expressed in degrees.
173
+ *
174
+ * AXISn_NAME defines the letter used to refer to the axis in (most) G-code commands.
175
+ * By convention the names and roles are typically:
176
+ *   'A' : Rotational axis parallel to X
177
+ *   'B' : Rotational axis parallel to Y
178
+ *   'C' : Rotational axis parallel to Z
179
+ *   'U' : Secondary linear axis parallel to X
180
+ *   'V' : Secondary linear axis parallel to Y
181
+ *   'W' : Secondary linear axis parallel to Z
182
+ *
183
+ * Regardless of these settings the axes are internally named I, J, K, U, V, W.
180 184
  */
181
-#if LINEAR_AXES >= 4
185
+#if NUM_AXES >= 4
182 186
   #define AXIS4_NAME 'A' // :['A', 'B', 'C', 'U', 'V', 'W']
187
+  #define AXIS4_ROTATES
188
+#endif
189
+#if NUM_AXES >= 5
190
+  #define AXIS5_NAME 'B' // :['B', 'C', 'U', 'V', 'W']
191
+  #define AXIS5_ROTATES
192
+#endif
193
+#if NUM_AXES >= 6
194
+  #define AXIS6_NAME 'C' // :['C', 'U', 'V', 'W']
195
+  #define AXIS6_ROTATES
196
+#endif
197
+#if NUM_AXES >= 7
198
+  #define AXIS7_NAME 'U' // :['U', 'V', 'W']
199
+  //#define AXIS7_ROTATES
183 200
 #endif
184
-#if LINEAR_AXES >= 5
185
-  #define AXIS5_NAME 'B' // :['A', 'B', 'C', 'U', 'V', 'W']
201
+#if NUM_AXES >= 8
202
+  #define AXIS8_NAME 'V' // :['V', 'W']
203
+  //#define AXIS8_ROTATES
186 204
 #endif
187
-#if LINEAR_AXES >= 6
188
-  #define AXIS6_NAME 'C' // :['A', 'B', 'C', 'U', 'V', 'W']
205
+#if NUM_AXES >= 9
206
+  #define AXIS9_NAME 'W' // :['W']
207
+  //#define AXIS9_ROTATES
189 208
 #endif
190 209
 
191 210
 // @section extruder
@@ -793,12 +812,18 @@
793 812
 //#define USE_IMIN_PLUG
794 813
 //#define USE_JMIN_PLUG
795 814
 //#define USE_KMIN_PLUG
815
+//#define USE_UMIN_PLUG
816
+//#define USE_VMIN_PLUG
817
+//#define USE_WMIN_PLUG
796 818
 //#define USE_XMAX_PLUG
797 819
 //#define USE_YMAX_PLUG
798 820
 //#define USE_ZMAX_PLUG
799 821
 //#define USE_IMAX_PLUG
800 822
 //#define USE_JMAX_PLUG
801 823
 //#define USE_KMAX_PLUG
824
+//#define USE_UMAX_PLUG
825
+//#define USE_VMAX_PLUG
826
+//#define USE_WMAX_PLUG
802 827
 
803 828
 // Enable pullup for all endstops to prevent a floating state
804 829
 #define ENDSTOPPULLUPS
@@ -810,12 +835,18 @@
810 835
   //#define ENDSTOPPULLUP_IMIN
811 836
   //#define ENDSTOPPULLUP_JMIN
812 837
   //#define ENDSTOPPULLUP_KMIN
838
+  //#define ENDSTOPPULLUP_UMIN
839
+  //#define ENDSTOPPULLUP_VMIN
840
+  //#define ENDSTOPPULLUP_WMIN
813 841
   //#define ENDSTOPPULLUP_XMAX
814 842
   //#define ENDSTOPPULLUP_YMAX
815 843
   //#define ENDSTOPPULLUP_ZMAX
816 844
   //#define ENDSTOPPULLUP_IMAX
817 845
   //#define ENDSTOPPULLUP_JMAX
818 846
   //#define ENDSTOPPULLUP_KMAX
847
+  //#define ENDSTOPPULLUP_UMAX
848
+  //#define ENDSTOPPULLUP_VMAX
849
+  //#define ENDSTOPPULLUP_WMAX
819 850
   //#define ENDSTOPPULLUP_ZMIN_PROBE
820 851
 #endif
821 852
 
@@ -829,12 +860,18 @@
829 860
   //#define ENDSTOPPULLDOWN_IMIN
830 861
   //#define ENDSTOPPULLDOWN_JMIN
831 862
   //#define ENDSTOPPULLDOWN_KMIN
863
+  //#define ENDSTOPPULLDOWN_UMIN
864
+  //#define ENDSTOPPULLDOWN_VMIN
865
+  //#define ENDSTOPPULLDOWN_WMIN
832 866
   //#define ENDSTOPPULLDOWN_XMAX
833 867
   //#define ENDSTOPPULLDOWN_YMAX
834 868
   //#define ENDSTOPPULLDOWN_ZMAX
835 869
   //#define ENDSTOPPULLDOWN_IMAX
836 870
   //#define ENDSTOPPULLDOWN_JMAX
837 871
   //#define ENDSTOPPULLDOWN_KMAX
872
+  //#define ENDSTOPPULLDOWN_UMAX
873
+  //#define ENDSTOPPULLDOWN_VMAX
874
+  //#define ENDSTOPPULLDOWN_WMAX
838 875
   //#define ENDSTOPPULLDOWN_ZMIN_PROBE
839 876
 #endif
840 877
 
@@ -845,12 +882,18 @@
845 882
 #define I_MIN_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop.
846 883
 #define J_MIN_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop.
847 884
 #define K_MIN_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop.
885
+#define U_MIN_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop.
886
+#define V_MIN_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop.
887
+#define W_MIN_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop.
848 888
 #define X_MAX_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop.
849 889
 #define Y_MAX_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop.
850 890
 #define Z_MAX_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop.
851 891
 #define I_MAX_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop.
852 892
 #define J_MAX_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop.
853 893
 #define K_MAX_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop.
894
+#define U_MAX_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop.
895
+#define V_MAX_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop.
896
+#define W_MAX_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop.
854 897
 #define Z_MIN_PROBE_ENDSTOP_INVERTING false // Set to true to invert the logic of the probe.
855 898
 
856 899
 /**
@@ -882,6 +925,9 @@
882 925
 //#define I_DRIVER_TYPE  A4988
883 926
 //#define J_DRIVER_TYPE  A4988
884 927
 //#define K_DRIVER_TYPE  A4988
928
+//#define U_DRIVER_TYPE  A4988
929
+//#define V_DRIVER_TYPE  A4988
930
+//#define W_DRIVER_TYPE  A4988
885 931
 #define E0_DRIVER_TYPE A4988
886 932
 //#define E1_DRIVER_TYPE A4988
887 933
 //#define E2_DRIVER_TYPE A4988
@@ -933,16 +979,16 @@
933 979
 //#define DISTINCT_E_FACTORS
934 980
 
935 981
 /**
936
- * Default Axis Steps Per Unit (steps/mm)
982
+ * Default Axis Steps Per Unit (linear=steps/mm, rotational=steps/°)
937 983
  * Override with M92
938
- *                                      X, Y, Z [, I [, J [, K]]], E0 [, E1[, E2...]]
984
+ *                                      X, Y, Z [, I [, J [, K...]]], E0 [, E1[, E2...]]
939 985
  */
940 986
 #define DEFAULT_AXIS_STEPS_PER_UNIT   { 80, 80, 400, 500 }
941 987
 
942 988
 /**
943
- * Default Max Feed Rate (mm/s)
989
+ * Default Max Feed Rate (linear=mm/s, rotational=°/s)
944 990
  * Override with M203
945
- *                                      X, Y, Z [, I [, J [, K]]], E0 [, E1[, E2...]]
991
+ *                                      X, Y, Z [, I [, J [, K...]]], E0 [, E1[, E2...]]
946 992
  */
947 993
 #define DEFAULT_MAX_FEEDRATE          { 300, 300, 5, 25 }
948 994
 
@@ -952,10 +998,10 @@
952 998
 #endif
953 999
 
954 1000
 /**
955
- * Default Max Acceleration (change/s) change = mm/s
1001
+ * Default Max Acceleration (speed change with time) (linear=mm/(s^2), rotational=°/(s^2))
956 1002
  * (Maximum start speed for accelerated moves)
957 1003
  * Override with M201
958
- *                                      X, Y, Z [, I [, J [, K]]], E0 [, E1[, E2...]]
1004
+ *                                      X, Y, Z [, I [, J [, K...]]], E0 [, E1[, E2...]]
959 1005
  */
960 1006
 #define DEFAULT_MAX_ACCELERATION      { 3000, 3000, 100, 10000 }
961 1007
 
@@ -965,7 +1011,7 @@
965 1011
 #endif
966 1012
 
967 1013
 /**
968
- * Default Acceleration (change/s) change = mm/s
1014
+ * Default Acceleration (speed change with time) (linear=mm/(s^2), rotational=°/(s^2))
969 1015
  * Override with M204
970 1016
  *
971 1017
  *   M204 P    Acceleration
@@ -978,7 +1024,7 @@
978 1024
 
979 1025
 /**
980 1026
  * Default Jerk limits (mm/s)
981
- * Override with M205 X Y Z E
1027
+ * Override with M205 X Y Z . . . E
982 1028
  *
983 1029
  * "Jerk" specifies the minimum speed change that requires acceleration.
984 1030
  * When changing speed and direction, if the difference is less than the
@@ -992,6 +1038,9 @@
992 1038
   //#define DEFAULT_IJERK  0.3
993 1039
   //#define DEFAULT_JJERK  0.3
994 1040
   //#define DEFAULT_KJERK  0.3
1041
+  //#define DEFAULT_UJERK  0.3
1042
+  //#define DEFAULT_VJERK  0.3
1043
+  //#define DEFAULT_WJERK  0.3
995 1044
 
996 1045
   //#define TRAVEL_EXTRA_XYJERK 0.0     // Additional jerk allowance for all travel moves
997 1046
 
@@ -1330,6 +1379,9 @@
1330 1379
 //#define I_ENABLE_ON 0
1331 1380
 //#define J_ENABLE_ON 0
1332 1381
 //#define K_ENABLE_ON 0
1382
+//#define U_ENABLE_ON 0
1383
+//#define V_ENABLE_ON 0
1384
+//#define W_ENABLE_ON 0
1333 1385
 
1334 1386
 // Disable axis steppers immediately when they're not being stepped.
1335 1387
 // WARNING: When motors turn off there is a chance of losing position accuracy!
@@ -1339,6 +1391,9 @@
1339 1391
 //#define DISABLE_I false
1340 1392
 //#define DISABLE_J false
1341 1393
 //#define DISABLE_K false
1394
+//#define DISABLE_U false
1395
+//#define DISABLE_V false
1396
+//#define DISABLE_W false
1342 1397
 
1343 1398
 // Turn off the display blinking that warns about possible accuracy reduction
1344 1399
 //#define DISABLE_REDUCED_ACCURACY_WARNING
@@ -1357,6 +1412,9 @@
1357 1412
 //#define INVERT_I_DIR false
1358 1413
 //#define INVERT_J_DIR false
1359 1414
 //#define INVERT_K_DIR false
1415
+//#define INVERT_U_DIR false
1416
+//#define INVERT_V_DIR false
1417
+//#define INVERT_W_DIR false
1360 1418
 
1361 1419
 // @section extruder
1362 1420
 
@@ -1395,6 +1453,9 @@
1395 1453
 //#define I_HOME_DIR -1
1396 1454
 //#define J_HOME_DIR -1
1397 1455
 //#define K_HOME_DIR -1
1456
+//#define U_HOME_DIR -1
1457
+//#define V_HOME_DIR -1
1458
+//#define W_HOME_DIR -1
1398 1459
 
1399 1460
 // @section machine
1400 1461
 
@@ -1402,7 +1463,7 @@
1402 1463
 #define X_BED_SIZE 200
1403 1464
 #define Y_BED_SIZE 200
1404 1465
 
1405
-// Travel limits (mm) after homing, corresponding to endstop positions.
1466
+// Travel limits (linear=mm, rotational=°) after homing, corresponding to endstop positions.
1406 1467
 #define X_MIN_POS 0
1407 1468
 #define Y_MIN_POS 0
1408 1469
 #define Z_MIN_POS 0
@@ -1415,6 +1476,12 @@
1415 1476
 //#define J_MAX_POS 50
1416 1477
 //#define K_MIN_POS 0
1417 1478
 //#define K_MAX_POS 50
1479
+//#define U_MIN_POS 0
1480
+//#define U_MAX_POS 50
1481
+//#define V_MIN_POS 0
1482
+//#define V_MAX_POS 50
1483
+//#define W_MIN_POS 0
1484
+//#define W_MAX_POS 50
1418 1485
 
1419 1486
 /**
1420 1487
  * Software Endstops
@@ -1434,6 +1501,9 @@
1434 1501
   #define MIN_SOFTWARE_ENDSTOP_I
1435 1502
   #define MIN_SOFTWARE_ENDSTOP_J
1436 1503
   #define MIN_SOFTWARE_ENDSTOP_K
1504
+  #define MIN_SOFTWARE_ENDSTOP_U
1505
+  #define MIN_SOFTWARE_ENDSTOP_V
1506
+  #define MIN_SOFTWARE_ENDSTOP_W
1437 1507
 #endif
1438 1508
 
1439 1509
 // Max software endstops constrain movement within maximum coordinate bounds
@@ -1445,6 +1515,9 @@
1445 1515
   #define MAX_SOFTWARE_ENDSTOP_I
1446 1516
   #define MAX_SOFTWARE_ENDSTOP_J
1447 1517
   #define MAX_SOFTWARE_ENDSTOP_K
1518
+  #define MAX_SOFTWARE_ENDSTOP_U
1519
+  #define MAX_SOFTWARE_ENDSTOP_V
1520
+  #define MAX_SOFTWARE_ENDSTOP_W
1448 1521
 #endif
1449 1522
 
1450 1523
 #if EITHER(MIN_SOFTWARE_ENDSTOPS, MAX_SOFTWARE_ENDSTOPS)
@@ -1759,6 +1832,9 @@
1759 1832
 //#define MANUAL_I_HOME_POS 0
1760 1833
 //#define MANUAL_J_HOME_POS 0
1761 1834
 //#define MANUAL_K_HOME_POS 0
1835
+//#define MANUAL_U_HOME_POS 0
1836
+//#define MANUAL_V_HOME_POS 0
1837
+//#define MANUAL_W_HOME_POS 0
1762 1838
 
1763 1839
 /**
1764 1840
  * Use "Z Safe Homing" to avoid homing with a Z probe outside the bed area.
@@ -1774,7 +1850,7 @@
1774 1850
   #define Z_SAFE_HOMING_Y_POINT Y_CENTER  // Y point for Z homing
1775 1851
 #endif
1776 1852
 
1777
-// Homing speeds (mm/min)
1853
+// Homing speeds (linear=mm/min, rotational=°/min)
1778 1854
 #define HOMING_FEEDRATE_MM_M { (50*60), (50*60), (4*60) }
1779 1855
 
1780 1856
 // Validate that endstops are triggered on homing moves

+ 131
- 14
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 02000903
33
+#define CONFIGURATION_ADV_H_VERSION 02010000
34 34
 
35 35
 //===========================================================================
36 36
 //============================= Thermal Settings ============================
@@ -843,12 +843,12 @@
843 843
  * the position of the toolhead relative to the workspace.
844 844
  */
845 845
 
846
-//#define SENSORLESS_BACKOFF_MM  { 2, 2, 0 }  // (mm) Backoff from endstops before sensorless homing
846
+//#define SENSORLESS_BACKOFF_MM  { 2, 2, 0 }  // (linear=mm, rotational=°) Backoff from endstops before sensorless homing
847 847
 
848
-#define HOMING_BUMP_MM      { 5, 5, 2 }       // (mm) Backoff from endstops after first bump
848
+#define HOMING_BUMP_MM      { 5, 5, 2 }       // (linear=mm, rotational=°) Backoff from endstops after first bump
849 849
 #define HOMING_BUMP_DIVISOR { 2, 2, 4 }       // Re-Bump Speed Divisor (Divides the Homing Feedrate)
850 850
 
851
-//#define HOMING_BACKOFF_POST_MM { 2, 2, 2 }  // (mm) Backoff from endstops after homing
851
+//#define HOMING_BACKOFF_POST_MM { 2, 2, 2 }  // (linear=mm, rotational=°) Backoff from endstops after homing
852 852
 
853 853
 //#define QUICK_HOME                          // If G28 contains XY do a diagonal move first
854 854
 //#define HOME_Y_BEFORE_X                     // If G28 contains XY home Y before X
@@ -1034,6 +1034,9 @@
1034 1034
 #define INVERT_I_STEP_PIN false
1035 1035
 #define INVERT_J_STEP_PIN false
1036 1036
 #define INVERT_K_STEP_PIN false
1037
+#define INVERT_U_STEP_PIN false
1038
+#define INVERT_V_STEP_PIN false
1039
+#define INVERT_W_STEP_PIN false
1037 1040
 #define INVERT_E_STEP_PIN false
1038 1041
 
1039 1042
 /**
@@ -1048,11 +1051,14 @@
1048 1051
 #define DISABLE_INACTIVE_I true
1049 1052
 #define DISABLE_INACTIVE_J true
1050 1053
 #define DISABLE_INACTIVE_K true
1054
+#define DISABLE_INACTIVE_U true
1055
+#define DISABLE_INACTIVE_V true
1056
+#define DISABLE_INACTIVE_W true
1051 1057
 #define DISABLE_INACTIVE_E true
1052 1058
 
1053 1059
 // Default Minimum Feedrates for printing and travel moves
1054
-#define DEFAULT_MINIMUMFEEDRATE       0.0     // (mm/s) Minimum feedrate. Set with M205 S.
1055
-#define DEFAULT_MINTRAVELFEEDRATE     0.0     // (mm/s) Minimum travel feedrate. Set with M205 T.
1060
+#define DEFAULT_MINIMUMFEEDRATE       0.0     // (mm/s. °/s for rotational-only moves) Minimum feedrate. Set with M205 S.
1061
+#define DEFAULT_MINTRAVELFEEDRATE     0.0     // (mm/s. °/s for rotational-only moves) Minimum travel feedrate. Set with M205 T.
1056 1062
 
1057 1063
 // Minimum time that a segment needs to take as the buffer gets emptied
1058 1064
 #define DEFAULT_MINSEGMENTTIME        20000   // (µs) Set with M205 B.
@@ -1088,7 +1094,7 @@
1088 1094
 #if ENABLED(BACKLASH_COMPENSATION)
1089 1095
   // Define values for backlash distance and correction.
1090 1096
   // If BACKLASH_GCODE is enabled these values are the defaults.
1091
-  #define BACKLASH_DISTANCE_MM { 0, 0, 0 } // (mm) One value for each linear axis
1097
+  #define BACKLASH_DISTANCE_MM { 0, 0, 0 } // (linear=mm, rotational=°) One value for each linear axis
1092 1098
   #define BACKLASH_CORRECTION    0.0       // 0.0 = no correction; 1.0 = full correction
1093 1099
 
1094 1100
   // Add steps for motor direction changes on CORE kinematics
@@ -1165,6 +1171,12 @@
1165 1171
   //#define CALIBRATION_MEASURE_JMAX
1166 1172
   //#define CALIBRATION_MEASURE_KMIN
1167 1173
   //#define CALIBRATION_MEASURE_KMAX
1174
+  //#define CALIBRATION_MEASURE_UMIN
1175
+  //#define CALIBRATION_MEASURE_UMAX
1176
+  //#define CALIBRATION_MEASURE_VMIN
1177
+  //#define CALIBRATION_MEASURE_VMAX
1178
+  //#define CALIBRATION_MEASURE_WMIN
1179
+  //#define CALIBRATION_MEASURE_WMAX
1168 1180
 
1169 1181
   // Probing at the exact top center only works if the center is flat. If
1170 1182
   // probing on a screwhead or hollow washer, probe near the edges.
@@ -2013,6 +2025,21 @@
2013 2025
 // @section leveling
2014 2026
 
2015 2027
 /**
2028
+ * Use Safe Bed Leveling coordinates to move axes to a useful position before bed probing.
2029
+ * For example, after homing a rotational axis the Z probe might not be perpendicular to the bed.
2030
+ * Choose values the orient the bed horizontally and the Z-probe vertically.
2031
+ */
2032
+//#define SAFE_BED_LEVELING_START_X 0.0
2033
+//#define SAFE_BED_LEVELING_START_Y 0.0
2034
+//#define SAFE_BED_LEVELING_START_Z 0.0
2035
+//#define SAFE_BED_LEVELING_START_I 0.0
2036
+//#define SAFE_BED_LEVELING_START_J 0.0
2037
+//#define SAFE_BED_LEVELING_START_K 0.0
2038
+//#define SAFE_BED_LEVELING_START_U 0.0
2039
+//#define SAFE_BED_LEVELING_START_V 0.0
2040
+//#define SAFE_BED_LEVELING_START_W 0.0
2041
+
2042
+/**
2016 2043
  * Points to probe for all 3-point Leveling procedures.
2017 2044
  * Override if the automatically selected points are inadequate.
2018 2045
  */
@@ -2423,7 +2450,7 @@
2423 2450
 
2424 2451
   /**
2425 2452
    * Extra G-code to run while executing tool-change commands. Can be used to use an additional
2426
-   * stepper motor (I axis, see option LINEAR_AXES in Configuration.h) to drive the tool-changer.
2453
+   * stepper motor (I axis, see option NUM_AXES in Configuration.h) to drive the tool-changer.
2427 2454
    */
2428 2455
   //#define EVENT_GCODE_TOOLCHANGE_T0 "G28 A\nG1 A0" // Extra G-code to run while executing tool-change command T0
2429 2456
   //#define EVENT_GCODE_TOOLCHANGE_T1 "G1 A10"       // Extra G-code to run while executing tool-change command T1
@@ -2626,6 +2653,24 @@
2626 2653
     #define K_MICROSTEPS       16
2627 2654
   #endif
2628 2655
 
2656
+  #if AXIS_DRIVER_TYPE_U(TMC26X)
2657
+    #define U_MAX_CURRENT    1000
2658
+    #define U_SENSE_RESISTOR   91
2659
+    #define U_MICROSTEPS       16
2660
+  #endif
2661
+
2662
+  #if AXIS_DRIVER_TYPE_V(TMC26X)
2663
+    #define V_MAX_CURRENT    1000
2664
+    #define V_SENSE_RESISTOR   91
2665
+    #define V_MICROSTEPS       16
2666
+  #endif
2667
+
2668
+  #if AXIS_DRIVER_TYPE_W(TMC26X)
2669
+    #define W_MAX_CURRENT    1000
2670
+    #define W_SENSE_RESISTOR   91
2671
+    #define W_MICROSTEPS       16
2672
+  #endif
2673
+
2629 2674
   #if AXIS_DRIVER_TYPE_E0(TMC26X)
2630 2675
     #define E0_MAX_CURRENT    1000
2631 2676
     #define E0_SENSE_RESISTOR   91
@@ -2814,6 +2859,33 @@
2814 2859
     //#define K_HOLD_MULTIPLIER 0.5
2815 2860
   #endif
2816 2861
 
2862
+  #if AXIS_IS_TMC(U)
2863
+    #define U_CURRENT      800
2864
+    #define U_CURRENT_HOME U_CURRENT
2865
+    #define U_MICROSTEPS     8
2866
+    #define U_RSENSE         0.11
2867
+    #define U_CHAIN_POS     -1
2868
+    //#define U_INTERPOLATE  true
2869
+  #endif
2870
+
2871
+  #if AXIS_IS_TMC(V)
2872
+    #define V_CURRENT      800
2873
+    #define V_CURRENT_HOME V_CURRENT
2874
+    #define V_MICROSTEPS     8
2875
+    #define V_RSENSE         0.11
2876
+    #define V_CHAIN_POS     -1
2877
+    //#define V_INTERPOLATE  true
2878
+  #endif
2879
+
2880
+  #if AXIS_IS_TMC(W)
2881
+    #define W_CURRENT      800
2882
+    #define W_CURRENT_HOME W_CURRENT
2883
+    #define W_MICROSTEPS     8
2884
+    #define W_RSENSE         0.11
2885
+    #define W_CHAIN_POS     -1
2886
+    //#define W_INTERPOLATE  true
2887
+  #endif
2888
+
2817 2889
   #if AXIS_IS_TMC(E0)
2818 2890
     #define E0_CURRENT      800
2819 2891
     #define E0_MICROSTEPS    16
@@ -2901,6 +2973,9 @@
2901 2973
   //#define I_CS_PIN          -1
2902 2974
   //#define J_CS_PIN          -1
2903 2975
   //#define K_CS_PIN          -1
2976
+  //#define U_CS_PIN          -1
2977
+  //#define V_CS_PIN          -1
2978
+  //#define W_CS_PIN          -1
2904 2979
   //#define E0_CS_PIN         -1
2905 2980
   //#define E1_CS_PIN         -1
2906 2981
   //#define E2_CS_PIN         -1
@@ -2943,6 +3018,9 @@
2943 3018
   //#define  I_SLAVE_ADDRESS 0
2944 3019
   //#define  J_SLAVE_ADDRESS 0
2945 3020
   //#define  K_SLAVE_ADDRESS 0
3021
+  //#define  U_SLAVE_ADDRESS 0
3022
+  //#define  V_SLAVE_ADDRESS 0
3023
+  //#define  W_SLAVE_ADDRESS 0
2946 3024
   //#define E0_SLAVE_ADDRESS 0
2947 3025
   //#define E1_SLAVE_ADDRESS 0
2948 3026
   //#define E2_SLAVE_ADDRESS 0
@@ -2970,6 +3048,9 @@
2970 3048
   #define STEALTHCHOP_I
2971 3049
   #define STEALTHCHOP_J
2972 3050
   #define STEALTHCHOP_K
3051
+  #define STEALTHCHOP_U
3052
+  #define STEALTHCHOP_V
3053
+  #define STEALTHCHOP_W
2973 3054
   #define STEALTHCHOP_E
2974 3055
 
2975 3056
   /**
@@ -2996,9 +3077,12 @@
2996 3077
   //#define CHOPPER_TIMING_Z2 CHOPPER_TIMING_Z
2997 3078
   //#define CHOPPER_TIMING_Z3 CHOPPER_TIMING_Z
2998 3079
   //#define CHOPPER_TIMING_Z4 CHOPPER_TIMING_Z
2999
-  //#define CHOPPER_TIMING_I  CHOPPER_TIMING
3000
-  //#define CHOPPER_TIMING_J  CHOPPER_TIMING
3001
-  //#define CHOPPER_TIMING_K  CHOPPER_TIMING
3080
+  //#define CHOPPER_TIMING_I  CHOPPER_TIMING        // For I Axis
3081
+  //#define CHOPPER_TIMING_J  CHOPPER_TIMING        // For J Axis
3082
+  //#define CHOPPER_TIMING_K  CHOPPER_TIMING        // For K Axis
3083
+  //#define CHOPPER_TIMING_U  CHOPPER_TIMING        // For U Axis
3084
+  //#define CHOPPER_TIMING_V  CHOPPER_TIMING        // For V Axis
3085
+  //#define CHOPPER_TIMING_W  CHOPPER_TIMING        // For W Axis
3002 3086
   //#define CHOPPER_TIMING_E  CHOPPER_TIMING        // For Extruders (override below)
3003 3087
   //#define CHOPPER_TIMING_E1 CHOPPER_TIMING_E
3004 3088
   //#define CHOPPER_TIMING_E2 CHOPPER_TIMING_E
@@ -3044,9 +3128,12 @@
3044 3128
   #define Z2_HYBRID_THRESHOLD      3
3045 3129
   #define Z3_HYBRID_THRESHOLD      3
3046 3130
   #define Z4_HYBRID_THRESHOLD      3
3047
-  #define I_HYBRID_THRESHOLD       3
3048
-  #define J_HYBRID_THRESHOLD       3
3049
-  #define K_HYBRID_THRESHOLD       3
3131
+  #define I_HYBRID_THRESHOLD       3  // [linear=mm/s, rotational=°/s]
3132
+  #define J_HYBRID_THRESHOLD       3  // [linear=mm/s, rotational=°/s]
3133
+  #define K_HYBRID_THRESHOLD       3  // [linear=mm/s, rotational=°/s]
3134
+  #define U_HYBRID_THRESHOLD       3  // [mm/s]
3135
+  #define V_HYBRID_THRESHOLD       3
3136
+  #define W_HYBRID_THRESHOLD       3
3050 3137
   #define E0_HYBRID_THRESHOLD     30
3051 3138
   #define E1_HYBRID_THRESHOLD     30
3052 3139
   #define E2_HYBRID_THRESHOLD     30
@@ -3096,6 +3183,9 @@
3096 3183
     //#define I_STALL_SENSITIVITY  8
3097 3184
     //#define J_STALL_SENSITIVITY  8
3098 3185
     //#define K_STALL_SENSITIVITY  8
3186
+    //#define U_STALL_SENSITIVITY  8
3187
+    //#define V_STALL_SENSITIVITY  8
3188
+    //#define W_STALL_SENSITIVITY  8
3099 3189
     //#define SPI_ENDSTOPS              // TMC2130 only
3100 3190
     //#define IMPROVE_HOMING_RELIABILITY
3101 3191
   #endif
@@ -3263,6 +3353,33 @@
3263 3353
     #define K_SLEW_RATE         1
3264 3354
   #endif
3265 3355
 
3356
+  #if AXIS_IS_L64XX(U)
3357
+    #define U_MICROSTEPS      128
3358
+    #define U_OVERCURRENT    2000
3359
+    #define U_STALLCURRENT   1500
3360
+    #define U_MAX_VOLTAGE     127
3361
+    #define U_CHAIN_POS        -1
3362
+    #define U_SLEW_RATE         1
3363
+  #endif
3364
+
3365
+  #if AXIS_IS_L64XX(V)
3366
+    #define V_MICROSTEPS      128
3367
+    #define V_OVERCURRENT    2000
3368
+    #define V_STALLCURRENT   1500
3369
+    #define V_MAX_VOLTAGE     127
3370
+    #define V_CHAIN_POS        -1
3371
+    #define V_SLEW_RATE         1
3372
+  #endif
3373
+
3374
+  #if AXIS_IS_L64XX(W)
3375
+    #define W_MICROSTEPS      128
3376
+    #define W_OVERCURRENT    2000
3377
+    #define W_STALLCURRENT   1500
3378
+    #define W_MAX_VOLTAGE     127
3379
+    #define W_CHAIN_POS        -1
3380
+    #define W_SLEW_RATE         1
3381
+  #endif
3382
+
3266 3383
   #if AXIS_IS_L64XX(E0)
3267 3384
     #define E0_MICROSTEPS              128
3268 3385
     #define E0_OVERCURRENT            2000

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

@@ -213,6 +213,51 @@ void setup_endstop_interrupts() {
213 213
       pciSetup(K_MIN_PIN);
214 214
     #endif
215 215
   #endif
216
+  #if HAS_U_MAX
217
+    #if (digitalPinToInterrupt(U_MAX_PIN) != NOT_AN_INTERRUPT)
218
+      _ATTACH(U_MAX_PIN);
219
+    #else
220
+      static_assert(digitalPinHasPCICR(U_MAX_PIN), "U_MAX_PIN is not interrupt-capable");
221
+      pciSetup(U_MAX_PIN);
222
+    #endif
223
+  #elif HAS_U_MIN
224
+    #if (digitalPinToInterrupt(U_MIN_PIN) != NOT_AN_INTERRUPT)
225
+      _ATTACH(U_MIN_PIN);
226
+    #else
227
+      static_assert(digitalPinHasPCICR(U_MIN_PIN), "U_MIN_PIN is not interrupt-capable");
228
+      pciSetup(U_MIN_PIN);
229
+    #endif
230
+  #endif
231
+  #if HAS_V_MAX
232
+    #if (digitalPinToInterrupt(V_MAX_PIN) != NOT_AN_INTERRUPT)
233
+      _ATTACH(V_MAX_PIN);
234
+    #else
235
+      static_assert(digitalPinHasPCICR(V_MAX_PIN), "V_MAX_PIN is not interrupt-capable");
236
+      pciSetup(V_MAX_PIN);
237
+    #endif
238
+  #elif HAS_V_MIN
239
+    #if (digitalPinToInterrupt(V_MIN_PIN) != NOT_AN_INTERRUPT)
240
+      _ATTACH(V_MIN_PIN);
241
+    #else
242
+      static_assert(digitalPinHasPCICR(V_MIN_PIN), "V_MIN_PIN is not interrupt-capable");
243
+      pciSetup(V_MIN_PIN);
244
+    #endif
245
+  #endif
246
+  #if HAS_W_MAX
247
+    #if (digitalPinToInterrupt(W_MAX_PIN) != NOT_AN_INTERRUPT)
248
+      _ATTACH(W_MAX_PIN);
249
+    #else
250
+      static_assert(digitalPinHasPCICR(W_MAX_PIN), "W_MAX_PIN is not interrupt-capable");
251
+      pciSetup(W_MAX_PIN);
252
+    #endif
253
+  #elif HAS_W_MIN
254
+    #if (digitalPinToInterrupt(W_MIN_PIN) != NOT_AN_INTERRUPT)
255
+      _ATTACH(W_MIN_PIN);
256
+    #else
257
+      static_assert(digitalPinHasPCICR(W_MIN_PIN), "W_MIN_PIN is not interrupt-capable");
258
+      pciSetup(W_MIN_PIN);
259
+    #endif
260
+  #endif
216 261
   #if HAS_X2_MAX
217 262
     #if (digitalPinToInterrupt(X2_MAX_PIN) != NOT_AN_INTERRUPT)
218 263
       _ATTACH(X2_MAX_PIN);

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

@@ -70,4 +70,10 @@ void setup_endstop_interrupts() {
70 70
   TERN_(HAS_J_MIN, _ATTACH(J_MIN_PIN));
71 71
   TERN_(HAS_K_MAX, _ATTACH(K_MAX_PIN));
72 72
   TERN_(HAS_K_MIN, _ATTACH(K_MIN_PIN));
73
+  TERN_(HAS_U_MAX, _ATTACH(U_MAX_PIN));
74
+  TERN_(HAS_U_MIN, _ATTACH(U_MIN_PIN));
75
+  TERN_(HAS_V_MAX, _ATTACH(V_MAX_PIN));
76
+  TERN_(HAS_V_MIN, _ATTACH(V_MIN_PIN));
77
+  TERN_(HAS_W_MAX, _ATTACH(W_MAX_PIN));
78
+  TERN_(HAS_W_MIN, _ATTACH(W_MIN_PIN));
73 79
 }

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

@@ -65,4 +65,10 @@ void setup_endstop_interrupts() {
65 65
   TERN_(HAS_J_MIN, _ATTACH(J_MIN_PIN));
66 66
   TERN_(HAS_K_MAX, _ATTACH(K_MAX_PIN));
67 67
   TERN_(HAS_K_MIN, _ATTACH(K_MIN_PIN));
68
+  TERN_(HAS_U_MAX, _ATTACH(U_MAX_PIN));
69
+  TERN_(HAS_U_MIN, _ATTACH(U_MIN_PIN));
70
+  TERN_(HAS_V_MAX, _ATTACH(V_MAX_PIN));
71
+  TERN_(HAS_V_MIN, _ATTACH(V_MIN_PIN));
72
+  TERN_(HAS_W_MAX, _ATTACH(W_MAX_PIN));
73
+  TERN_(HAS_W_MIN, _ATTACH(W_MIN_PIN));
68 74
 }

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

@@ -155,4 +155,37 @@ void setup_endstop_interrupts() {
155 155
     #endif
156 156
     _ATTACH(K_MIN_PIN);
157 157
   #endif
158
+  #if HAS_U_MAX
159
+    #if !LPC1768_PIN_INTERRUPT_M(U_MAX_PIN)
160
+      #error "U_MAX_PIN is not INTERRUPT-capable."
161
+    #endif
162
+    _ATTACH(U_MAX_PIN);
163
+  #elif HAS_U_MIN
164
+    #if !LPC1768_PIN_INTERRUPT_M(U_MIN_PIN)
165
+      #error "U_MIN_PIN is not INTERRUPT-capable."
166
+    #endif
167
+    _ATTACH(U_MIN_PIN);
168
+  #endif
169
+  #if HAS_V_MAX
170
+    #if !LPC1768_PIN_INTERRUPT_M(V_MAX_PIN)
171
+      #error "V_MAX_PIN is not INTERRUPT-capable."
172
+    #endif
173
+    _ATTACH(V_MAX_PIN);
174
+  #elif HAS_V_MIN
175
+    #if !LPC1768_PIN_INTERRUPT_M(V_MIN_PIN)
176
+      #error "V_MIN_PIN is not INTERRUPT-capable."
177
+    #endif
178
+    _ATTACH(V_MIN_PIN);
179
+  #endif
180
+  #if HAS_W_MAX
181
+    #if !LPC1768_PIN_INTERRUPT_M(W_MAX_PIN)
182
+      #error "W_MAX_PIN is not INTERRUPT-capable."
183
+    #endif
184
+    _ATTACH(W_MAX_PIN);
185
+  #elif HAS_W_MIN
186
+    #if !LPC1768_PIN_INTERRUPT_M(W_MIN_PIN)
187
+      #error "W_MIN_PIN is not INTERRUPT-capable."
188
+    #endif
189
+    _ATTACH(W_MIN_PIN);
190
+  #endif
158 191
 }

+ 45
- 0
Marlin/src/HAL/SAMD51/endstop_interrupts.h View File

@@ -60,6 +60,12 @@
60 60
 #define MATCH_J_MIN_EILINE(P)   TERN0(HAS_J_MIN,  DEFER4(MATCH_EILINE)(P, J_MIN_PIN))
61 61
 #define MATCH_K_MAX_EILINE(P)   TERN0(HAS_K_MAX,  DEFER4(MATCH_EILINE)(P, K_MAX_PIN))
62 62
 #define MATCH_K_MIN_EILINE(P)   TERN0(HAS_K_MIN,  DEFER4(MATCH_EILINE)(P, K_MIN_PIN))
63
+#define MATCH_U_MAX_EILINE(P)   TERN0(HAS_U_MAX,  DEFER4(MATCH_EILINE)(P, U_MAX_PIN))
64
+#define MATCH_U_MIN_EILINE(P)   TERN0(HAS_U_MIN,  DEFER4(MATCH_EILINE)(P, U_MIN_PIN))
65
+#define MATCH_V_MAX_EILINE(P)   TERN0(HAS_V_MAX,  DEFER4(MATCH_EILINE)(P, V_MAX_PIN))
66
+#define MATCH_V_MIN_EILINE(P)   TERN0(HAS_V_MIN,  DEFER4(MATCH_EILINE)(P, V_MIN_PIN))
67
+#define MATCH_W_MAX_EILINE(P)   TERN0(HAS_W_MAX,  DEFER4(MATCH_EILINE)(P, W_MAX_PIN))
68
+#define MATCH_W_MIN_EILINE(P)   TERN0(HAS_W_MIN,  DEFER4(MATCH_EILINE)(P, W_MIN_PIN))
63 69
 #define MATCH_Z2_MAX_EILINE(P)  TERN0(HAS_Z2_MAX, DEFER4(MATCH_EILINE)(P, Z2_MAX_PIN))
64 70
 #define MATCH_Z2_MIN_EILINE(P)  TERN0(HAS_Z2_MIN, DEFER4(MATCH_EILINE)(P, Z2_MIN_PIN))
65 71
 #define MATCH_Z3_MAX_EILINE(P)  TERN0(HAS_Z3_MAX, DEFER4(MATCH_EILINE)(P, Z3_MAX_PIN))
@@ -75,6 +81,9 @@
75 81
   && !MATCH_I_MAX_EILINE(P) && !MATCH_I_MIN_EILINE(P)   \
76 82
   && !MATCH_J_MAX_EILINE(P) && !MATCH_J_MIN_EILINE(P)   \
77 83
   && !MATCH_K_MAX_EILINE(P) && !MATCH_K_MIN_EILINE(P)   \
84
+  && !MATCH_U_MAX_EILINE(P) && !MATCH_U_MIN_EILINE(P)   \
85
+  && !MATCH_V_MAX_EILINE(P) && !MATCH_V_MIN_EILINE(P)   \
86
+  && !MATCH_W_MAX_EILINE(P) && !MATCH_W_MIN_EILINE(P)   \
78 87
   && !MATCH_Z2_MAX_EILINE(P) && !MATCH_Z2_MIN_EILINE(P) \
79 88
   && !MATCH_Z3_MAX_EILINE(P) && !MATCH_Z3_MIN_EILINE(P) \
80 89
   && !MATCH_Z4_MAX_EILINE(P) && !MATCH_Z4_MIN_EILINE(P) \
@@ -199,4 +208,40 @@ void setup_endstop_interrupts() {
199 208
     #endif
200 209
     attachInterrupt(K_MIN_PIN, endstop_ISR, CHANGE);
201 210
   #endif
211
+  #if HAS_U_MAX
212
+    #if !AVAILABLE_EILINE(U_MAX_PIN)
213
+      #error "U_MAX_PIN has no EXTINT line available."
214
+    #endif
215
+    attachInterrupt(U_MAX_PIN, endstop_ISR, CHANGE);
216
+  #endif
217
+  #if HAS_U_MIN
218
+    #if !AVAILABLE_EILINE(U_MIN_PIN)
219
+      #error "U_MIN_PIN has no EXTINT line available."
220
+    #endif
221
+    attachInterrupt(U_MIN_PIN, endstop_ISR, CHANGE);
222
+  #endif
223
+  #if HAS_V_MAX
224
+    #if !AVAILABLE_EILINE(V_MAX_PIN)
225
+      #error "V_MAX_PIN has no EXTINT line available."
226
+    #endif
227
+    attachInterrupt(V_MAX_PIN, endstop_ISR, CHANGE);
228
+  #endif
229
+  #if HAS_V_MIN
230
+    #if !AVAILABLE_EILINE(V_MIN_PIN)
231
+      #error "V_MIN_PIN has no EXTINT line available."
232
+    #endif
233
+    attachInterrupt(V_MIN_PIN, endstop_ISR, CHANGE);
234
+  #endif
235
+  #if HAS_W_MAX
236
+    #if !AVAILABLE_EILINE(W_MAX_PIN)
237
+      #error "W_MAX_PIN has no EXTINT line available."
238
+    #endif
239
+    attachInterrupt(W_MAX_PIN, endstop_ISR, CHANGE);
240
+  #endif
241
+  #if HAS_W_MIN
242
+    #if !AVAILABLE_EILINE(W_MIN_PIN)
243
+      #error "W_MIN_PIN has no EXTINT line available."
244
+    #endif
245
+    attachInterrupt(W_MIN_PIN, endstop_ISR, CHANGE);
246
+  #endif
202 247
 }

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

@@ -52,4 +52,10 @@ void setup_endstop_interrupts() {
52 52
   TERN_(HAS_J_MIN, _ATTACH(J_MIN_PIN));
53 53
   TERN_(HAS_K_MAX, _ATTACH(K_MAX_PIN));
54 54
   TERN_(HAS_K_MIN, _ATTACH(K_MIN_PIN));
55
+  TERN_(HAS_U_MAX, _ATTACH(U_MAX_PIN));
56
+  TERN_(HAS_U_MIN, _ATTACH(U_MIN_PIN));
57
+  TERN_(HAS_V_MAX, _ATTACH(V_MAX_PIN));
58
+  TERN_(HAS_V_MIN, _ATTACH(V_MIN_PIN));
59
+  TERN_(HAS_W_MAX, _ATTACH(W_MAX_PIN));
60
+  TERN_(HAS_W_MIN, _ATTACH(W_MIN_PIN));
55 61
 }

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

@@ -77,4 +77,10 @@ void setup_endstop_interrupts() {
77 77
   TERN_(HAS_J_MIN, _ATTACH(J_MIN_PIN));
78 78
   TERN_(HAS_K_MAX, _ATTACH(K_MAX_PIN));
79 79
   TERN_(HAS_K_MIN, _ATTACH(K_MIN_PIN));
80
+  TERN_(HAS_U_MAX, _ATTACH(U_MAX_PIN));
81
+  TERN_(HAS_U_MIN, _ATTACH(U_MIN_PIN));
82
+  TERN_(HAS_V_MAX, _ATTACH(V_MAX_PIN));
83
+  TERN_(HAS_V_MIN, _ATTACH(V_MIN_PIN));
84
+  TERN_(HAS_W_MAX, _ATTACH(W_MAX_PIN));
85
+  TERN_(HAS_W_MIN, _ATTACH(W_MIN_PIN));
80 86
 }

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

@@ -70,4 +70,10 @@ void setup_endstop_interrupts() {
70 70
   TERN_(HAS_J_MIN, _ATTACH(J_MIN_PIN));
71 71
   TERN_(HAS_K_MAX, _ATTACH(K_MAX_PIN));
72 72
   TERN_(HAS_K_MIN, _ATTACH(K_MIN_PIN));
73
+  TERN_(HAS_U_MAX, _ATTACH(U_MAX_PIN));
74
+  TERN_(HAS_U_MIN, _ATTACH(U_MIN_PIN));
75
+  TERN_(HAS_V_MAX, _ATTACH(V_MAX_PIN));
76
+  TERN_(HAS_V_MIN, _ATTACH(V_MIN_PIN));
77
+  TERN_(HAS_W_MAX, _ATTACH(W_MAX_PIN));
78
+  TERN_(HAS_W_MIN, _ATTACH(W_MIN_PIN));
73 79
 }

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

@@ -69,4 +69,10 @@ void setup_endstop_interrupts() {
69 69
   TERN_(HAS_J_MIN, _ATTACH(J_MIN_PIN));
70 70
   TERN_(HAS_K_MAX, _ATTACH(K_MAX_PIN));
71 71
   TERN_(HAS_K_MIN, _ATTACH(K_MIN_PIN));
72
+  TERN_(HAS_U_MAX, _ATTACH(U_MAX_PIN));
73
+  TERN_(HAS_U_MIN, _ATTACH(U_MIN_PIN));
74
+  TERN_(HAS_V_MAX, _ATTACH(V_MAX_PIN));
75
+  TERN_(HAS_V_MIN, _ATTACH(V_MIN_PIN));
76
+  TERN_(HAS_W_MAX, _ATTACH(W_MAX_PIN));
77
+  TERN_(HAS_W_MIN, _ATTACH(W_MIN_PIN));
72 78
 }

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

@@ -436,6 +436,9 @@ inline void manage_inactivity(const bool no_stepper_sleep=false) {
436 436
         TERN_(DISABLE_INACTIVE_I, stepper.disable_axis(I_AXIS));
437 437
         TERN_(DISABLE_INACTIVE_J, stepper.disable_axis(J_AXIS));
438 438
         TERN_(DISABLE_INACTIVE_K, stepper.disable_axis(K_AXIS));
439
+        TERN_(DISABLE_INACTIVE_U, stepper.disable_axis(U_AXIS));
440
+        TERN_(DISABLE_INACTIVE_V, stepper.disable_axis(V_AXIS));
441
+        TERN_(DISABLE_INACTIVE_W, stepper.disable_axis(W_AXIS));
439 442
         TERN_(DISABLE_INACTIVE_E, stepper.disable_e_steppers());
440 443
 
441 444
         TERN_(AUTO_BED_LEVELING_UBL, ubl.steppers_were_disabled());
@@ -993,6 +996,15 @@ inline void tmc_standby_setup() {
993 996
   #if PIN_EXISTS(K_STDBY)
994 997
     SET_INPUT_PULLDOWN(K_STDBY_PIN);
995 998
   #endif
999
+  #if PIN_EXISTS(U_STDBY)
1000
+    SET_INPUT_PULLDOWN(U_STDBY_PIN);
1001
+  #endif
1002
+  #if PIN_EXISTS(V_STDBY)
1003
+    SET_INPUT_PULLDOWN(V_STDBY_PIN);
1004
+  #endif
1005
+  #if PIN_EXISTS(W_STDBY)
1006
+    SET_INPUT_PULLDOWN(W_STDBY_PIN);
1007
+  #endif
996 1008
   #if PIN_EXISTS(E0_STDBY)
997 1009
     SET_INPUT_PULLDOWN(E0_STDBY_PIN);
998 1010
   #endif

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

@@ -63,6 +63,9 @@
63 63
 #define AXIS_DRIVER_TYPE_I(T) _AXIS_DRIVER_TYPE(I,T)
64 64
 #define AXIS_DRIVER_TYPE_J(T) _AXIS_DRIVER_TYPE(J,T)
65 65
 #define AXIS_DRIVER_TYPE_K(T) _AXIS_DRIVER_TYPE(K,T)
66
+#define AXIS_DRIVER_TYPE_U(T) _AXIS_DRIVER_TYPE(U,T)
67
+#define AXIS_DRIVER_TYPE_V(T) _AXIS_DRIVER_TYPE(V,T)
68
+#define AXIS_DRIVER_TYPE_W(T) _AXIS_DRIVER_TYPE(W,T)
66 69
 
67 70
 #define AXIS_DRIVER_TYPE_X2(T) (EITHER(X_DUAL_STEPPER_DRIVERS, DUAL_X_CARRIAGE) && _AXIS_DRIVER_TYPE(X2,T))
68 71
 #define AXIS_DRIVER_TYPE_Y2(T) (ENABLED(Y_DUAL_STEPPER_DRIVERS) && _AXIS_DRIVER_TYPE(Y2,T))
@@ -87,6 +90,7 @@
87 90
 
88 91
 #define HAS_DRIVER(T) (  AXIS_DRIVER_TYPE_X(T)  || AXIS_DRIVER_TYPE_Y(T)  || AXIS_DRIVER_TYPE_Z(T)  \
89 92
                       || AXIS_DRIVER_TYPE_I(T)  || AXIS_DRIVER_TYPE_J(T)  || AXIS_DRIVER_TYPE_K(T)  \
93
+                      || AXIS_DRIVER_TYPE_U(T)  || AXIS_DRIVER_TYPE_V(T)  || AXIS_DRIVER_TYPE_W(T)  \
90 94
                       || AXIS_DRIVER_TYPE_X2(T) || AXIS_DRIVER_TYPE_Y2(T) || AXIS_DRIVER_TYPE_Z2(T) \
91 95
                       || AXIS_DRIVER_TYPE_Z3(T) || AXIS_DRIVER_TYPE_Z4(T) || HAS_E_DRIVER(T) )
92 96
 
@@ -161,6 +165,7 @@
161 165
                           || AXIS_HAS_##T(Y) || AXIS_HAS_##T(Y2) \
162 166
                           || AXIS_HAS_##T(Z) || AXIS_HAS_##T(Z2) || AXIS_HAS_##T(Z3) || AXIS_HAS_##T(Z4) \
163 167
                           || AXIS_HAS_##T(I) || AXIS_HAS_##T(J)  || AXIS_HAS_##T(K) \
168
+                          || AXIS_HAS_##T(U) || AXIS_HAS_##T(V)  || AXIS_HAS_##T(W) \
164 169
                           || E_AXIS_HAS(T) )
165 170
 
166 171
 #if ANY_AXIS_HAS(STEALTHCHOP)

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

@@ -444,6 +444,54 @@
444 444
   #define STR_K   ""
445 445
 #endif
446 446
 
447
+#if HAS_U_AXIS
448
+  #if AXIS7_NAME == 'U'
449
+    #define STR_U "U"
450
+    #define STR_U_MIN "u_min"
451
+    #define STR_U_MAX "u_max"
452
+  #elif AXIS7_NAME == 'V'
453
+    #define STR_U "V"
454
+    #define STR_U_MIN "v_min"
455
+    #define STR_U_MAX "v_max"
456
+  #elif AXIS7_NAME == 'W'
457
+    #define STR_U "W"
458
+    #define STR_U_MIN "w_min"
459
+    #define STR_U_MAX "w_max"
460
+  #else
461
+    #error "AXIS7_NAME can only be one of 'U', 'V', or 'W'."
462
+  #endif
463
+#else
464
+  #define STR_U   ""
465
+#endif
466
+
467
+#if HAS_V_AXIS
468
+  #if AXIS8_NAME == 'V'
469
+    #define STR_V "V"
470
+    #define STR_V_MIN "v_min"
471
+    #define STR_V_MAX "v_max"
472
+  #elif AXIS8_NAME == 'W'
473
+    #define STR_V "W"
474
+    #define STR_V_MIN "w_min"
475
+    #define STR_V_MAX "w_max"
476
+  #else
477
+    #error "AXIS8_NAME can only be one of 'V', or 'W'."
478
+  #endif
479
+#else
480
+  #define STR_V   ""
481
+#endif
482
+
483
+#if HAS_W_AXIS
484
+  #if AXIS9_NAME == 'W'
485
+    #define STR_W "W"
486
+    #define STR_W_MIN "w_min"
487
+    #define STR_W_MAX "w_max"
488
+  #else
489
+    #error "AXIS9_NAME can only be 'W'."
490
+  #endif
491
+#else
492
+  #define STR_W   ""
493
+#endif
494
+
447 495
 #if EITHER(HAS_MARLINUI_HD44780, IS_TFTGLCD_PANEL)
448 496
 
449 497
   // Custom characters defined in the first 8 characters of the LCD

+ 13
- 1
Marlin/src/core/macros.h View File

@@ -39,24 +39,36 @@
39 39
 #define _ISTOP_  0x04
40 40
 #define _JSTOP_  0x05
41 41
 #define _KSTOP_  0x06
42
+#define _USTOP_  0x07
43
+#define _VSTOP_  0x08
44
+#define _WSTOP_  0x09
42 45
 #define _XMIN_   0x11
43 46
 #define _YMIN_   0x12
44 47
 #define _ZMIN_   0x13
45 48
 #define _IMIN_   0x14
46 49
 #define _JMIN_   0x15
47 50
 #define _KMIN_   0x16
51
+#define _UMIN_   0x17
52
+#define _VMIN_   0x18
53
+#define _WMIN_   0x19
48 54
 #define _XMAX_   0x21
49 55
 #define _YMAX_   0x22
50 56
 #define _ZMAX_   0x23
51 57
 #define _IMAX_   0x24
52 58
 #define _JMAX_   0x25
53 59
 #define _KMAX_   0x26
60
+#define _UMAX_   0x27
61
+#define _VMAX_   0x28
62
+#define _WMAX_   0x29
54 63
 #define _XDIAG_  0x31
55 64
 #define _YDIAG_  0x32
56 65
 #define _ZDIAG_  0x33
57 66
 #define _IDIAG_  0x34
58 67
 #define _JDIAG_  0x35
59 68
 #define _KDIAG_  0x36
69
+#define _UDIAG_  0x37
70
+#define _VDIAG_  0x38
71
+#define _WDIAG_  0x39
60 72
 #define _E0DIAG_ 0xE0
61 73
 #define _E1DIAG_ 0xE1
62 74
 #define _E2DIAG_ 0xE2
@@ -350,7 +362,7 @@
350 362
 
351 363
 #define _LIST_N(N,V...) LIST_##N(V)
352 364
 #define LIST_N(N,V...) _LIST_N(N,V)
353
-#define LIST_N_1(N,K) _LIST_N(N,K,K,K,K,K,K,K,K,K,K,K,K,K,K,K,K)
365
+#define LIST_N_1(N,K) _LIST_N(N,K,K,K,K,K,K,K,K,K,K,K,K,K,K,K,K,K,K,K,K)
354 366
 #define ARRAY_N(N,V...) { _LIST_N(N,V) }
355 367
 #define ARRAY_N_1(N,K)  { LIST_N_1(N,K) }
356 368
 

+ 6
- 2
Marlin/src/core/serial.cpp View File

@@ -32,14 +32,18 @@ uint8_t marlin_debug_flags = MARLIN_DEBUG_NONE;
32 32
 // Commonly-used strings in serial output
33 33
 PGMSTR(NUL_STR,   "");   PGMSTR(SP_P_STR, " P");  PGMSTR(SP_T_STR, " T");
34 34
 PGMSTR(X_STR,     "X");  PGMSTR(Y_STR,     "Y");  PGMSTR(Z_STR,     "Z");  PGMSTR(E_STR,     "E");
35
+PGMSTR(U_STR, STR_U); PGMSTR(V_STR, STR_V); PGMSTR(W_STR, STR_W);
35 36
 PGMSTR(X_LBL,     "X:"); PGMSTR(Y_LBL,     "Y:"); PGMSTR(Z_LBL,     "Z:"); PGMSTR(E_LBL,     "E:");
37
+PGMSTR(U_LBL, STR_U ":"); PGMSTR(V_LBL, STR_V ":"); PGMSTR(W_LBL, STR_W ":");
36 38
 PGMSTR(SP_A_STR, " A");  PGMSTR(SP_B_STR, " B");  PGMSTR(SP_C_STR, " C");
37 39
 PGMSTR(SP_X_STR, " X");  PGMSTR(SP_Y_STR, " Y");  PGMSTR(SP_Z_STR, " Z");  PGMSTR(SP_E_STR, " E");
38 40
 PGMSTR(SP_X_LBL, " X:"); PGMSTR(SP_Y_LBL, " Y:"); PGMSTR(SP_Z_LBL, " Z:"); PGMSTR(SP_E_LBL, " E:");
39 41
 PGMSTR(I_STR, STR_I);     PGMSTR(J_STR, STR_J);     PGMSTR(K_STR, STR_K);
40 42
 PGMSTR(I_LBL, STR_I ":"); PGMSTR(J_LBL, STR_J ":"); PGMSTR(K_LBL, STR_K ":");
41 43
 PGMSTR(SP_I_STR, " " STR_I);     PGMSTR(SP_J_STR, " " STR_J);     PGMSTR(SP_K_STR, " " STR_K);
44
+PGMSTR(SP_U_STR, " " STR_U); PGMSTR(SP_V_STR, " " STR_V); PGMSTR(SP_W_STR, " " STR_W);
42 45
 PGMSTR(SP_I_LBL, " " STR_I ":"); PGMSTR(SP_J_LBL, " " STR_J ":"); PGMSTR(SP_K_LBL, " " STR_K ":");
46
+PGMSTR(SP_U_LBL, " " STR_U ":"); PGMSTR(SP_V_LBL, " " STR_V ":"); PGMSTR(SP_W_LBL, " " STR_W ":");
43 47
 
44 48
 // Hook Meatpack if it's enabled on the first leaf
45 49
 #if ENABLED(MEATPACK_ON_SERIAL_PORT_1)
@@ -102,10 +106,10 @@ void print_bin(uint16_t val) {
102 106
   }
103 107
 }
104 108
 
105
-void print_pos(LINEAR_AXIS_ARGS(const_float_t), FSTR_P const prefix/*=nullptr*/, FSTR_P const suffix/*=nullptr*/) {
109
+void print_pos(NUM_AXIS_ARGS(const_float_t), FSTR_P const prefix/*=nullptr*/, FSTR_P const suffix/*=nullptr*/) {
106 110
   if (prefix) serial_print(prefix);
107 111
   SERIAL_ECHOPGM_P(
108
-    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
+    LIST_N(DOUBLE(NUM_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, SP_U_STR, u, SP_V_STR, v, SP_W_STR, w)
109 113
   );
110 114
   if (suffix) serial_print(suffix); else SERIAL_EOL();
111 115
 }

+ 8
- 13
Marlin/src/core/serial.h View File

@@ -29,17 +29,12 @@
29 29
 #endif
30 30
 
31 31
 // Commonly-used strings in serial output
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[],
39
-                  X_STR[], Y_STR[], Z_STR[], E_STR[],
40
-                  I_STR[], J_STR[], K_STR[],
41
-                  X_LBL[], Y_LBL[], Z_LBL[], E_LBL[],
42
-                  I_LBL[], J_LBL[], K_LBL[];
32
+extern const char NUL_STR[], SP_P_STR[], SP_T_STR[],
33
+                  SP_A_STR[], SP_B_STR[], SP_C_STR[],
34
+                  SP_X_STR[], SP_Y_STR[], SP_Z_STR[], SP_I_STR[], SP_J_STR[], SP_K_STR[], SP_U_STR[], SP_V_STR[], SP_W_STR[], SP_E_STR[],
35
+                  SP_X_LBL[], SP_Y_LBL[], SP_Z_LBL[], SP_I_LBL[], SP_J_LBL[], SP_K_LBL[], SP_U_LBL[], SP_V_LBL[], SP_W_LBL[], SP_E_LBL[],
36
+                  X_STR[], Y_STR[], Z_STR[], I_STR[], J_STR[], K_STR[], U_STR[], V_STR[], W_STR[], E_STR[],
37
+                  X_LBL[], Y_LBL[], Z_LBL[], I_LBL[], J_LBL[], K_LBL[], U_LBL[], V_LBL[], W_LBL[], E_LBL[];
43 38
 
44 39
 //
45 40
 // Debugging flags for use by M111
@@ -348,10 +343,10 @@ void serial_spaces(uint8_t count);
348 343
 void serial_offset(const_float_t v, const uint8_t sp=0); // For v==0 draw space (sp==1) or plus (sp==2)
349 344
 
350 345
 void print_bin(const uint16_t val);
351
-void print_pos(LINEAR_AXIS_ARGS(const_float_t), FSTR_P const prefix=nullptr, FSTR_P const suffix=nullptr);
346
+void print_pos(NUM_AXIS_ARGS(const_float_t), FSTR_P const prefix=nullptr, FSTR_P const suffix=nullptr);
352 347
 
353 348
 inline void print_pos(const xyz_pos_t &xyz, FSTR_P const prefix=nullptr, FSTR_P const suffix=nullptr) {
354
-  print_pos(LINEAR_AXIS_ELEM(xyz), prefix, suffix);
349
+  print_pos(NUM_AXIS_ELEM(xyz), prefix, suffix);
355 350
 }
356 351
 
357 352
 #define SERIAL_POS(SUFFIX,VAR) do { print_pos(VAR, F("  " STRINGIFY(VAR) "="), F(" : " SUFFIX "\n")); }while(0)

+ 207
- 177
Marlin/src/core/types.h View File

@@ -36,23 +36,33 @@ struct IF { typedef R type; };
36 36
 template <class L, class R>
37 37
 struct IF<true, L, R> { typedef L type; };
38 38
 
39
-#define LINEAR_AXIS_GANG(V...) GANG_N(LINEAR_AXES, V)
40
-#define LINEAR_AXIS_CODE(V...) CODE_N(LINEAR_AXES, V)
41
-#define LINEAR_AXIS_LIST(V...) LIST_N(LINEAR_AXES, V)
42
-#define LINEAR_AXIS_ARRAY(V...) { LINEAR_AXIS_LIST(V) }
43
-#define LINEAR_AXIS_ARGS(T...) LINEAR_AXIS_LIST(T x, T y, T z, T i, T j, T k)
44
-#define LINEAR_AXIS_ELEM(O)    LINEAR_AXIS_LIST(O.x, O.y, O.z, O.i, O.j, O.k)
45
-#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
-
47
-#define LOGICAL_AXIS_GANG(E,V...) LINEAR_AXIS_GANG(V) GANG_ITEM_E(E)
48
-#define LOGICAL_AXIS_CODE(E,V...) LINEAR_AXIS_CODE(V) CODE_ITEM_E(E)
49
-#define LOGICAL_AXIS_LIST(E,V...) LINEAR_AXIS_LIST(V) LIST_ITEM_E(E)
39
+#define NUM_AXIS_GANG(V...) GANG_N(NUM_AXES, V)
40
+#define NUM_AXIS_CODE(V...) CODE_N(NUM_AXES, V)
41
+#define NUM_AXIS_LIST(V...) LIST_N(NUM_AXES, V)
42
+#define NUM_AXIS_ARRAY(V...) { NUM_AXIS_LIST(V) }
43
+#define NUM_AXIS_ARGS(T...) NUM_AXIS_LIST(T x, T y, T z, T i, T j, T k, T u, T v, T w)
44
+#define NUM_AXIS_ELEM(O)    NUM_AXIS_LIST(O.x, O.y, O.z, O.i, O.j, O.k, O.u, O.v, O.w)
45
+#define NUM_AXIS_DEFS(T,V)  NUM_AXIS_LIST(T x=V, T y=V, T z=V, T i=V, T j=V, T k=V, T u=V, T v=V, T w=V)
46
+
47
+#define LOGICAL_AXIS_GANG(E,V...) NUM_AXIS_GANG(V) GANG_ITEM_E(E)
48
+#define LOGICAL_AXIS_CODE(E,V...) NUM_AXIS_CODE(V) CODE_ITEM_E(E)
49
+#define LOGICAL_AXIS_LIST(E,V...) NUM_AXIS_LIST(V) LIST_ITEM_E(E)
50 50
 #define LOGICAL_AXIS_ARRAY(E,V...) { LOGICAL_AXIS_LIST(E,V) }
51
-#define LOGICAL_AXIS_ARGS(T...) LOGICAL_AXIS_LIST(T e, T x, T y, T z, T i, T j, T k)
52
-#define LOGICAL_AXIS_ELEM(O)    LOGICAL_AXIS_LIST(O.e, O.x, O.y, O.z, O.i, O.j, O.k)
53
-#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
+#define LOGICAL_AXIS_ARGS(T...) LOGICAL_AXIS_LIST(T e, T x, T y, T z, T i, T j, T k, T u, T v, T w)
52
+#define LOGICAL_AXIS_ELEM(O)    LOGICAL_AXIS_LIST(O.e, O.x, O.y, O.z, O.i, O.j, O.k, O.u, O.v, O.w)
53
+#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, T u=V, T v=V, T w=V)
54 54
 
55
-#define LOGICAL_AXES_STRING LOGICAL_AXIS_GANG("E", "X", "Y", "Z", STR_I, STR_J, STR_K)
55
+#define LOGICAL_AXES_STRING LOGICAL_AXIS_GANG("E", "X", "Y", "Z", STR_I, STR_J, STR_K, STR_U, STR_V, STR_W)
56
+
57
+#define XYZ_GANG(V...) GANG_N(PRIMARY_LINEAR_AXES, V)
58
+#define XYZ_CODE(V...) CODE_N(PRIMARY_LINEAR_AXES, V)
59
+
60
+#define SECONDARY_AXIS_GANG(V...) GANG_N(SECONDARY_AXES, V)
61
+#define SECONDARY_AXIS_CODE(V...) CODE_N(SECONDARY_AXES, V)
62
+
63
+#if HAS_ROTATIONAL_AXES
64
+  #define ROTATIONAL_AXIS_GANG(V...) GANG_N(ROTATIONAL_AXES, V)
65
+#endif
56 66
 
57 67
 #if HAS_EXTRUDERS
58 68
   #define LIST_ITEM_E(N) , N
@@ -64,7 +74,7 @@ struct IF<true, L, R> { typedef L type; };
64 74
   #define GANG_ITEM_E(N)
65 75
 #endif
66 76
 
67
-#define AXIS_COLLISION(L) (AXIS4_NAME == L || AXIS5_NAME == L || AXIS6_NAME == L)
77
+#define AXIS_COLLISION(L) (AXIS4_NAME == L || AXIS5_NAME == L || AXIS6_NAME == L || AXIS7_NAME == L || AXIS8_NAME == L || AXIS9_NAME == L)
68 78
 
69 79
 //
70 80
 // Enumerated axis indices
@@ -76,7 +86,7 @@ struct IF<true, L, R> { typedef L type; };
76 86
 enum AxisEnum : uint8_t {
77 87
 
78 88
   // Linear axes may be controlled directly or indirectly
79
-  LINEAR_AXIS_LIST(X_AXIS, Y_AXIS, Z_AXIS, I_AXIS, J_AXIS, K_AXIS)
89
+  NUM_AXIS_LIST(X_AXIS, Y_AXIS, Z_AXIS, I_AXIS, J_AXIS, K_AXIS, U_AXIS, V_AXIS, W_AXIS)
80 90
 
81 91
   // Extruder axes may be considered distinctly
82 92
   #define _EN_ITEM(N) , E##N##_AXIS
@@ -110,12 +120,13 @@ enum AxisEnum : uint8_t {
110 120
 };
111 121
 
112 122
 typedef IF<(NUM_AXIS_ENUMS > 8), uint16_t, uint8_t>::type axis_bits_t;
123
+typedef IF<(NUM_AXES > 8), uint16_t, uint8_t>::type linear_axis_bits_t;
113 124
 
114 125
 //
115 126
 // Loop over axes
116 127
 //
117 128
 #define LOOP_ABC(VAR) LOOP_S_LE_N(VAR, A_AXIS, C_AXIS)
118
-#define LOOP_LINEAR_AXES(VAR) LOOP_S_L_N(VAR, X_AXIS, LINEAR_AXES)
129
+#define LOOP_NUM_AXES(VAR) LOOP_S_L_N(VAR, X_AXIS, NUM_AXES)
119 130
 #define LOOP_LOGICAL_AXES(VAR) LOOP_S_L_N(VAR, X_AXIS, LOGICAL_AXES)
120 131
 #define LOOP_DISTINCT_AXES(VAR) LOOP_S_L_N(VAR, X_AXIS, DISTINCT_AXES)
121 132
 #define LOOP_DISTINCT_E(VAR) LOOP_L_N(VAR, DISTINCT_E)
@@ -260,10 +271,10 @@ struct XYval {
260 271
     FI void set(const T px, const T py)                 { x = px; y = py; }
261 272
     FI void set(const T (&arr)[XY])                     { x = arr[0]; y = arr[1]; }
262 273
   #endif
263
-  #if LINEAR_AXES > XY
264
-    FI void set(const T (&arr)[LINEAR_AXES])            { x = arr[0]; y = arr[1]; }
274
+  #if NUM_AXES > XY
275
+    FI void set(const T (&arr)[NUM_AXES])               { x = arr[0]; y = arr[1]; }
265 276
   #endif
266
-  #if LOGICAL_AXES > LINEAR_AXES
277
+  #if LOGICAL_AXES > NUM_AXES
267 278
     FI void set(const T (&arr)[LOGICAL_AXES])           { x = arr[0]; y = arr[1]; }
268 279
     #if DISTINCT_AXES > LOGICAL_AXES
269 280
       FI void set(const T (&arr)[DISTINCT_AXES])        { x = arr[0]; y = arr[1]; }
@@ -385,60 +396,69 @@ struct XYval {
385 396
 template<typename T>
386 397
 struct XYZval {
387 398
   union {
388
-    struct { T LINEAR_AXIS_ARGS(); };
389
-    struct { T LINEAR_AXIS_LIST(a, b, c, u, v, w); };
390
-    T pos[LINEAR_AXES];
399
+    struct { T NUM_AXIS_ARGS(); };
400
+    struct { T NUM_AXIS_LIST(a, b, c, _i, _j, _k, _u, _v, _w); };
401
+    T pos[NUM_AXES];
391 402
   };
392 403
 
393 404
   // Set all to 0
394
-  FI void reset()                                      { LINEAR_AXIS_GANG(x =, y =, z =, i =, j =, k =) 0; }
405
+  FI void reset()                                      { NUM_AXIS_GANG(x =, y =, z =, i =, j =, k =, u =, v =, w =) 0; }
395 406
 
396 407
   // Setters taking struct types and arrays
397 408
   FI void set(const T px)                              { x = px; }
398 409
   FI void set(const T px, const T py)                  { x = px; y = py; }
399 410
   FI void set(const XYval<T> pxy)                      { x = pxy.x; y = pxy.y; }
400
-  FI void set(const XYval<T> pxy, const T pz)          { LINEAR_AXIS_CODE(x = pxy.x, y = pxy.y, z = pz, NOOP, NOOP, NOOP); }
411
+  FI void set(const XYval<T> pxy, const T pz)          { NUM_AXIS_CODE(x = pxy.x, y = pxy.y, z = pz, NOOP, NOOP, NOOP, NOOP, NOOP, NOOP); }
401 412
   FI void set(const T (&arr)[XY])                      { x = arr[0]; y = arr[1]; }
402 413
   #if HAS_Z_AXIS
403
-    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]); }
404
-    FI void set(LINEAR_AXIS_ARGS(const T))             { LINEAR_AXIS_CODE(a = x,      b = y,      c = z,      u = i,      v = j,      w = k    ); }
414
+    FI void set(const T (&arr)[NUM_AXES])              { NUM_AXIS_CODE(x = arr[0], y = arr[1], z = arr[2], i = arr[3], j = arr[4], k = arr[5], u = arr[6], v = arr[7], w = arr[8]); }
415
+    FI void set(NUM_AXIS_ARGS(const T))                { NUM_AXIS_CODE(a = x,      b = y,      c = z,     _i = i,     _j = j,     _k = k,     _u = u,     _v = v,     _w = w   ); }
405 416
   #endif
406
-  #if LOGICAL_AXES > LINEAR_AXES
407
-    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]); }
408
-    FI void set(LOGICAL_AXIS_ARGS(const T))            { LINEAR_AXIS_CODE(a = x,      b = y,      c = z,      u = i,      v = j,      w = k    ); }
417
+  #if LOGICAL_AXES > NUM_AXES
418
+    FI void set(const T (&arr)[LOGICAL_AXES])          { NUM_AXIS_CODE(x = arr[0], y = arr[1], z = arr[2], i = arr[3], j = arr[4], k = arr[5], u = arr[6], v = arr[7], w = arr[8]); }
419
+    FI void set(LOGICAL_AXIS_ARGS(const T))            { NUM_AXIS_CODE(a = x,      b = y,      c = z,     _i = i,     _j = j,     _k = k,     _u = u,     _v = v,     _w = w   ); }
409 420
     #if DISTINCT_AXES > LOGICAL_AXES
410
-      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]); }
421
+      FI void set(const T (&arr)[DISTINCT_AXES])       { NUM_AXIS_CODE(x = arr[0], y = arr[1], z = arr[2], i = arr[3], j = arr[4], k = arr[5], u = arr[6], v = arr[7], w = arr[8]); }
411 422
     #endif
412 423
   #endif
413 424
   #if HAS_I_AXIS
414
-    FI void set(const T px, const T py, const T pz)                         { x = px; y = py; z = pz; }
425
+    FI void set(const T px, const T py, const T pz) { x = px; y = py; z = pz; }
415 426
   #endif
416 427
   #if HAS_J_AXIS
417
-    FI void set(const T px, const T py, const T pz, const T pi)             { x = px; y = py; z = pz; i = pi; }
428
+    FI void set(const T px, const T py, const T pz, const T pi) { x = px; y = py; z = pz; i = pi; }
418 429
   #endif
419 430
   #if HAS_K_AXIS
420 431
     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; }
421 432
   #endif
433
+  #if HAS_U_AXIS
434
+    FI void set(const T px, const T py, const T pz, const T pi, const T pj, const T pk) { x = px; y = py; z = pz; i = pi; j = pj; k = pk; }
435
+  #endif
436
+  #if HAS_V_AXIS
437
+    FI void set(const T px, const T py, const T pz, const T pi, const T pj, const T pk, const T pm) { x = px; y = py; z = pz; i = pi; j = pj; k = pk; u = pu; }
438
+  #endif
439
+  #if HAS_W_AXIS
440
+    FI void set(const T px, const T py, const T pz, const T pi, const T pj, const T pk, const T pm, const T po) { x = px; y = py; z = pz; i = pi; j = pj; k = pk; u = pu; v = pv; }
441
+  #endif
422 442
 
423 443
   // Length reduced to one dimension
424
-  FI T magnitude()                               const { return (T)sqrtf(LINEAR_AXIS_GANG(x*x, + y*y, + z*z, + i*i, + j*j, + k*k)); }
444
+  FI T magnitude()                               const { return (T)sqrtf(NUM_AXIS_GANG(x*x, + y*y, + z*z, + i*i, + j*j, + k*k, + u*u, + v*v, + w*w)); }
425 445
   // Pointer to the data as a simple array
426 446
   FI operator T* ()                                    { return pos; }
427 447
   // If any element is true then it's true
428
-  FI operator bool()                                   { return LINEAR_AXIS_GANG(x, || y, || z, || i, || j, || k); }
448
+  FI operator bool()                                   { return NUM_AXIS_GANG(x, || y, || z, || i, || j, || k, || u, || v, || w); }
429 449
 
430 450
   // Explicit copy and copies with conversion
431 451
   FI XYZval<T>          copy()                   const { XYZval<T> o = *this; return o; }
432
-  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))); }
433
-  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)); }
434
-  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)); }
435
-  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)); }
436
-  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)); }
437
-  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))); }
438
-  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))); }
439
-  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)); }
440
-  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)); }
441
-  FI XYZval<float> reciprocal()                  const { return LINEAR_AXIS_ARRAY(_RECIP(x),  _RECIP(y),  _RECIP(z),  _RECIP(i),  _RECIP(j),  _RECIP(k)); }
452
+  FI XYZval<T>           ABS()                   const { return NUM_AXIS_ARRAY(T(_ABS(x)), T(_ABS(y)), T(_ABS(z)), T(_ABS(i)), T(_ABS(j)), T(_ABS(k)), T(_ABS(u)), T(_ABS(v)), T(_ABS(w))); }
453
+  FI XYZval<int16_t>   asInt()                         { return NUM_AXIS_ARRAY(int16_t(x), int16_t(y), int16_t(z), int16_t(i), int16_t(j), int16_t(k), int16_t(u), int16_t(v), int16_t(w)); }
454
+  FI XYZval<int16_t>   asInt()                   const { return NUM_AXIS_ARRAY(int16_t(x), int16_t(y), int16_t(z), int16_t(i), int16_t(j), int16_t(k), int16_t(u), int16_t(v), int16_t(w)); }
455
+  FI XYZval<int32_t>  asLong()                         { return NUM_AXIS_ARRAY(int32_t(x), int32_t(y), int32_t(z), int32_t(i), int32_t(j), int32_t(k), int32_t(u), int32_t(v), int32_t(w)); }
456
+  FI XYZval<int32_t>  asLong()                   const { return NUM_AXIS_ARRAY(int32_t(x), int32_t(y), int32_t(z), int32_t(i), int32_t(j), int32_t(k), int32_t(u), int32_t(v), int32_t(w)); }
457
+  FI XYZval<int32_t>  ROUNDL()                         { return NUM_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)), int32_t(LROUND(u)), int32_t(LROUND(v)), int32_t(LROUND(w))); }
458
+  FI XYZval<int32_t>  ROUNDL()                   const { return NUM_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)), int32_t(LROUND(u)), int32_t(LROUND(v)), int32_t(LROUND(w))); }
459
+  FI XYZval<float>   asFloat()                         { return NUM_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), static_cast<float>(u), static_cast<float>(v), static_cast<float>(w)); }
460
+  FI XYZval<float>   asFloat()                   const { return NUM_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), static_cast<float>(u), static_cast<float>(v), static_cast<float>(w)); }
461
+  FI XYZval<float> reciprocal()                  const { return NUM_AXIS_ARRAY(_RECIP(x),  _RECIP(y),  _RECIP(z),  _RECIP(i),  _RECIP(j),  _RECIP(k),  _RECIP(u),  _RECIP(v),  _RECIP(w)); }
442 462
 
443 463
   // Marlin workspace shifting is done with G92 and M206
444 464
   FI XYZval<float> asLogical()                   const { XYZval<float> o = asFloat(); toLogical(o); return o; }
@@ -449,78 +469,78 @@ struct XYZval {
449 469
   FI operator const XYval<T>&()                  const { return *(const XYval<T>*)this; }
450 470
 
451 471
   // Cast to a type with more fields by making a new object
452
-  FI operator       XYZEval<T>()                 const { return LINEAR_AXIS_ARRAY(x, y, z, i, j, k); }
472
+  FI operator       XYZEval<T>()                 const { return NUM_AXIS_ARRAY(x, y, z, i, j, k, u, v, w); }
453 473
 
454 474
   // Accessor via an AxisEnum (or any integer) [index]
455 475
   FI       T&   operator[](const int n)                { return pos[n]; }
456 476
   FI const T&   operator[](const int n)          const { return pos[n]; }
457 477
 
458 478
   // Assignment operator overrides do the expected thing
459
-  FI XYZval<T>& operator= (const T v)                  { set(ARRAY_N_1(LINEAR_AXES, v)); return *this; }
479
+  FI XYZval<T>& operator= (const T v)                  { set(ARRAY_N_1(NUM_AXES, v)); return *this; }
460 480
   FI XYZval<T>& operator= (const XYval<T>   &rs)       { set(rs.x, rs.y      ); return *this; }
461
-  FI XYZval<T>& operator= (const XYZEval<T> &rs)       { set(LINEAR_AXIS_ELEM(rs)); return *this; }
481
+  FI XYZval<T>& operator= (const XYZEval<T> &rs)       { set(NUM_AXIS_ELEM(rs)); return *this; }
462 482
 
463 483
   // Override other operators to get intuitive behaviors
464
-  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; }
465
-  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; }
466
-  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; }
467
-  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; }
468
-  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; }
469
-  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; }
470
-  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; }
471
-  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; }
472
-  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; }
473
-  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; }
474
-  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; }
475
-  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; }
476
-  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; }
477
-  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; }
478
-  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; }
479
-  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; }
480
-  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; }
481
-  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; }
482
-  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; }
483
-  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; }
484
-  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; }
485
-  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; }
486
-  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; }
487
-  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; }
488
-  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; }
489
-  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; }
490
-  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; }
491
-  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; }
492
-  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; }
493
-  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; }
494
-  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; }
495
-  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; }
496
-  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; }
497
-  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; }
498
-  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; }
499
-  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; }
500
-  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; }
501
-  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; }
484
+  FI XYZval<T>  operator+ (const XYval<T>   &rs) const { XYZval<T> ls = *this; NUM_AXIS_CODE(ls.x += rs.x, ls.y += rs.y, NOOP        , NOOP        , NOOP        , NOOP        , NOOP        , NOOP        , NOOP        ); return ls; }
485
+  FI XYZval<T>  operator+ (const XYval<T>   &rs)       { XYZval<T> ls = *this; NUM_AXIS_CODE(ls.x += rs.x, ls.y += rs.y, NOOP        , NOOP        , NOOP        , NOOP        , NOOP        , NOOP        , NOOP        ); return ls; }
486
+  FI XYZval<T>  operator- (const XYval<T>   &rs) const { XYZval<T> ls = *this; NUM_AXIS_CODE(ls.x -= rs.x, ls.y -= rs.y, NOOP        , NOOP        , NOOP        , NOOP        , NOOP        , NOOP        , NOOP        ); return ls; }
487
+  FI XYZval<T>  operator- (const XYval<T>   &rs)       { XYZval<T> ls = *this; NUM_AXIS_CODE(ls.x -= rs.x, ls.y -= rs.y, NOOP        , NOOP        , NOOP        , NOOP        , NOOP        , NOOP        , NOOP        ); return ls; }
488
+  FI XYZval<T>  operator* (const XYval<T>   &rs) const { XYZval<T> ls = *this; NUM_AXIS_CODE(ls.x *= rs.x, ls.y *= rs.y, NOOP        , NOOP        , NOOP        , NOOP        , NOOP        , NOOP        , NOOP        ); return ls; }
489
+  FI XYZval<T>  operator* (const XYval<T>   &rs)       { XYZval<T> ls = *this; NUM_AXIS_CODE(ls.x *= rs.x, ls.y *= rs.y, NOOP        , NOOP        , NOOP        , NOOP        , NOOP        , NOOP        , NOOP        ); return ls; }
490
+  FI XYZval<T>  operator/ (const XYval<T>   &rs) const { XYZval<T> ls = *this; NUM_AXIS_CODE(ls.x /= rs.x, ls.y /= rs.y, NOOP        , NOOP        , NOOP        , NOOP        , NOOP        , NOOP        , NOOP        ); return ls; }
491
+  FI XYZval<T>  operator/ (const XYval<T>   &rs)       { XYZval<T> ls = *this; NUM_AXIS_CODE(ls.x /= rs.x, ls.y /= rs.y, NOOP        , NOOP        , NOOP        , NOOP        , NOOP        , NOOP        , NOOP        ); return ls; }
492
+  FI XYZval<T>  operator+ (const XYZval<T>  &rs) const { XYZval<T> ls = *this; NUM_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, ls.u += rs.u, ls.v += rs.v, ls.w += rs.w); return ls; }
493
+  FI XYZval<T>  operator+ (const XYZval<T>  &rs)       { XYZval<T> ls = *this; NUM_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, ls.u += rs.u, ls.v += rs.v, ls.w += rs.w); return ls; }
494
+  FI XYZval<T>  operator- (const XYZval<T>  &rs) const { XYZval<T> ls = *this; NUM_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, ls.u -= rs.u, ls.v -= rs.v, ls.w -= rs.w); return ls; }
495
+  FI XYZval<T>  operator- (const XYZval<T>  &rs)       { XYZval<T> ls = *this; NUM_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, ls.u -= rs.u, ls.v -= rs.v, ls.w -= rs.w); return ls; }
496
+  FI XYZval<T>  operator* (const XYZval<T>  &rs) const { XYZval<T> ls = *this; NUM_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, ls.u *= rs.u, ls.v *= rs.v, ls.w *= rs.w); return ls; }
497
+  FI XYZval<T>  operator* (const XYZval<T>  &rs)       { XYZval<T> ls = *this; NUM_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, ls.u *= rs.u, ls.v *= rs.v, ls.w *= rs.w); return ls; }
498
+  FI XYZval<T>  operator/ (const XYZval<T>  &rs) const { XYZval<T> ls = *this; NUM_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, ls.u /= rs.u, ls.v /= rs.v, ls.w /= rs.w); return ls; }
499
+  FI XYZval<T>  operator/ (const XYZval<T>  &rs)       { XYZval<T> ls = *this; NUM_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, ls.u /= rs.u, ls.v /= rs.v, ls.w /= rs.w); return ls; }
500
+  FI XYZval<T>  operator+ (const XYZEval<T> &rs) const { XYZval<T> ls = *this; NUM_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, ls.u += rs.u, ls.v += rs.v, ls.w += rs.w); return ls; }
501
+  FI XYZval<T>  operator+ (const XYZEval<T> &rs)       { XYZval<T> ls = *this; NUM_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, ls.u += rs.u, ls.v += rs.v, ls.w += rs.w); return ls; }
502
+  FI XYZval<T>  operator- (const XYZEval<T> &rs) const { XYZval<T> ls = *this; NUM_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, ls.u -= rs.u, ls.v -= rs.v, ls.w -= rs.w); return ls; }
503
+  FI XYZval<T>  operator- (const XYZEval<T> &rs)       { XYZval<T> ls = *this; NUM_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, ls.u -= rs.u, ls.v -= rs.v, ls.w -= rs.w); return ls; }
504
+  FI XYZval<T>  operator* (const XYZEval<T> &rs) const { XYZval<T> ls = *this; NUM_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, ls.u *= rs.u, ls.v *= rs.v, ls.w *= rs.w); return ls; }
505
+  FI XYZval<T>  operator* (const XYZEval<T> &rs)       { XYZval<T> ls = *this; NUM_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, ls.u *= rs.u, ls.v *= rs.v, ls.w *= rs.w); return ls; }
506
+  FI XYZval<T>  operator/ (const XYZEval<T> &rs) const { XYZval<T> ls = *this; NUM_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, ls.u /= rs.u, ls.v /= rs.v, ls.w /= rs.w); return ls; }
507
+  FI XYZval<T>  operator/ (const XYZEval<T> &rs)       { XYZval<T> ls = *this; NUM_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, ls.u /= rs.u, ls.v /= rs.v, ls.w /= rs.w); return ls; }
508
+  FI XYZval<T>  operator* (const float &v)       const { XYZval<T> ls = *this; NUM_AXIS_CODE(ls.x *= v,    ls.y *= v,    ls.z *= v,    ls.i *= v,    ls.j *= v,    ls.k *= v,    ls.u *= v,    ls.v *= v,    ls.w *= v   ); return ls; }
509
+  FI XYZval<T>  operator* (const float &v)             { XYZval<T> ls = *this; NUM_AXIS_CODE(ls.x *= v,    ls.y *= v,    ls.z *= v,    ls.i *= v,    ls.j *= v,    ls.k *= v,    ls.u *= v,    ls.v *= v,    ls.w *= v   ); return ls; }
510
+  FI XYZval<T>  operator* (const int &v)         const { XYZval<T> ls = *this; NUM_AXIS_CODE(ls.x *= v,    ls.y *= v,    ls.z *= v,    ls.i *= v,    ls.j *= v,    ls.k *= v,    ls.u *= v,    ls.v *= v,    ls.w *= v   ); return ls; }
511
+  FI XYZval<T>  operator* (const int &v)               { XYZval<T> ls = *this; NUM_AXIS_CODE(ls.x *= v,    ls.y *= v,    ls.z *= v,    ls.i *= v,    ls.j *= v,    ls.k *= v,    ls.u *= v,    ls.v *= v,    ls.w *= v   ); return ls; }
512
+  FI XYZval<T>  operator/ (const float &v)       const { XYZval<T> ls = *this; NUM_AXIS_CODE(ls.x /= v,    ls.y /= v,    ls.z /= v,    ls.i /= v,    ls.j /= v,    ls.k /= v,    ls.u /= v,    ls.v /= v,    ls.w /= v   ); return ls; }
513
+  FI XYZval<T>  operator/ (const float &v)             { XYZval<T> ls = *this; NUM_AXIS_CODE(ls.x /= v,    ls.y /= v,    ls.z /= v,    ls.i /= v,    ls.j /= v,    ls.k /= v,    ls.u /= v,    ls.v /= v,    ls.w /= v   ); return ls; }
514
+  FI XYZval<T>  operator/ (const int &v)         const { XYZval<T> ls = *this; NUM_AXIS_CODE(ls.x /= v,    ls.y /= v,    ls.z /= v,    ls.i /= v,    ls.j /= v,    ls.k /= v,    ls.u /= v,    ls.v /= v,    ls.w /= v   ); return ls; }
515
+  FI XYZval<T>  operator/ (const int &v)               { XYZval<T> ls = *this; NUM_AXIS_CODE(ls.x /= v,    ls.y /= v,    ls.z /= v,    ls.i /= v,    ls.j /= v,    ls.k /= v,    ls.u /= v,    ls.v /= v,    ls.w /= v   ); return ls; }
516
+  FI XYZval<T>  operator>>(const int &v)         const { XYZval<T> ls = *this; NUM_AXIS_CODE(_RS(ls.x),    _RS(ls.y),    _RS(ls.z),    _RS(ls.i),    _RS(ls.j),    _RS(ls.k),    _RS(ls.u),    _RS(ls.v),    _RS(ls.w)   ); return ls; }
517
+  FI XYZval<T>  operator>>(const int &v)               { XYZval<T> ls = *this; NUM_AXIS_CODE(_RS(ls.x),    _RS(ls.y),    _RS(ls.z),    _RS(ls.i),    _RS(ls.j),    _RS(ls.k),    _RS(ls.u),    _RS(ls.v),    _RS(ls.w)   ); return ls; }
518
+  FI XYZval<T>  operator<<(const int &v)         const { XYZval<T> ls = *this; NUM_AXIS_CODE(_LS(ls.x),    _LS(ls.y),    _LS(ls.z),    _LS(ls.i),    _LS(ls.j),    _LS(ls.k),    _LS(ls.u),    _LS(ls.v),    _LS(ls.w)   ); return ls; }
519
+  FI XYZval<T>  operator<<(const int &v)               { XYZval<T> ls = *this; NUM_AXIS_CODE(_LS(ls.x),    _LS(ls.y),    _LS(ls.z),    _LS(ls.i),    _LS(ls.j),    _LS(ls.k),    _LS(ls.u),    _LS(ls.v),    _LS(ls.w)   ); return ls; }
520
+  FI const XYZval<T> operator-()                 const { XYZval<T> o = *this; NUM_AXIS_CODE(o.x = -x, o.y = -y, o.z = -z, o.i = -i, o.j = -j, o.k = -k, o.u = -u, o.v = -v, o.w = -w); return o; }
521
+  FI XYZval<T>       operator-()                       { XYZval<T> o = *this; NUM_AXIS_CODE(o.x = -x, o.y = -y, o.z = -z, o.i = -i, o.j = -j, o.k = -k, o.u = -u, o.v = -v, o.w = -w); return o; }
502 522
 
503 523
   // Modifier operators
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 XYval<T>   &rs)       { LINEAR_AXIS_CODE(x -= rs.x, y -= rs.y, NOOP,      NOOP,      NOOP,      NOOP     ); return *this; }
506
-  FI XYZval<T>& operator*=(const XYval<T>   &rs)       { LINEAR_AXIS_CODE(x *= rs.x, y *= rs.y, NOOP,      NOOP,      NOOP,      NOOP     ); return *this; }
507
-  FI XYZval<T>& operator/=(const XYval<T>   &rs)       { LINEAR_AXIS_CODE(x /= rs.x, y /= rs.y, NOOP,      NOOP,      NOOP,      NOOP     ); 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 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; }
510
-  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; }
511
-  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; }
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 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; }
514
-  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; }
515
-  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; }
516
-  FI XYZval<T>& operator*=(const float &v)             { LINEAR_AXIS_CODE(x *= v,    y *= v,    z *= v,    i *= v,    j *= v,    k *= v);    return *this; }
517
-  FI XYZval<T>& operator*=(const int &v)               { LINEAR_AXIS_CODE(x *= v,    y *= v,    z *= v,    i *= v,    j *= v,    k *= v);    return *this; }
518
-  FI XYZval<T>& operator>>=(const int &v)              { LINEAR_AXIS_CODE(_RS(x),    _RS(y),    _RS(z),    _RS(i),    _RS(j),    _RS(k));    return *this; }
519
-  FI XYZval<T>& operator<<=(const int &v)              { LINEAR_AXIS_CODE(_LS(x),    _LS(y),    _LS(z),    _LS(i),    _LS(j),    _LS(k));    return *this; }
524
+  FI XYZval<T>& operator+=(const XYval<T>   &rs)       { NUM_AXIS_CODE(x += rs.x, y += rs.y, NOOP,      NOOP,      NOOP,      NOOP,      NOOP,      NOOP,      NOOP     ); return *this; }
525
+  FI XYZval<T>& operator-=(const XYval<T>   &rs)       { NUM_AXIS_CODE(x -= rs.x, y -= rs.y, NOOP,      NOOP,      NOOP,      NOOP,      NOOP,      NOOP,      NOOP     ); return *this; }
526
+  FI XYZval<T>& operator*=(const XYval<T>   &rs)       { NUM_AXIS_CODE(x *= rs.x, y *= rs.y, NOOP,      NOOP,      NOOP,      NOOP,      NOOP,      NOOP,      NOOP     ); return *this; }
527
+  FI XYZval<T>& operator/=(const XYval<T>   &rs)       { NUM_AXIS_CODE(x /= rs.x, y /= rs.y, NOOP,      NOOP,      NOOP,      NOOP,      NOOP,      NOOP,      NOOP     ); return *this; }
528
+  FI XYZval<T>& operator+=(const XYZval<T>  &rs)       { NUM_AXIS_CODE(x += rs.x, y += rs.y, z += rs.z, i += rs.i, j += rs.j, k += rs.k, u += rs.u, v += rs.v, w += rs.w); return *this; }
529
+  FI XYZval<T>& operator-=(const XYZval<T>  &rs)       { NUM_AXIS_CODE(x -= rs.x, y -= rs.y, z -= rs.z, i -= rs.i, j -= rs.j, k -= rs.k, u -= rs.u, v -= rs.v, w -= rs.w); return *this; }
530
+  FI XYZval<T>& operator*=(const XYZval<T>  &rs)       { NUM_AXIS_CODE(x *= rs.x, y *= rs.y, z *= rs.z, i *= rs.i, j *= rs.j, k *= rs.k, u *= rs.u, v *= rs.v, w *= rs.w); return *this; }
531
+  FI XYZval<T>& operator/=(const XYZval<T>  &rs)       { NUM_AXIS_CODE(x /= rs.x, y /= rs.y, z /= rs.z, i /= rs.i, j /= rs.j, k /= rs.k, u /= rs.u, v /= rs.v, w /= rs.w); return *this; }
532
+  FI XYZval<T>& operator+=(const XYZEval<T> &rs)       { NUM_AXIS_CODE(x += rs.x, y += rs.y, z += rs.z, i += rs.i, j += rs.j, k += rs.k, u += rs.u, v += rs.v, w += rs.w); return *this; }
533
+  FI XYZval<T>& operator-=(const XYZEval<T> &rs)       { NUM_AXIS_CODE(x -= rs.x, y -= rs.y, z -= rs.z, i -= rs.i, j -= rs.j, k -= rs.k, u -= rs.u, v -= rs.v, w -= rs.w); return *this; }
534
+  FI XYZval<T>& operator*=(const XYZEval<T> &rs)       { NUM_AXIS_CODE(x *= rs.x, y *= rs.y, z *= rs.z, i *= rs.i, j *= rs.j, k *= rs.k, u *= rs.u, v *= rs.v, w *= rs.w); return *this; }
535
+  FI XYZval<T>& operator/=(const XYZEval<T> &rs)       { NUM_AXIS_CODE(x /= rs.x, y /= rs.y, z /= rs.z, i /= rs.i, j /= rs.j, k /= rs.k, u /= rs.u, v /= rs.v, w /= rs.w); return *this; }
536
+  FI XYZval<T>& operator*=(const float &v)             { NUM_AXIS_CODE(x *= v,    y *= v,    z *= v,    i *= v,    j *= v,    k *= v,    u *= v,    v *= v,    w *= v);    return *this; }
537
+  FI XYZval<T>& operator*=(const int &v)               { NUM_AXIS_CODE(x *= v,    y *= v,    z *= v,    i *= v,    j *= v,    k *= v,    u *= v,    v *= v,    w *= v);    return *this; }
538
+  FI XYZval<T>& operator>>=(const int &v)              { NUM_AXIS_CODE(_RS(x),    _RS(y),    _RS(z),    _RS(i),    _RS(j),    _RS(k),    _RS(u),    _RS(v),    _RS(w));    return *this; }
539
+  FI XYZval<T>& operator<<=(const int &v)              { NUM_AXIS_CODE(_LS(x),    _LS(y),    _LS(z),    _LS(i),    _LS(j),    _LS(k),    _LS(u),    _LS(v),    _LS(w));    return *this; }
520 540
 
521 541
   // Exact comparisons. For floats a "NEAR" operation may be better.
522
-  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); }
523
-  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); }
542
+  FI bool       operator==(const XYZEval<T> &rs)       { return true NUM_AXIS_GANG(&& x == rs.x, && y == rs.y, && z == rs.z, && i == rs.i, && j == rs.j, && k == rs.k, && u == rs.u, && v == rs.v, && w == rs.w); }
543
+  FI bool       operator==(const XYZEval<T> &rs) const { return true NUM_AXIS_GANG(&& x == rs.x, && y == rs.y, && z == rs.z, && i == rs.i, && j == rs.j, && k == rs.k, && u == rs.u, && v == rs.v, && w == rs.w); }
524 544
   FI bool       operator!=(const XYZEval<T> &rs)       { return !operator==(rs); }
525 545
   FI bool       operator!=(const XYZEval<T> &rs) const { return !operator==(rs); }
526 546
 };
@@ -532,56 +552,66 @@ template<typename T>
532 552
 struct XYZEval {
533 553
   union {
534 554
     struct { T LOGICAL_AXIS_ARGS(); };
535
-    struct { T LOGICAL_AXIS_LIST(_e, a, b, c, u, v, w); };
555
+    struct { T LOGICAL_AXIS_LIST(_e, a, b, c, _i, _j, _k, _u, _v, _w); };
536 556
     T pos[LOGICAL_AXES];
537 557
   };
538 558
   // Reset all to 0
539
-  FI void reset()                     { LOGICAL_AXIS_GANG(e =, x =, y =, z =, i =, j =, k =) 0; }
559
+  FI void reset()                     { LOGICAL_AXIS_GANG(e =, x =, y =, z =, i =, j =, k =, u =, v =, w =) 0; }
540 560
 
541 561
   // Setters for some number of linear axes, not all
542
-  FI void set(const T px)                                                   { x = px; }
543
-  FI void set(const T px, const T py)                                       { x = px; y = py; }
562
+  FI void set(const T px)                                                                                       { x = px; }
563
+  FI void set(const T px, const T py)                                                                           { x = px; y = py; }
544 564
   #if HAS_I_AXIS
545
-    FI void set(const T px, const T py, const T pz)                         { x = px; y = py; z = pz; }
565
+    FI void set(const T px, const T py, const T pz)                                                             { x = px; y = py; z = pz; }
546 566
   #endif
547 567
   #if HAS_J_AXIS
548
-    FI void set(const T px, const T py, const T pz, const T pi)             { x = px; y = py; z = pz; i = pi; }
568
+    FI void set(const T px, const T py, const T pz, const T pi)                                                 { x = px; y = py; z = pz; i = pi; }
549 569
   #endif
550 570
   #if HAS_K_AXIS
551
-    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; }
571
+    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; }
572
+  #endif
573
+  #if HAS_U_AXIS
574
+    FI void set(const T px, const T py, const T pz, const T pi, const T pj, const T pk)                         { x = px; y = py; z = pz; i = pi; j = pj; k = pk; }
552 575
   #endif
576
+  #if HAS_V_AXIS
577
+    FI void set(const T px, const T py, const T pz, const T pi, const T pj, const T pk, const T pm)             { x = px; y = py; z = pz; i = pi; j = pj; k = pk; u = pu; }
578
+  #endif
579
+  #if HAS_W_AXIS
580
+    FI void set(const T px, const T py, const T pz, const T pi, const T pj, const T pk, const T pm, const T po) { x = px; y = py; z = pz; i = pi; j = pj; k = pk; u = pm; v = pv; }
581
+  #endif
582
+
553 583
   // Setters taking struct types and arrays
554
-  FI void set(const XYval<T> pxy)                  { x = pxy.x; y = pxy.y; }
555
-  FI void set(const XYZval<T> pxyz)                { set(LINEAR_AXIS_ELEM(pxyz)); }
584
+  FI void set(const XYval<T> pxy)                           { x = pxy.x; y = pxy.y; }
585
+  FI void set(const XYZval<T> pxyz)                         { set(NUM_AXIS_ELEM(pxyz)); }
556 586
   #if HAS_Z_AXIS
557
-    FI void set(LINEAR_AXIS_ARGS(const T))         { LINEAR_AXIS_CODE(a = x, b = y, c = z, u = i, v = j, w = k); }
587
+    FI void set(NUM_AXIS_ARGS(const T))                     { NUM_AXIS_CODE(a = x, b = y, c = z, _i = i, _j = j, _k = k, _u = u, _v = v, _w = w); }
558 588
   #endif
559
-  FI void set(const XYval<T> pxy, const T pz)      { set(pxy); TERN_(HAS_Z_AXIS, z = pz); }
560
-  #if LOGICAL_AXES > LINEAR_AXES
589
+  FI void set(const XYval<T> pxy, const T pz)               { set(pxy); TERN_(HAS_Z_AXIS, z = pz); }
590
+  #if LOGICAL_AXES > NUM_AXES
561 591
     FI void set(const XYval<T> pxy, const T pz, const T pe) { set(pxy, pz); e = pe; }
562
-    FI void set(const XYZval<T> pxyz, const T pe)  { set(pxyz); e = pe; }
563
-    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); }
592
+    FI void set(const XYZval<T> pxyz, const T pe)           { set(pxyz); e = pe; }
593
+    FI void set(LOGICAL_AXIS_ARGS(const T))                 { LOGICAL_AXIS_CODE(_e = e, a = x, b = y, c = z, _i = i, _j = j, _k = k, _u = u, _v = v, _w = w); }
564 594
   #endif
565 595
 
566 596
   // Length reduced to one dimension
567
-  FI T magnitude()                                 const { return (T)sqrtf(LOGICAL_AXIS_GANG(+ e*e, + x*x, + y*y, + z*z, + i*i, + j*j, + k*k)); }
597
+  FI T magnitude()                                 const { return (T)sqrtf(LOGICAL_AXIS_GANG(+ e*e, + x*x, + y*y, + z*z, + i*i, + j*j, + k*k, + u*u, + v*v, + w*w)); }
568 598
   // Pointer to the data as a simple array
569 599
   FI operator T* ()                                      { return pos; }
570 600
   // If any element is true then it's true
571
-  FI operator bool()                                     { return 0 LOGICAL_AXIS_GANG(|| e, || x, || y, || z, || i, || j, || k); }
601
+  FI operator bool()                                     { return 0 LOGICAL_AXIS_GANG(|| e, || x, || y, || z, || i, || j, || k, || u, || v, || w); }
572 602
 
573 603
   // Explicit copy and copies with conversion
574
-  FI XYZEval<T>          copy()  const { XYZEval<T> o = *this; return o; }
575
-  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))); }
576
-  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)); }
577
-  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)); }
578
-  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)); }
579
-  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)); }
580
-  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))); }
581
-  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))); }
582
-  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)); }
583
-  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)); }
584
-  FI XYZEval<float> reciprocal() const { return LOGICAL_AXIS_ARRAY(_RECIP(e),  _RECIP(x),  _RECIP(y),  _RECIP(z),  _RECIP(i),  _RECIP(j),  _RECIP(k)); }
604
+  FI XYZEval<T>          copy()  const { XYZEval<T> v = *this; return v; }
605
+  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)), T(_ABS(u)), T(_ABS(v)), T(_ABS(w))); }
606
+  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), int16_t(u), int16_t(v), int16_t(w)); }
607
+  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), int16_t(u), int16_t(v), int16_t(w)); }
608
+  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), int32_t(u), int32_t(v), int32_t(w)); }
609
+  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), int32_t(u), int32_t(v), int32_t(w)); }
610
+  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)), int32_t(LROUND(u)), int32_t(LROUND(v)), int32_t(LROUND(w))); }
611
+  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)), int32_t(LROUND(u)), int32_t(LROUND(v)), int32_t(LROUND(w))); }
612
+  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), static_cast<float>(u), static_cast<float>(v), static_cast<float>(w)); }
613
+  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), static_cast<float>(u), static_cast<float>(v), static_cast<float>(w)); }
614
+  FI XYZEval<float> reciprocal() const { return LOGICAL_AXIS_ARRAY(_RECIP(e),  _RECIP(x),  _RECIP(y),  _RECIP(z),  _RECIP(i),  _RECIP(j),  _RECIP(k),  _RECIP(u),  _RECIP(v),  _RECIP(w)); }
585 615
 
586 616
   // Marlin workspace shifting is done with G92 and M206
587 617
   FI XYZEval<float> asLogical()  const { XYZEval<float> o = asFloat(); toLogical(o); return o; }
@@ -598,9 +628,9 @@ struct XYZEval {
598 628
   FI const T&    operator[](const int n)            const { return pos[n]; }
599 629
 
600 630
   // Assignment operator overrides do the expected thing
601
-  FI XYZEval<T>& operator= (const T v)                    { set(LIST_N_1(LINEAR_AXES, v)); return *this; }
631
+  FI XYZEval<T>& operator= (const T v)                    { set(LIST_N_1(NUM_AXES, v)); return *this; }
602 632
   FI XYZEval<T>& operator= (const XYval<T>   &rs)         { set(rs.x, rs.y); return *this; }
603
-  FI XYZEval<T>& operator= (const XYZval<T>  &rs)         { set(LINEAR_AXIS_ELEM(rs)); return *this; }
633
+  FI XYZEval<T>& operator= (const XYZval<T>  &rs)         { set(NUM_AXIS_ELEM(rs)); return *this; }
604 634
 
605 635
   // Override other operators to get intuitive behaviors
606 636
   FI XYZEval<T>  operator+ (const XYval<T>   &rs)   const { XYZEval<T> ls = *this; ls.x += rs.x; ls.y += rs.y; return ls; }
@@ -611,57 +641,57 @@ struct XYZEval {
611 641
   FI XYZEval<T>  operator* (const XYval<T>   &rs)         { XYZEval<T> ls = *this; ls.x *= rs.x; ls.y *= rs.y; return ls; }
612 642
   FI XYZEval<T>  operator/ (const XYval<T>   &rs)   const { XYZEval<T> ls = *this; ls.x /= rs.x; ls.y /= rs.y; return ls; }
613 643
   FI XYZEval<T>  operator/ (const XYval<T>   &rs)         { XYZEval<T> ls = *this; ls.x /= rs.x; ls.y /= rs.y; return ls; }
614
-  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; }
615
-  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; }
616
-  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; }
617
-  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; }
618
-  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; }
619
-  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; }
620
-  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; }
621
-  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; }
622
-  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; }
623
-  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; }
624
-  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; }
625
-  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; }
626
-  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; }
627
-  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; }
628
-  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; }
629
-  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; }
630
-  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; }
631
-  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; }
632
-  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; }
633
-  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; }
634
-  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; }
635
-  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; }
636
-  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; }
637
-  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; }
638
-  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; }
639
-  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; }
640
-  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; }
641
-  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; }
642
-  FI const XYZEval<T> operator-()                   const { return LOGICAL_AXIS_ARRAY(-e, -x, -y, -z, -i, -j, -k); }
643
-  FI       XYZEval<T> operator-()                         { return LOGICAL_AXIS_ARRAY(-e, -x, -y, -z, -i, -j, -k); }
644
+  FI XYZEval<T>  operator+ (const XYZval<T>  &rs)   const { XYZval<T>  ls = *this; NUM_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, ls.u += rs.u, ls.v += rs.v, ls.w += rs.w); return ls; }
645
+  FI XYZEval<T>  operator+ (const XYZval<T>  &rs)         { XYZval<T>  ls = *this; NUM_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, ls.u += rs.u, ls.v += rs.v, ls.w += rs.w); return ls; }
646
+  FI XYZEval<T>  operator- (const XYZval<T>  &rs)   const { XYZval<T>  ls = *this; NUM_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, ls.u -= rs.u, ls.v -= rs.v, ls.w -= rs.w); return ls; }
647
+  FI XYZEval<T>  operator- (const XYZval<T>  &rs)         { XYZval<T>  ls = *this; NUM_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, ls.u -= rs.u, ls.v -= rs.v, ls.w -= rs.w); return ls; }
648
+  FI XYZEval<T>  operator* (const XYZval<T>  &rs)   const { XYZval<T>  ls = *this; NUM_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, ls.u *= rs.u, ls.v *= rs.v, ls.w *= rs.w); return ls; }
649
+  FI XYZEval<T>  operator* (const XYZval<T>  &rs)         { XYZval<T>  ls = *this; NUM_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, ls.u *= rs.u, ls.v *= rs.v, ls.w *= rs.w); return ls; }
650
+  FI XYZEval<T>  operator/ (const XYZval<T>  &rs)   const { XYZval<T>  ls = *this; NUM_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, ls.u /= rs.u, ls.v /= rs.v, ls.w /= rs.w); return ls; }
651
+  FI XYZEval<T>  operator/ (const XYZval<T>  &rs)         { XYZval<T>  ls = *this; NUM_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, ls.u /= rs.u, ls.v /= rs.v, ls.w /= rs.w); return ls; }
652
+  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, ls.u += rs.u, ls.v += rs.v, ls.w += rs.w); return ls; }
653
+  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, ls.u += rs.u, ls.v += rs.v, ls.w += rs.w); return ls; }
654
+  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, ls.u -= rs.u, ls.v -= rs.v, ls.w -= rs.w); return ls; }
655
+  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, ls.u -= rs.u, ls.v -= rs.v, ls.w -= rs.w); return ls; }
656
+  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, ls.u *= rs.u, ls.v *= rs.v, ls.w *= rs.w); return ls; }
657
+  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, ls.u *= rs.u, ls.v *= rs.v, ls.w *= rs.w); return ls; }
658
+  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, ls.u /= rs.u, ls.v /= rs.v, ls.w /= rs.w); return ls; }
659
+  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, ls.u /= rs.u, ls.v /= rs.v, ls.w /= rs.w); return ls; }
660
+  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,    ls.u *= v,    ls.v *= v,    ls.w *= v   ); return ls; }
661
+  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,    ls.u *= v,    ls.v *= v,    ls.w *= v   ); return ls; }
662
+  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,    ls.u *= v,    ls.v *= v,    ls.w *= v   ); return ls; }
663
+  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,    ls.u *= v,    ls.v *= v,    ls.w *= v   ); return ls; }
664
+  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,    ls.u /= v,    ls.v /= v,    ls.w /= v   ); return ls; }
665
+  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,    ls.u /= v,    ls.v /= v,    ls.w /= v   ); return ls; }
666
+  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,    ls.u /= v,    ls.v /= v,    ls.w /= v   ); return ls; }
667
+  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,    ls.u /= v,    ls.v /= v,    ls.w /= v   ); return ls; }
668
+  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),    _RS(ls.u),    _RS(ls.v),    _RS(ls.w)   ); return ls; }
669
+  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),    _RS(ls.u),    _RS(ls.v),    _RS(ls.w)   ); return ls; }
670
+  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),    _LS(ls.u),    _LS(ls.v),    _LS(ls.w)   ); return ls; }
671
+  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),    _LS(ls.u),    _LS(ls.v),    _LS(ls.w)   ); return ls; }
672
+  FI const XYZEval<T> operator-()                   const { return LOGICAL_AXIS_ARRAY(-e, -x, -y, -z, -i, -j, -k, -u, -v, -w); }
673
+  FI       XYZEval<T> operator-()                         { return LOGICAL_AXIS_ARRAY(-e, -x, -y, -z, -i, -j, -k, -u, -v, -w); }
644 674
 
645 675
   // Modifier operators
646 676
   FI XYZEval<T>& operator+=(const XYval<T>   &rs)         { x += rs.x; y += rs.y; return *this; }
647 677
   FI XYZEval<T>& operator-=(const XYval<T>   &rs)         { x -= rs.x; y -= rs.y; return *this; }
648 678
   FI XYZEval<T>& operator*=(const XYval<T>   &rs)         { x *= rs.x; y *= rs.y; return *this; }
649 679
   FI XYZEval<T>& operator/=(const XYval<T>   &rs)         { x /= rs.x; y /= rs.y; return *this; }
650
-  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; }
651
-  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; }
652
-  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; }
653
-  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; }
654
-  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; }
655
-  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; }
656
-  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; }
657
-  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; }
658
-  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; }
659
-  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; }
660
-  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; }
680
+  FI XYZEval<T>& operator+=(const XYZval<T>  &rs)         { NUM_AXIS_CODE(x += rs.x, y += rs.y, z += rs.z, i += rs.i, j += rs.j, k += rs.k, u += rs.u, v += rs.v, w += rs.w); return *this; }
681
+  FI XYZEval<T>& operator-=(const XYZval<T>  &rs)         { NUM_AXIS_CODE(x -= rs.x, y -= rs.y, z -= rs.z, i -= rs.i, j -= rs.j, k -= rs.k, u -= rs.u, v -= rs.v, w -= rs.w); return *this; }
682
+  FI XYZEval<T>& operator*=(const XYZval<T>  &rs)         { NUM_AXIS_CODE(x *= rs.x, y *= rs.y, z *= rs.z, i *= rs.i, j *= rs.j, k *= rs.k, u *= rs.u, v *= rs.v, w *= rs.w); return *this; }
683
+  FI XYZEval<T>& operator/=(const XYZval<T>  &rs)         { NUM_AXIS_CODE(x /= rs.x, y /= rs.y, z /= rs.z, i /= rs.i, j /= rs.j, k /= rs.k, u /= rs.u, v /= rs.v, w /= rs.w); return *this; }
684
+  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, u += rs.u, v += rs.v, w += rs.w); return *this; }
685
+  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, u -= rs.u, v -= rs.v, w -= rs.w); return *this; }
686
+  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, u *= rs.u, v *= rs.v, w *= rs.w); return *this; }
687
+  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, u /= rs.u, v /= rs.v, w /= rs.w); return *this; }
688
+  FI XYZEval<T>& operator*=(const T &v)                   { LOGICAL_AXIS_CODE(e *= v,    x *= v,    y *= v,    z *= v,    i *= v,    j *= v,    k *= v,    u *= v,    v *= v,    w *= v);    return *this; }
689
+  FI XYZEval<T>& operator>>=(const int &v)                { LOGICAL_AXIS_CODE(_RS(e),    _RS(x),    _RS(y),    _RS(z),    _RS(i),    _RS(j),    _RS(k),    _RS(u),    _RS(v),    _RS(w));    return *this; }
690
+  FI XYZEval<T>& operator<<=(const int &v)                { LOGICAL_AXIS_CODE(_LS(e),    _LS(x),    _LS(y),    _LS(z),    _LS(i),    _LS(j),    _LS(k),    _LS(u),    _LS(v),    _LS(w));    return *this; }
661 691
 
662 692
   // Exact comparisons. For floats a "NEAR" operation may be better.
663
-  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); }
664
-  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); }
693
+  FI bool        operator==(const XYZval<T>  &rs)         { return true NUM_AXIS_GANG(&& x == rs.x, && y == rs.y, && z == rs.z, && i == rs.i, && j == rs.j, && k == rs.k, && u == rs.u, && v == rs.v, && w == rs.w); }
694
+  FI bool        operator==(const XYZval<T>  &rs)   const { return true NUM_AXIS_GANG(&& x == rs.x, && y == rs.y, && z == rs.z, && i == rs.i, && j == rs.j, && k == rs.k, && u == rs.u, && v == rs.v, && w == rs.w); }
665 695
   FI bool        operator!=(const XYZval<T>  &rs)         { return !operator==(rs); }
666 696
   FI bool        operator!=(const XYZval<T>  &rs)   const { return !operator==(rs); }
667 697
 };

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

@@ -125,7 +125,7 @@ void safe_delay(millis_t ms) {
125 125
         #endif
126 126
         #if ABL_PLANAR
127 127
           SERIAL_ECHOPGM("ABL Adjustment");
128
-          LOOP_LINEAR_AXES(a) {
128
+          LOOP_NUM_AXES(a) {
129 129
             SERIAL_CHAR(' ', AXIS_CHAR(a));
130 130
             serial_offset(planner.get_axis_position_mm(AxisEnum(a)) - current_position[a]);
131 131
           }

+ 6
- 3
Marlin/src/core/utility.h View File

@@ -77,10 +77,13 @@ 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', AXIS4_NAME, AXIS5_NAME, AXIS6_NAME);
81
-
82
-#if LINEAR_AXES <= XYZ
80
+// Axis names for G-code parsing, reports, etc.
81
+const xyze_char_t axis_codes LOGICAL_AXIS_ARRAY('E', 'X', 'Y', 'Z', AXIS4_NAME, AXIS5_NAME, AXIS6_NAME, AXIS7_NAME, AXIS8_NAME, AXIS9_NAME);
82
+#if NUM_AXES <= XYZ
83 83
   #define AXIS_CHAR(A) ((char)('X' + A))
84
+  #define IAXIS_CHAR AXIS_CHAR
84 85
 #else
86
+  const xyze_char_t iaxis_codes LOGICAL_AXIS_ARRAY('E', 'X', 'Y', 'Z', 'I', 'J', 'K', 'U', 'V', 'W');
85 87
   #define AXIS_CHAR(A) axis_codes[A]
88
+  #define IAXIS_CHAR(A) iaxis_codes[A]
86 89
 #endif

+ 4
- 4
Marlin/src/feature/backlash.cpp View File

@@ -97,7 +97,7 @@ void Backlash::add_correction_steps(const int32_t &da, const int32_t &db, const
97 97
 
98 98
   const float f_corr = float(correction) / all_on;
99 99
 
100
-  LOOP_LINEAR_AXES(axis) {
100
+  LOOP_NUM_AXES(axis) {
101 101
     if (distance_mm[axis]) {
102 102
       const bool reverse = TEST(dm, axis);
103 103
 
@@ -145,7 +145,7 @@ void Backlash::add_correction_steps(const int32_t &da, const int32_t &db, const
145 145
 }
146 146
 
147 147
 int32_t Backlash::get_applied_steps(const AxisEnum axis) {
148
-  if (axis >= LINEAR_AXES) return 0;
148
+  if (axis >= NUM_AXES) return 0;
149 149
 
150 150
   const bool reverse = TEST(last_direction_bits, axis);
151 151
 
@@ -165,11 +165,11 @@ class Backlash::StepAdjuster {
165 165
   xyz_long_t applied_steps;
166 166
 public:
167 167
   StepAdjuster() {
168
-    LOOP_LINEAR_AXES(axis) applied_steps[axis] = backlash.get_applied_steps((AxisEnum)axis);
168
+    LOOP_NUM_AXES(axis) applied_steps[axis] = backlash.get_applied_steps((AxisEnum)axis);
169 169
   }
170 170
   ~StepAdjuster() {
171 171
     // after backlash compensation parameter changes, ensure applied step count does not change
172
-    LOOP_LINEAR_AXES(axis) residual_error[axis] += backlash.get_applied_steps((AxisEnum)axis) - applied_steps[axis];
172
+    LOOP_NUM_AXES(axis) residual_error[axis] += backlash.get_applied_steps((AxisEnum)axis) - applied_steps[axis];
173 173
   }
174 174
 };
175 175
 

+ 36
- 0
Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp View File

@@ -317,6 +317,42 @@ void unified_bed_leveling::G29() {
317 317
     // Send 'N' to force homing before G29 (internal only)
318 318
     if (axes_should_home() || parser.seen_test('N')) gcode.home_all_axes();
319 319
     TERN_(HAS_MULTI_HOTEND, if (active_extruder != 0) tool_change(0, true));
320
+
321
+    // Position bed horizontally and Z probe vertically.
322
+    #if    defined(SAFE_BED_LEVELING_START_X) || defined(SAFE_BED_LEVELING_START_Y) || defined(SAFE_BED_LEVELING_START_Z) \
323
+        || defined(SAFE_BED_LEVELING_START_I) || defined(SAFE_BED_LEVELING_START_J) || defined(SAFE_BED_LEVELING_START_K) \
324
+        || defined(SAFE_BED_LEVELING_START_U) || defined(SAFE_BED_LEVELING_START_V) || defined(SAFE_BED_LEVELING_START_W)
325
+      xyze_pos_t safe_position = current_position;
326
+      #ifdef SAFE_BED_LEVELING_START_X
327
+        safe_position.x = SAFE_BED_LEVELING_START_X;
328
+      #endif
329
+      #ifdef SAFE_BED_LEVELING_START_Y
330
+        safe_position.y = SAFE_BED_LEVELING_START_Y;
331
+      #endif
332
+      #ifdef SAFE_BED_LEVELING_START_Z
333
+        safe_position.z = SAFE_BED_LEVELING_START_Z;
334
+      #endif
335
+      #ifdef SAFE_BED_LEVELING_START_I
336
+        safe_position.i = SAFE_BED_LEVELING_START_I;
337
+      #endif
338
+      #ifdef SAFE_BED_LEVELING_START_J
339
+        safe_position.j = SAFE_BED_LEVELING_START_J;
340
+      #endif
341
+      #ifdef SAFE_BED_LEVELING_START_K
342
+        safe_position.k = SAFE_BED_LEVELING_START_K;
343
+      #endif
344
+      #ifdef SAFE_BED_LEVELING_START_U
345
+        safe_position.u = SAFE_BED_LEVELING_START_U;
346
+      #endif
347
+      #ifdef SAFE_BED_LEVELING_START_V
348
+        safe_position.v = SAFE_BED_LEVELING_START_V;
349
+      #endif
350
+      #ifdef SAFE_BED_LEVELING_START_W
351
+        safe_position.w = SAFE_BED_LEVELING_START_W;
352
+      #endif
353
+
354
+      do_blocking_move_to(safe_position);
355
+    #endif
320 356
   }
321 357
 
322 358
   // Invalidate one or more nearby mesh points, possibly all.

+ 2
- 2
Marlin/src/feature/encoder_i2c.cpp View File

@@ -337,7 +337,7 @@ bool I2CPositionEncoder::test_axis() {
337 337
   ec = false;
338 338
 
339 339
   xyze_pos_t startCoord, endCoord;
340
-  LOOP_LINEAR_AXES(a) {
340
+  LOOP_NUM_AXES(a) {
341 341
     startCoord[a] = planner.get_axis_position_mm((AxisEnum)a);
342 342
     endCoord[a] = planner.get_axis_position_mm((AxisEnum)a);
343 343
   }
@@ -395,7 +395,7 @@ void I2CPositionEncoder::calibrate_steps_mm(const uint8_t iter) {
395 395
   travelDistance = endDistance - startDistance;
396 396
 
397 397
   xyze_pos_t startCoord, endCoord;
398
-  LOOP_LINEAR_AXES(a) {
398
+  LOOP_NUM_AXES(a) {
399 399
     startCoord[a] = planner.get_axis_position_mm((AxisEnum)a);
400 400
     endCoord[a] = planner.get_axis_position_mm((AxisEnum)a);
401 401
   }

+ 1
- 1
Marlin/src/feature/joystick.cpp View File

@@ -163,7 +163,7 @@ Joystick joystick;
163 163
     // norm_jog values of [-1 .. 1] maps linearly to [-feedrate .. feedrate]
164 164
     xyz_float_t move_dist{0};
165 165
     float hypot2 = 0;
166
-    LOOP_LINEAR_AXES(i) if (norm_jog[i]) {
166
+    LOOP_NUM_AXES(i) if (norm_jog[i]) {
167 167
       move_dist[i] = seg_time * norm_jog[i] * TERN(EXTENSIBLE_UI, manual_feedrate_mm_s, planner.settings.max_feedrate_mm_s)[i];
168 168
       hypot2 += sq(move_dist[i]);
169 169
     }

+ 3
- 3
Marlin/src/feature/powerloss.cpp View File

@@ -562,7 +562,7 @@ void PrintJobRecovery::resume() {
562 562
   TERN_(HAS_HOME_OFFSET, home_offset = info.home_offset);
563 563
   TERN_(HAS_POSITION_SHIFT, position_shift = info.position_shift);
564 564
   #if HAS_HOME_OFFSET || HAS_POSITION_SHIFT
565
-    LOOP_LINEAR_AXES(i) update_workspace_offset((AxisEnum)i);
565
+    LOOP_NUM_AXES(i) update_workspace_offset((AxisEnum)i);
566 566
   #endif
567 567
 
568 568
   // Relative axis modes
@@ -612,7 +612,7 @@ void PrintJobRecovery::resume() {
612 612
 
613 613
         #if HAS_HOME_OFFSET
614 614
           DEBUG_ECHOPGM("home_offset: ");
615
-          LOOP_LINEAR_AXES(i) {
615
+          LOOP_NUM_AXES(i) {
616 616
             if (i) DEBUG_CHAR(',');
617 617
             DEBUG_DECIMAL(info.home_offset[i]);
618 618
           }
@@ -621,7 +621,7 @@ void PrintJobRecovery::resume() {
621 621
 
622 622
         #if HAS_POSITION_SHIFT
623 623
           DEBUG_ECHOPGM("position_shift: ");
624
-          LOOP_LINEAR_AXES(i) {
624
+          LOOP_NUM_AXES(i) {
625 625
             if (i) DEBUG_CHAR(',');
626 626
             DEBUG_DECIMAL(info.position_shift[i]);
627 627
           }

+ 24
- 18
Marlin/src/feature/stepper_driver_safety.cpp View File

@@ -65,15 +65,18 @@ void stepper_driver_backward_check() {
65 65
   TEST_BACKWARD(I,   8);
66 66
   TEST_BACKWARD(J,   9);
67 67
   TEST_BACKWARD(K,  10);
68
-
69
-  TEST_BACKWARD(E0, 11);
70
-  TEST_BACKWARD(E1, 12);
71
-  TEST_BACKWARD(E2, 13);
72
-  TEST_BACKWARD(E3, 14);
73
-  TEST_BACKWARD(E4, 15);
74
-  TEST_BACKWARD(E5, 16);
75
-  TEST_BACKWARD(E6, 17);
76
-  TEST_BACKWARD(E7, 18);
68
+  TEST_BACKWARD(U,  11);
69
+  TEST_BACKWARD(V,  12);
70
+  TEST_BACKWARD(W,  13);
71
+
72
+  TEST_BACKWARD(E0, 14);
73
+  TEST_BACKWARD(E1, 15);
74
+  TEST_BACKWARD(E2, 16);
75
+  TEST_BACKWARD(E3, 17);
76
+  TEST_BACKWARD(E4, 18);
77
+  TEST_BACKWARD(E5, 19);
78
+  TEST_BACKWARD(E6, 20);
79
+  TEST_BACKWARD(E7, 21);
77 80
 
78 81
   if (!axis_plug_backward)
79 82
     WRITE(SAFE_POWER_PIN, HIGH);
@@ -103,15 +106,18 @@ void stepper_driver_backward_report() {
103 106
   REPORT_BACKWARD(I,   8);
104 107
   REPORT_BACKWARD(J,   9);
105 108
   REPORT_BACKWARD(K,  10);
106
-
107
-  REPORT_BACKWARD(E0, 11);
108
-  REPORT_BACKWARD(E1, 12);
109
-  REPORT_BACKWARD(E2, 13);
110
-  REPORT_BACKWARD(E3, 14);
111
-  REPORT_BACKWARD(E4, 15);
112
-  REPORT_BACKWARD(E5, 16);
113
-  REPORT_BACKWARD(E6, 17);
114
-  REPORT_BACKWARD(E7, 18);
109
+  REPORT_BACKWARD(U,  11);
110
+  REPORT_BACKWARD(V,  12);
111
+  REPORT_BACKWARD(W,  13);
112
+
113
+  REPORT_BACKWARD(E0, 14);
114
+  REPORT_BACKWARD(E1, 15);
115
+  REPORT_BACKWARD(E2, 16);
116
+  REPORT_BACKWARD(E3, 17);
117
+  REPORT_BACKWARD(E4, 18);
118
+  REPORT_BACKWARD(E5, 19);
119
+  REPORT_BACKWARD(E6, 20);
120
+  REPORT_BACKWARD(E7, 21);
115 121
 }
116 122
 
117 123
 #endif // HAS_DRIVER_SAFE_POWER_PROTECT

+ 57
- 0
Marlin/src/feature/tmc_util.cpp View File

@@ -429,6 +429,18 @@
429 429
         if (monitor_tmc_driver(stepperK, need_update_error_counters, need_debug_reporting))
430 430
           step_current_down(stepperK);
431 431
       #endif
432
+      #if AXIS_IS_TMC(U)
433
+        if (monitor_tmc_driver(stepperU, need_update_error_counters, need_debug_reporting))
434
+          step_current_down(stepperU);
435
+      #endif
436
+      #if AXIS_IS_TMC(V)
437
+        if (monitor_tmc_driver(stepperV, need_update_error_counters, need_debug_reporting))
438
+          step_current_down(stepperV);
439
+      #endif
440
+      #if AXIS_IS_TMC(W)
441
+        if (monitor_tmc_driver(stepperW, need_update_error_counters, need_debug_reporting))
442
+          step_current_down(stepperW);
443
+      #endif
432 444
 
433 445
       #if AXIS_IS_TMC(E0)
434 446
         (void)monitor_tmc_driver(stepperE0, need_update_error_counters, need_debug_reporting);
@@ -809,6 +821,15 @@
809 821
     #if AXIS_IS_TMC(K)
810 822
       if (k) tmc_status(stepperK, n);
811 823
     #endif
824
+    #if AXIS_IS_TMC(U)
825
+      if (u) tmc_status(stepperU, n);
826
+    #endif
827
+    #if AXIS_IS_TMC(V)
828
+      if (v) tmc_status(stepperV, n);
829
+    #endif
830
+    #if AXIS_IS_TMC(W)
831
+      if (w) tmc_status(stepperW, n);
832
+    #endif
812 833
 
813 834
     if (TERN0(HAS_EXTRUDERS, e)) {
814 835
       #if AXIS_IS_TMC(E0)
@@ -883,6 +904,15 @@
883 904
     #if AXIS_IS_TMC(K)
884 905
       if (k) tmc_parse_drv_status(stepperK, n);
885 906
     #endif
907
+    #if AXIS_IS_TMC(U)
908
+      if (u) tmc_parse_drv_status(stepperU, n);
909
+    #endif
910
+    #if AXIS_IS_TMC(V)
911
+      if (v) tmc_parse_drv_status(stepperV, n);
912
+    #endif
913
+    #if AXIS_IS_TMC(W)
914
+      if (w) tmc_parse_drv_status(stepperW, n);
915
+    #endif
886 916
 
887 917
     if (TERN0(HAS_EXTRUDERS, e)) {
888 918
       #if AXIS_IS_TMC(E0)
@@ -1088,6 +1118,15 @@
1088 1118
     #if AXIS_IS_TMC(K)
1089 1119
       if (k) tmc_get_registers(stepperK, n);
1090 1120
     #endif
1121
+    #if AXIS_IS_TMC(U)
1122
+      if (u) tmc_get_registers(stepperU, n);
1123
+    #endif
1124
+    #if AXIS_IS_TMC(V)
1125
+      if (v) tmc_get_registers(stepperV, n);
1126
+    #endif
1127
+    #if AXIS_IS_TMC(W)
1128
+      if (w) tmc_get_registers(stepperW, n);
1129
+    #endif
1091 1130
 
1092 1131
     if (TERN0(HAS_EXTRUDERS, e)) {
1093 1132
       #if AXIS_IS_TMC(E0)
@@ -1244,6 +1283,15 @@ void test_tmc_connection(LOGICAL_AXIS_ARGS(const bool)) {
1244 1283
   #if AXIS_IS_TMC(K)
1245 1284
     if (k) axis_connection += test_connection(stepperK);
1246 1285
   #endif
1286
+  #if AXIS_IS_TMC(U)
1287
+    if (u) axis_connection += test_connection(stepperU);
1288
+  #endif
1289
+  #if AXIS_IS_TMC(V)
1290
+    if (v) axis_connection += test_connection(stepperV);
1291
+  #endif
1292
+  #if AXIS_IS_TMC(W)
1293
+    if (w) axis_connection += test_connection(stepperW);
1294
+  #endif
1247 1295
 
1248 1296
   if (TERN0(HAS_EXTRUDERS, e)) {
1249 1297
     #if AXIS_IS_TMC(E0)
@@ -1313,6 +1361,15 @@ void test_tmc_connection(LOGICAL_AXIS_ARGS(const bool)) {
1313 1361
     #if AXIS_HAS_SPI(K)
1314 1362
       SET_CS_PIN(K);
1315 1363
     #endif
1364
+    #if AXIS_HAS_SPI(U)
1365
+      SET_CS_PIN(U);
1366
+    #endif
1367
+    #if AXIS_HAS_SPI(V)
1368
+      SET_CS_PIN(V);
1369
+    #endif
1370
+    #if AXIS_HAS_SPI(W)
1371
+      SET_CS_PIN(W);
1372
+    #endif
1316 1373
     #if AXIS_HAS_SPI(E0)
1317 1374
       SET_CS_PIN(E0);
1318 1375
     #endif

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

@@ -348,7 +348,7 @@ void test_tmc_connection(LOGICAL_AXIS_DECL(const bool, true));
348 348
 #if USE_SENSORLESS
349 349
 
350 350
   // Track enabled status of stealthChop and only re-enable where applicable
351
-  struct sensorless_t { bool LINEAR_AXIS_ARGS(), x2, y2, z2, z3, z4; };
351
+  struct sensorless_t { bool NUM_AXIS_ARGS(), x2, y2, z2, z3, z4; };
352 352
 
353 353
   #if ENABLED(IMPROVE_HOMING_RELIABILITY)
354 354
     extern millis_t sg_guard_period;

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

@@ -437,6 +437,42 @@ G29_TYPE GcodeSuite::G29() {
437 437
       #endif
438 438
     }
439 439
 
440
+    // Position bed horizontally and Z probe vertically.
441
+    #if    defined(SAFE_BED_LEVELING_START_X) || defined(SAFE_BED_LEVELING_START_Y) || defined(SAFE_BED_LEVELING_START_Z) \
442
+        || defined(SAFE_BED_LEVELING_START_I) || defined(SAFE_BED_LEVELING_START_J) || defined(SAFE_BED_LEVELING_START_K) \
443
+        || defined(SAFE_BED_LEVELING_START_U) || defined(SAFE_BED_LEVELING_START_V) || defined(SAFE_BED_LEVELING_START_W)
444
+      xyze_pos_t safe_position = current_position;
445
+      #ifdef SAFE_BED_LEVELING_START_X
446
+        safe_position.x = SAFE_BED_LEVELING_START_X;
447
+      #endif
448
+      #ifdef SAFE_BED_LEVELING_START_Y
449
+        safe_position.y = SAFE_BED_LEVELING_START_Y;
450
+      #endif
451
+      #ifdef SAFE_BED_LEVELING_START_Z
452
+        safe_position.z = SAFE_BED_LEVELING_START_Z;
453
+      #endif
454
+      #ifdef SAFE_BED_LEVELING_START_I
455
+        safe_position.i = SAFE_BED_LEVELING_START_I;
456
+      #endif
457
+      #ifdef SAFE_BED_LEVELING_START_J
458
+        safe_position.j = SAFE_BED_LEVELING_START_J;
459
+      #endif
460
+      #ifdef SAFE_BED_LEVELING_START_K
461
+        safe_position.k = SAFE_BED_LEVELING_START_K;
462
+      #endif
463
+      #ifdef SAFE_BED_LEVELING_START_U
464
+        safe_position.u = SAFE_BED_LEVELING_START_U;
465
+      #endif
466
+      #ifdef SAFE_BED_LEVELING_START_V
467
+        safe_position.v = SAFE_BED_LEVELING_START_V;
468
+      #endif
469
+      #ifdef SAFE_BED_LEVELING_START_W
470
+        safe_position.w = SAFE_BED_LEVELING_START_W;
471
+      #endif
472
+
473
+      do_blocking_move_to(safe_position);
474
+    #endif
475
+
440 476
     // Disable auto bed leveling during G29.
441 477
     // Be formal so G29 can be done successively without G28.
442 478
     if (!no_action) set_bed_leveling_enabled(false);

+ 37
- 0
Marlin/src/gcode/bedlevel/mbl/G29.cpp View File

@@ -106,6 +106,43 @@ void GcodeSuite::G29() {
106 106
         queue.inject(parser.seen_test('N') ? F("G28" TERN(CAN_SET_LEVELING_AFTER_G28, "L0", "") "\nG29S2") : F("G29S2"));
107 107
         TERN_(EXTENSIBLE_UI, ExtUI::onLevelingStart());
108 108
         TERN_(DWIN_LCD_PROUI, DWIN_LevelingStart());
109
+
110
+        // Position bed horizontally and Z probe vertically.
111
+        #if    defined(SAFE_BED_LEVELING_START_X) || defined(SAFE_BED_LEVELING_START_Y) || defined(SAFE_BED_LEVELING_START_Z) \
112
+            || defined(SAFE_BED_LEVELING_START_I) || defined(SAFE_BED_LEVELING_START_J) || defined(SAFE_BED_LEVELING_START_K) \
113
+            || defined(SAFE_BED_LEVELING_START_U) || defined(SAFE_BED_LEVELING_START_V) || defined(SAFE_BED_LEVELING_START_W)
114
+          xyze_pos_t safe_position = current_position;
115
+          #ifdef SAFE_BED_LEVELING_START_X
116
+            safe_position.x = SAFE_BED_LEVELING_START_X;
117
+          #endif
118
+          #ifdef SAFE_BED_LEVELING_START_Y
119
+            safe_position.y = SAFE_BED_LEVELING_START_Y;
120
+          #endif
121
+          #ifdef SAFE_BED_LEVELING_START_Z
122
+            safe_position.z = SAFE_BED_LEVELING_START_Z;
123
+          #endif
124
+          #ifdef SAFE_BED_LEVELING_START_I
125
+            safe_position.i = SAFE_BED_LEVELING_START_I;
126
+          #endif
127
+          #ifdef SAFE_BED_LEVELING_START_J
128
+            safe_position.j = SAFE_BED_LEVELING_START_J;
129
+          #endif
130
+          #ifdef SAFE_BED_LEVELING_START_K
131
+            safe_position.k = SAFE_BED_LEVELING_START_K;
132
+          #endif
133
+          #ifdef SAFE_BED_LEVELING_START_U
134
+            safe_position.u = SAFE_BED_LEVELING_START_U;
135
+          #endif
136
+          #ifdef SAFE_BED_LEVELING_START_V
137
+            safe_position.v = SAFE_BED_LEVELING_START_V;
138
+          #endif
139
+          #ifdef SAFE_BED_LEVELING_START_W
140
+            safe_position.w = SAFE_BED_LEVELING_START_W;
141
+          #endif
142
+
143
+          do_blocking_move_to(safe_position);
144
+        #endif
145
+
109 146
         return;
110 147
       }
111 148
       state = MeshNext;

+ 80
- 46
Marlin/src/gcode/calibrate/G28.cpp View File

@@ -82,7 +82,7 @@
82 82
 
83 83
     #if ENABLED(SENSORLESS_HOMING)
84 84
       sensorless_t stealth_states {
85
-        LINEAR_AXIS_LIST(
85
+        NUM_AXIS_LIST(
86 86
           TERN0(X_SENSORLESS, tmc_enable_stallguard(stepperX)),
87 87
           TERN0(Y_SENSORLESS, tmc_enable_stallguard(stepperY)),
88 88
           false, false, false, false
@@ -214,7 +214,7 @@ void GcodeSuite::G28() {
214 214
 
215 215
   #if ENABLED(MARLIN_DEV_MODE)
216 216
     if (parser.seen_test('S')) {
217
-      LOOP_LINEAR_AXES(a) set_axis_is_at_home((AxisEnum)a);
217
+      LOOP_NUM_AXES(a) set_axis_is_at_home((AxisEnum)a);
218 218
       sync_plan_position();
219 219
       SERIAL_ECHOLNPGM("Simulated Homing");
220 220
       report_current_position();
@@ -258,7 +258,7 @@ void GcodeSuite::G28() {
258 258
   reset_stepper_timeout();
259 259
 
260 260
   #define HAS_CURRENT_HOME(N) (defined(N##_CURRENT_HOME) && N##_CURRENT_HOME != N##_CURRENT)
261
-  #if HAS_CURRENT_HOME(X) || HAS_CURRENT_HOME(X2) || HAS_CURRENT_HOME(Y) || HAS_CURRENT_HOME(Y2) || (ENABLED(DELTA) && HAS_CURRENT_HOME(Z)) || HAS_CURRENT_HOME(I) || HAS_CURRENT_HOME(J) || HAS_CURRENT_HOME(K)
261
+  #if HAS_CURRENT_HOME(X) || HAS_CURRENT_HOME(X2) || HAS_CURRENT_HOME(Y) || HAS_CURRENT_HOME(Y2) || (ENABLED(DELTA) && HAS_CURRENT_HOME(Z)) || HAS_CURRENT_HOME(I) || HAS_CURRENT_HOME(J) || HAS_CURRENT_HOME(K) || HAS_CURRENT_HOME(U) || HAS_CURRENT_HOME(V) || HAS_CURRENT_HOME(W)
262 262
     #define HAS_HOMING_CURRENT 1
263 263
   #endif
264 264
 
@@ -286,21 +286,6 @@ void GcodeSuite::G28() {
286 286
       stepperY2.rms_current(Y2_CURRENT_HOME);
287 287
       if (DEBUGGING(LEVELING)) debug_current(F(STR_Y2), tmc_save_current_Y2, Y2_CURRENT_HOME);
288 288
     #endif
289
-    #if HAS_CURRENT_HOME(I)
290
-      const int16_t tmc_save_current_I = stepperI.getMilliamps();
291
-      stepperI.rms_current(I_CURRENT_HOME);
292
-      if (DEBUGGING(LEVELING)) debug_current(F(STR_I), tmc_save_current_I, I_CURRENT_HOME);
293
-    #endif
294
-    #if HAS_CURRENT_HOME(J)
295
-      const int16_t tmc_save_current_J = stepperJ.getMilliamps();
296
-      stepperJ.rms_current(J_CURRENT_HOME);
297
-      if (DEBUGGING(LEVELING)) debug_current(F(STR_J), tmc_save_current_J, J_CURRENT_HOME);
298
-    #endif
299
-    #if HAS_CURRENT_HOME(K)
300
-      const int16_t tmc_save_current_K = stepperK.getMilliamps();
301
-      stepperK.rms_current(K_CURRENT_HOME);
302
-      if (DEBUGGING(LEVELING)) debug_current(F(STR_K), tmc_save_current_K, K_CURRENT_HOME);
303
-    #endif
304 289
     #if HAS_CURRENT_HOME(Z) && ENABLED(DELTA)
305 290
       const int16_t tmc_save_current_Z = stepperZ.getMilliamps();
306 291
       stepperZ.rms_current(Z_CURRENT_HOME);
@@ -321,6 +306,21 @@ void GcodeSuite::G28() {
321 306
       stepperK.rms_current(K_CURRENT_HOME);
322 307
       if (DEBUGGING(LEVELING)) debug_current(F(STR_K), tmc_save_current_K, K_CURRENT_HOME);
323 308
     #endif
309
+    #if HAS_CURRENT_HOME(U)
310
+      const int16_t tmc_save_current_U = stepperU.getMilliamps();
311
+      stepperU.rms_current(U_CURRENT_HOME);
312
+      if (DEBUGGING(LEVELING)) debug_current(F(STR_U), tmc_save_current_U, U_CURRENT_HOME);
313
+    #endif
314
+    #if HAS_CURRENT_HOME(V)
315
+      const int16_t tmc_save_current_V = stepperV.getMilliamps();
316
+      stepperV.rms_current(V_CURRENT_HOME);
317
+      if (DEBUGGING(LEVELING)) debug_current(F(STR_V), tmc_save_current_V, V_CURRENT_HOME);
318
+    #endif
319
+    #if HAS_CURRENT_HOME(W)
320
+      const int16_t tmc_save_current_W = stepperW.getMilliamps();
321
+      stepperW.rms_current(W_CURRENT_HOME);
322
+      if (DEBUGGING(LEVELING)) debug_current(F(STR_W), tmc_save_current_W, W_CURRENT_HOME);
323
+    #endif
324 324
   #endif
325 325
 
326 326
   #if ENABLED(IMPROVE_HOMING_RELIABILITY)
@@ -364,23 +364,28 @@ void GcodeSuite::G28() {
364 364
     #define _UNSAFE(A) (homeZ && TERN0(Z_SAFE_HOMING, axes_should_home(_BV(A##_AXIS))))
365 365
 
366 366
     const bool homeZ = TERN0(HAS_Z_AXIS, parser.seen_test('Z')),
367
-               LINEAR_AXIS_LIST(              // Other axes should be homed before Z safe-homing
367
+               NUM_AXIS_LIST(              // Other axes should be homed before Z safe-homing
368 368
                  needX = _UNSAFE(X), needY = _UNSAFE(Y), needZ = false, // UNUSED
369
-                 needI = _UNSAFE(I), needJ = _UNSAFE(J), needK = _UNSAFE(K)
369
+                 needI = _UNSAFE(I), needJ = _UNSAFE(J), needK = _UNSAFE(K),
370
+                 needU = _UNSAFE(U), needV = _UNSAFE(V), needW = _UNSAFE(W)
370 371
                ),
371
-               LINEAR_AXIS_LIST(              // Home each axis if needed or flagged
372
+               NUM_AXIS_LIST(              // Home each axis if needed or flagged
372 373
                  homeX = needX || parser.seen_test('X'),
373 374
                  homeY = needY || parser.seen_test('Y'),
374 375
                  homeZZ = homeZ,
375
-                 homeI = needI || parser.seen_test(AXIS4_NAME), homeJ = needJ || parser.seen_test(AXIS5_NAME), homeK = needK || parser.seen_test(AXIS6_NAME)
376
+                 homeI = needI || parser.seen_test(AXIS4_NAME), homeJ = needJ || parser.seen_test(AXIS5_NAME),
377
+                 homeK = needK || parser.seen_test(AXIS6_NAME), homeU = needU || parser.seen_test(AXIS7_NAME),
378
+                 homeV = needV || parser.seen_test(AXIS8_NAME), homeW = needW || parser.seen_test(AXIS9_NAME),
376 379
                ),
377
-               home_all = LINEAR_AXIS_GANG(   // Home-all if all or none are flagged
380
+               home_all = NUM_AXIS_GANG(   // Home-all if all or none are flagged
378 381
                     homeX == homeX, && homeY == homeX, && homeZ == homeX,
379
-                 && homeI == homeX, && homeJ == homeX, && homeK == homeX
382
+                 && homeI == homeX, && homeJ == homeX, && homeK == homeX,
383
+                 && homeU == homeX, && homeV == homeX, && homeW == homeX
380 384
                ),
381
-               LINEAR_AXIS_LIST(
385
+               NUM_AXIS_LIST(
382 386
                  doX = home_all || homeX, doY = home_all || homeY, doZ = home_all || homeZ,
383
-                 doI = home_all || homeI, doJ = home_all || homeJ, doK = home_all || homeK
387
+                 doI = home_all || homeI, doJ = home_all || homeJ, doK = home_all || homeK,
388
+                 doU = home_all || homeU, doV = home_all || homeV, doW = home_all || homeW
384 389
                );
385 390
 
386 391
     #if HAS_Z_AXIS
@@ -394,7 +399,7 @@ void GcodeSuite::G28() {
394 399
     const bool seenR = parser.seenval('R');
395 400
     const float z_homing_height = seenR ? parser.value_linear_units() : Z_HOMING_HEIGHT;
396 401
 
397
-    if (z_homing_height && (seenR || LINEAR_AXIS_GANG(doX, || doY, || TERN0(Z_SAFE_HOMING, doZ), || doI, || doJ, || doK))) {
402
+    if (z_homing_height && (seenR || NUM_AXIS_GANG(doX, || doY, || TERN0(Z_SAFE_HOMING, doZ), || doI, || doJ, || doK, || doU, || doV, || doW))) {
398 403
       // Raise Z before homing any other axes and z is not already high enough (never lower z)
399 404
       if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("Raise Z (before homing) by ", z_homing_height);
400 405
       do_z_clearance(z_homing_height);
@@ -434,33 +439,53 @@ void GcodeSuite::G28() {
434 439
       #endif
435 440
     }
436 441
 
442
+    #if BOTH(FOAMCUTTER_XYUV, HAS_I_AXIS)
443
+      // Home I (after X)
444
+      if (doI) homeaxis(I_AXIS);
445
+    #endif
446
+
437 447
     // Home Y (after X)
438 448
     if (DISABLED(HOME_Y_BEFORE_X) && doY)
439 449
       homeaxis(Y_AXIS);
440 450
 
451
+    #if BOTH(FOAMCUTTER_XYUV, HAS_J_AXIS)
452
+      // Home J (after Y)
453
+      if (doJ) homeaxis(J_AXIS);
454
+    #endif
455
+
441 456
     TERN_(IMPROVE_HOMING_RELIABILITY, end_slow_homing(saved_motion_state));
442 457
 
443
-    // Home Z last if homing towards the bed
444
-    #if HAS_Z_AXIS && DISABLED(HOME_Z_FIRST)
445
-      if (doZ) {
446
-        #if EITHER(Z_MULTI_ENDSTOPS, Z_STEPPER_AUTO_ALIGN)
447
-          stepper.set_all_z_lock(false);
448
-          stepper.set_separate_multi_axis(false);
449
-        #endif
458
+    #if ENABLED(FOAMCUTTER_XYUV)
459
+      // skip homing of unused Z axis for foamcutters
460
+      if (doZ) set_axis_is_at_home(Z_AXIS);
461
+    #else
462
+      // Home Z last if homing towards the bed
463
+      #if HAS_Z_AXIS && DISABLED(HOME_Z_FIRST)
464
+        if (doZ) {
465
+          #if EITHER(Z_MULTI_ENDSTOPS, Z_STEPPER_AUTO_ALIGN)
466
+            stepper.set_all_z_lock(false);
467
+            stepper.set_separate_multi_axis(false);
468
+          #endif
469
+
470
+          #if ENABLED(Z_SAFE_HOMING)
471
+            if (TERN1(POWER_LOSS_RECOVERY, !parser.seen_test('H'))) home_z_safely(); else homeaxis(Z_AXIS);
472
+          #else
473
+            homeaxis(Z_AXIS);
474
+          #endif
475
+          probe.move_z_after_homing();
476
+        }
477
+      #endif
450 478
 
451
-        #if ENABLED(Z_SAFE_HOMING)
452
-          if (TERN1(POWER_LOSS_RECOVERY, !parser.seen_test('H'))) home_z_safely(); else homeaxis(Z_AXIS);
453
-        #else
454
-          homeaxis(Z_AXIS);
455
-        #endif
456
-        probe.move_z_after_homing();
457
-      }
479
+      SECONDARY_AXIS_CODE(
480
+        if (doI) homeaxis(I_AXIS),
481
+        if (doJ) homeaxis(J_AXIS),
482
+        if (doK) homeaxis(K_AXIS),
483
+        if (doU) homeaxis(U_AXIS),
484
+        if (doV) homeaxis(V_AXIS),
485
+        if (doW) homeaxis(W_AXIS)
486
+      );
458 487
     #endif
459 488
 
460
-    TERN_(HAS_I_AXIS, if (doI) homeaxis(I_AXIS));
461
-    TERN_(HAS_J_AXIS, if (doJ) homeaxis(J_AXIS));
462
-    TERN_(HAS_K_AXIS, if (doK) homeaxis(K_AXIS));
463
-
464 489
     sync_plan_position();
465 490
 
466 491
   #endif
@@ -542,6 +567,15 @@ void GcodeSuite::G28() {
542 567
     #if HAS_CURRENT_HOME(K)
543 568
       stepperK.rms_current(tmc_save_current_K);
544 569
     #endif
570
+    #if HAS_CURRENT_HOME(U)
571
+      stepperU.rms_current(tmc_save_current_U);
572
+    #endif
573
+    #if HAS_CURRENT_HOME(V)
574
+      stepperV.rms_current(tmc_save_current_V);
575
+    #endif
576
+    #if HAS_CURRENT_HOME(W)
577
+      stepperW.rms_current(tmc_save_current_W);
578
+    #endif
545 579
   #endif // HAS_HOMING_CURRENT
546 580
 
547 581
   ui.refresh();
@@ -562,7 +596,7 @@ void GcodeSuite::G28() {
562 596
     // If not, this will need a PROGMEM directive and an accessor.
563 597
     #define _EN_ITEM(N) , E_AXIS
564 598
     static constexpr AxisEnum L64XX_axis_xref[MAX_L64XX] = {
565
-      LINEAR_AXIS_LIST(X_AXIS, Y_AXIS, Z_AXIS, I_AXIS, J_AXIS, K_AXIS),
599
+      NUM_AXIS_LIST(X_AXIS, Y_AXIS, Z_AXIS, I_AXIS, J_AXIS, K_AXIS, U_AXIS, V_AXIS, W_AXIS),
566 600
       X_AXIS, Y_AXIS, Z_AXIS, Z_AXIS, Z_AXIS
567 601
       REPEAT(E_STEPPERS, _EN_ITEM)
568 602
     };

+ 5
- 5
Marlin/src/gcode/calibrate/G33.cpp View File

@@ -343,7 +343,7 @@ static float auto_tune_a(const float dcr) {
343 343
   abc_float_t delta_e = { 0.0f }, delta_t = { 0.0f };
344 344
 
345 345
   delta_t.reset();
346
-  LOOP_LINEAR_AXES(axis) {
346
+  LOOP_NUM_AXES(axis) {
347 347
     delta_t[axis] = diff;
348 348
     calc_kinematics_diff_probe_points(z_pt, dcr, delta_e, delta_r, delta_t);
349 349
     delta_t[axis] = 0;
@@ -536,7 +536,7 @@ void GcodeSuite::G33() {
536 536
 
537 537
         case 1:
538 538
           test_precision = 0.0f; // forced end
539
-          LOOP_LINEAR_AXES(axis) e_delta[axis] = +Z4(CEN);
539
+          LOOP_NUM_AXES(axis) e_delta[axis] = +Z4(CEN);
540 540
           break;
541 541
 
542 542
         case 2:
@@ -584,14 +584,14 @@ void GcodeSuite::G33() {
584 584
       // Normalize angles to least-squares
585 585
       if (_angle_results) {
586 586
         float a_sum = 0.0f;
587
-        LOOP_LINEAR_AXES(axis) a_sum += delta_tower_angle_trim[axis];
588
-        LOOP_LINEAR_AXES(axis) delta_tower_angle_trim[axis] -= a_sum / 3.0f;
587
+        LOOP_NUM_AXES(axis) a_sum += delta_tower_angle_trim[axis];
588
+        LOOP_NUM_AXES(axis) delta_tower_angle_trim[axis] -= a_sum / 3.0f;
589 589
       }
590 590
 
591 591
       // adjust delta_height and endstops by the max amount
592 592
       const float z_temp = _MAX(delta_endstop_adj.a, delta_endstop_adj.b, delta_endstop_adj.c);
593 593
       delta_height -= z_temp;
594
-      LOOP_LINEAR_AXES(axis) delta_endstop_adj[axis] -= z_temp;
594
+      LOOP_NUM_AXES(axis) delta_endstop_adj[axis] -= z_temp;
595 595
     }
596 596
     recalc_delta_settings();
597 597
     NOMORE(zero_std_dev_min, zero_std_dev);

+ 130
- 6
Marlin/src/gcode/calibrate/G425.cpp View File

@@ -85,10 +85,19 @@
85 85
 #if ALL(HAS_K_AXIS, CALIBRATION_MEASURE_KMIN, CALIBRATION_MEASURE_KMAX)
86 86
   #define HAS_K_CENTER 1
87 87
 #endif
88
+#if ALL(HAS_U_AXIS, CALIBRATION_MEASURE_UMIN, CALIBRATION_MEASURE_UMAX)
89
+  #define HAS_U_CENTER 1
90
+#endif
91
+#if ALL(HAS_V_AXIS, CALIBRATION_MEASURE_VMIN, CALIBRATION_MEASURE_VMAX)
92
+  #define HAS_V_CENTER 1
93
+#endif
94
+#if ALL(HAS_W_AXIS, CALIBRATION_MEASURE_WMIN, CALIBRATION_MEASURE_WMAX)
95
+  #define HAS_W_CENTER 1
96
+#endif
88 97
 
89 98
 enum side_t : uint8_t {
90 99
   TOP, RIGHT, FRONT, LEFT, BACK, NUM_SIDES,
91
-  LIST_N(DOUBLE(SUB3(LINEAR_AXES)), IMINIMUM, IMAXIMUM, JMINIMUM, JMAXIMUM, KMINIMUM, KMAXIMUM)
100
+  LIST_N(DOUBLE(SECONDARY_AXES), IMINIMUM, IMAXIMUM, JMINIMUM, JMAXIMUM, KMINIMUM, KMAXIMUM, UMINIMUM, UMAXIMUM, VMINIMUM, VMAXIMUM, WMINIMUM, WMAXIMUM)
92 101
 };
93 102
 
94 103
 static constexpr xyz_pos_t true_center CALIBRATION_OBJECT_CENTER;
@@ -282,6 +291,15 @@ inline void probe_side(measurements_t &m, const float uncertainty, const side_t
282 291
     #if HAS_K_AXIS && AXIS_CAN_CALIBRATE(K)
283 292
       _PCASE(K);
284 293
     #endif
294
+    #if HAS_U_AXIS && AXIS_CAN_CALIBRATE(U)
295
+      _PCASE(U);
296
+    #endif
297
+    #if HAS_V_AXIS && AXIS_CAN_CALIBRATE(V)
298
+      _PCASE(V);
299
+    #endif
300
+    #if HAS_W_AXIS && AXIS_CAN_CALIBRATE(W)
301
+      _PCASE(W);
302
+    #endif
285 303
     default: return;
286 304
   }
287 305
 
@@ -335,6 +353,12 @@ inline void probe_sides(measurements_t &m, const float uncertainty) {
335 353
   TERN_(CALIBRATION_MEASURE_JMAX,  probe_side(m, uncertainty, JMAXIMUM, probe_top_at_edge));
336 354
   TERN_(CALIBRATION_MEASURE_KMIN,  probe_side(m, uncertainty, KMINIMUM, probe_top_at_edge));
337 355
   TERN_(CALIBRATION_MEASURE_KMAX,  probe_side(m, uncertainty, KMAXIMUM, probe_top_at_edge));
356
+  TERN_(CALIBRATION_MEASURE_UMIN,  probe_side(m, uncertainty, UMINIMUM, probe_top_at_edge));
357
+  TERN_(CALIBRATION_MEASURE_UMAX,  probe_side(m, uncertainty, UMAXIMUM, probe_top_at_edge));
358
+  TERN_(CALIBRATION_MEASURE_VMIN,  probe_side(m, uncertainty, VMINIMUM, probe_top_at_edge));
359
+  TERN_(CALIBRATION_MEASURE_VMAX,  probe_side(m, uncertainty, VMAXIMUM, probe_top_at_edge));
360
+  TERN_(CALIBRATION_MEASURE_WMIN,  probe_side(m, uncertainty, WMINIMUM, probe_top_at_edge));
361
+  TERN_(CALIBRATION_MEASURE_WMAX,  probe_side(m, uncertainty, WMAXIMUM, probe_top_at_edge));
338 362
 
339 363
   // Compute the measured center of the calibration object.
340 364
   TERN_(HAS_X_CENTER, m.obj_center.x = (m.obj_side[LEFT]     + m.obj_side[RIGHT])    / 2);
@@ -342,6 +366,9 @@ inline void probe_sides(measurements_t &m, const float uncertainty) {
342 366
   TERN_(HAS_I_CENTER, m.obj_center.i = (m.obj_side[IMINIMUM] + m.obj_side[IMAXIMUM]) / 2);
343 367
   TERN_(HAS_J_CENTER, m.obj_center.j = (m.obj_side[JMINIMUM] + m.obj_side[JMAXIMUM]) / 2);
344 368
   TERN_(HAS_K_CENTER, m.obj_center.k = (m.obj_side[KMINIMUM] + m.obj_side[KMAXIMUM]) / 2);
369
+  TERN_(HAS_U_CENTER, m.obj_center.u = (m.obj_side[UMINIMUM] + m.obj_side[UMAXIMUM]) / 2);
370
+  TERN_(HAS_V_CENTER, m.obj_center.v = (m.obj_side[VMINIMUM] + m.obj_side[VMAXIMUM]) / 2);
371
+  TERN_(HAS_W_CENTER, m.obj_center.w = (m.obj_side[WMINIMUM] + m.obj_side[WMAXIMUM]) / 2);
345 372
 
346 373
   // Compute the outside diameter of the nozzle at the height
347 374
   // at which it makes contact with the calibration object
@@ -352,13 +379,16 @@ inline void probe_sides(measurements_t &m, const float uncertainty) {
352 379
 
353 380
   // The difference between the known and the measured location
354 381
   // of the calibration object is the positional error
355
-  LINEAR_AXIS_CODE(
382
+  NUM_AXIS_CODE(
356 383
     m.pos_error.x = TERN0(HAS_X_CENTER, true_center.x - m.obj_center.x),
357 384
     m.pos_error.y = TERN0(HAS_Y_CENTER, true_center.y - m.obj_center.y),
358 385
     m.pos_error.z = true_center.z - m.obj_center.z,
359 386
     m.pos_error.i = TERN0(HAS_I_CENTER, true_center.i - m.obj_center.i),
360 387
     m.pos_error.j = TERN0(HAS_J_CENTER, true_center.j - m.obj_center.j),
361
-    m.pos_error.k = TERN0(HAS_K_CENTER, true_center.k - m.obj_center.k)
388
+    m.pos_error.k = TERN0(HAS_K_CENTER, true_center.k - m.obj_center.k),
389
+    m.pos_error.u = TERN0(HAS_U_CENTER, true_center.u - m.obj_center.u),
390
+    m.pos_error.v = TERN0(HAS_V_CENTER, true_center.v - m.obj_center.v),
391
+    m.pos_error.w = TERN0(HAS_W_CENTER, true_center.w - m.obj_center.w)
362 392
   );
363 393
 }
364 394
 
@@ -406,6 +436,30 @@ inline void probe_sides(measurements_t &m, const float uncertainty) {
406 436
         SERIAL_ECHOLNPGM("  " STR_K_MAX ": ", m.obj_side[KMAXIMUM]);
407 437
       #endif
408 438
     #endif
439
+    #if HAS_U_AXIS
440
+      #if ENABLED(CALIBRATION_MEASURE_UMIN)
441
+        SERIAL_ECHOLNPAIR("  " STR_U_MIN ": ", m.obj_side[UMINIMUM]);
442
+      #endif
443
+      #if ENABLED(CALIBRATION_MEASURE_UMAX)
444
+        SERIAL_ECHOLNPAIR("  " STR_U_MAX ": ", m.obj_side[UMAXIMUM]);
445
+      #endif
446
+    #endif
447
+    #if HAS_V_AXIS
448
+      #if ENABLED(CALIBRATION_MEASURE_VMIN)
449
+        SERIAL_ECHOLNPAIR("  " STR_V_MIN ": ", m.obj_side[VMINIMUM]);
450
+      #endif
451
+      #if ENABLED(CALIBRATION_MEASURE_VMAX)
452
+        SERIAL_ECHOLNPAIR("  " STR_V_MAX ": ", m.obj_side[VMAXIMUM]);
453
+      #endif
454
+    #endif
455
+    #if HAS_W_AXIS
456
+      #if ENABLED(CALIBRATION_MEASURE_WMIN)
457
+        SERIAL_ECHOLNPAIR("  " STR_W_MIN ": ", m.obj_side[WMINIMUM]);
458
+      #endif
459
+      #if ENABLED(CALIBRATION_MEASURE_WMAX)
460
+        SERIAL_ECHOLNPAIR("  " STR_W_MAX ": ", m.obj_side[WMAXIMUM]);
461
+      #endif
462
+    #endif
409 463
     SERIAL_EOL();
410 464
   }
411 465
 
@@ -427,6 +481,15 @@ inline void probe_sides(measurements_t &m, const float uncertainty) {
427 481
     #if HAS_K_CENTER
428 482
       SERIAL_ECHOLNPGM_P(SP_K_STR, m.obj_center.k);
429 483
     #endif
484
+    #if HAS_U_CENTER
485
+      SERIAL_ECHOLNPGM_P(SP_U_STR, m.obj_center.u);
486
+    #endif
487
+    #if HAS_V_CENTER
488
+      SERIAL_ECHOLNPGM_P(SP_V_STR, m.obj_center.v);
489
+    #endif
490
+    #if HAS_W_CENTER
491
+      SERIAL_ECHOLNPGM_P(SP_W_STR, m.obj_center.w);
492
+    #endif
430 493
     SERIAL_EOL();
431 494
   }
432 495
 
@@ -475,6 +538,30 @@ inline void probe_sides(measurements_t &m, const float uncertainty) {
475 538
         SERIAL_ECHOLNPGM("  " STR_K_MAX ": ", m.backlash[KMAXIMUM]);
476 539
       #endif
477 540
     #endif
541
+    #if HAS_U_AXIS && AXIS_CAN_CALIBRATE(U)
542
+      #if ENABLED(CALIBRATION_MEASURE_UMIN)
543
+        SERIAL_ECHOLNPGM("  " STR_U_MIN ": ", m.backlash[UMINIMUM]);
544
+      #endif
545
+      #if ENABLED(CALIBRATION_MEASURE_UMAX)
546
+        SERIAL_ECHOLNPGM("  " STR_U_MAX ": ", m.backlash[UMAXIMUM]);
547
+      #endif
548
+    #endif
549
+    #if HAS_V_AXIS && AXIS_CAN_CALIBRATE(V)
550
+      #if ENABLED(CALIBRATION_MEASURE_VMIN)
551
+        SERIAL_ECHOLNPGM("  " STR_V_MIN ": ", m.backlash[VMINIMUM]);
552
+      #endif
553
+      #if ENABLED(CALIBRATION_MEASURE_VMAX)
554
+        SERIAL_ECHOLNPGM("  " STR_V_MAX ": ", m.backlash[VMAXIMUM]);
555
+      #endif
556
+    #endif
557
+    #if HAS_W_AXIS && AXIS_CAN_CALIBRATE(W)
558
+      #if ENABLED(CALIBRATION_MEASURE_WMIN)
559
+        SERIAL_ECHOLNPGM("  " STR_W_MIN ": ", m.backlash[WMINIMUM]);
560
+      #endif
561
+      #if ENABLED(CALIBRATION_MEASURE_WMAX)
562
+        SERIAL_ECHOLNPGM("  " STR_W_MAX ": ", m.backlash[WMAXIMUM]);
563
+      #endif
564
+    #endif
478 565
     SERIAL_EOL();
479 566
   }
480 567
 
@@ -498,7 +585,16 @@ inline void probe_sides(measurements_t &m, const float uncertainty) {
498 585
       SERIAL_ECHOLNPGM_P(SP_J_STR, m.pos_error.j);
499 586
     #endif
500 587
     #if HAS_K_CENTER && AXIS_CAN_CALIBRATE(K)
501
-      SERIAL_ECHOLNPGM_P(SP_Z_STR, m.pos_error.z);
588
+      SERIAL_ECHOLNPGM_P(SP_K_STR, m.pos_error.k);
589
+    #endif
590
+    #if HAS_U_CENTER && AXIS_CAN_CALIBRATE(U)
591
+      SERIAL_ECHOLNPGM_P(SP_U_STR, m.pos_error.u);
592
+    #endif
593
+    #if HAS_V_CENTER && AXIS_CAN_CALIBRATE(V)
594
+      SERIAL_ECHOLNPGM_P(SP_V_STR, m.pos_error.v);
595
+    #endif
596
+    #if HAS_W_CENTER && AXIS_CAN_CALIBRATE(W)
597
+      SERIAL_ECHOLNPGM_P(SP_W_STR, m.pos_error.w);
502 598
     #endif
503 599
     SERIAL_EOL();
504 600
   }
@@ -587,6 +683,30 @@ inline void calibrate_backlash(measurements_t &m, const float uncertainty) {
587 683
         backlash.set_distance_mm(K_AXIS, m.backlash[KMAXIMUM]);
588 684
       #endif
589 685
 
686
+      #if HAS_U_CENTER
687
+        backlash.distance_mm.u = (m.backlash[UMINIMUM] + m.backlash[UMAXIMUM]) / 2;
688
+      #elif ENABLED(CALIBRATION_MEASURE_UMIN)
689
+        backlash.distance_mm.u = m.backlash[UMINIMUM];
690
+      #elif ENABLED(CALIBRATION_MEASURE_UMAX)
691
+        backlash.distance_mm.u = m.backlash[UMAXIMUM];
692
+      #endif
693
+
694
+      #if HAS_V_CENTER
695
+        backlash.distance_mm.v = (m.backlash[VMINIMUM] + m.backlash[VMAXIMUM]) / 2;
696
+      #elif ENABLED(CALIBRATION_MEASURE_VMIN)
697
+        backlash.distance_mm.v = m.backlash[VMINIMUM];
698
+      #elif ENABLED(CALIBRATION_MEASURE_UMAX)
699
+        backlash.distance_mm.v = m.backlash[VMAXIMUM];
700
+      #endif
701
+
702
+      #if HAS_W_CENTER
703
+        backlash.distance_mm.w = (m.backlash[WMINIMUM] + m.backlash[WMAXIMUM]) / 2;
704
+      #elif ENABLED(CALIBRATION_MEASURE_WMIN)
705
+        backlash.distance_mm.w = m.backlash[WMINIMUM];
706
+      #elif ENABLED(CALIBRATION_MEASURE_WMAX)
707
+        backlash.distance_mm.w = m.backlash[WMAXIMUM];
708
+      #endif
709
+
590 710
     #endif // BACKLASH_GCODE
591 711
   }
592 712
 
@@ -597,9 +717,10 @@ inline void calibrate_backlash(measurements_t &m, const float uncertainty) {
597 717
       // New scope for TEMPORARY_BACKLASH_CORRECTION
598 718
       TEMPORARY_BACKLASH_CORRECTION(backlash.all_on);
599 719
       TEMPORARY_BACKLASH_SMOOTHING(0.0f);
600
-      const xyz_float_t move = LINEAR_AXIS_ARRAY(
720
+      const xyz_float_t move = NUM_AXIS_ARRAY(
601 721
         AXIS_CAN_CALIBRATE(X) * 3, AXIS_CAN_CALIBRATE(Y) * 3, AXIS_CAN_CALIBRATE(Z) * 3,
602
-        AXIS_CAN_CALIBRATE(I) * 3, AXIS_CAN_CALIBRATE(J) * 3, AXIS_CAN_CALIBRATE(K) * 3
722
+        AXIS_CAN_CALIBRATE(I) * 3, AXIS_CAN_CALIBRATE(J) * 3, AXIS_CAN_CALIBRATE(K) * 3,
723
+        AXIS_CAN_CALIBRATE(U) * 3, AXIS_CAN_CALIBRATE(V) * 3, AXIS_CAN_CALIBRATE(W) * 3
603 724
       );
604 725
       current_position += move; calibration_move();
605 726
       current_position -= move; calibration_move();
@@ -650,6 +771,9 @@ inline void calibrate_toolhead(measurements_t &m, const float uncertainty, const
650 771
   TERN_(HAS_I_CENTER, update_measurements(m, I_AXIS));
651 772
   TERN_(HAS_J_CENTER, update_measurements(m, J_AXIS));
652 773
   TERN_(HAS_K_CENTER, update_measurements(m, K_AXIS));
774
+  TERN_(HAS_U_CENTER, update_measurements(m, U_AXIS));
775
+  TERN_(HAS_V_CENTER, update_measurements(m, V_AXIS));
776
+  TERN_(HAS_W_CENTER, update_measurements(m, W_AXIS));
653 777
 
654 778
   sync_plan_position();
655 779
 }

+ 16
- 10
Marlin/src/gcode/calibrate/M425.cpp View File

@@ -49,21 +49,24 @@ void GcodeSuite::M425() {
49 49
   auto axis_can_calibrate = [](const uint8_t a) {
50 50
     switch (a) {
51 51
       default: return false;
52
-      LINEAR_AXIS_CODE(
52
+      NUM_AXIS_CODE(
53 53
         case X_AXIS: return AXIS_CAN_CALIBRATE(X),
54 54
         case Y_AXIS: return AXIS_CAN_CALIBRATE(Y),
55 55
         case Z_AXIS: return AXIS_CAN_CALIBRATE(Z),
56 56
         case I_AXIS: return AXIS_CAN_CALIBRATE(I),
57 57
         case J_AXIS: return AXIS_CAN_CALIBRATE(J),
58
-        case K_AXIS: return AXIS_CAN_CALIBRATE(K)
58
+        case K_AXIS: return AXIS_CAN_CALIBRATE(K),
59
+        case U_AXIS: return AXIS_CAN_CALIBRATE(U),
60
+        case V_AXIS: return AXIS_CAN_CALIBRATE(V),
61
+        case W_AXIS: return AXIS_CAN_CALIBRATE(W)
59 62
       );
60 63
     }
61 64
   };
62 65
 
63
-  LOOP_LINEAR_AXES(a) {
66
+  LOOP_NUM_AXES(a) {
64 67
     if (axis_can_calibrate(a) && parser.seen(AXIS_CHAR(a))) {
65 68
       planner.synchronize();
66
-      backlash.set_distance_mm(AxisEnum(a), parser.has_value() ? parser.value_linear_units() : backlash.get_measurement(AxisEnum(a)));
69
+      backlash.set_distance_mm(AxisEnum(a), parser.has_value() ? parser.value_axis_units(AxisEnum(a)) : backlash.get_measurement(AxisEnum(a)));
67 70
       noArgs = false;
68 71
     }
69 72
   }
@@ -88,7 +91,7 @@ void GcodeSuite::M425() {
88 91
     SERIAL_ECHOLNPGM("active:");
89 92
     SERIAL_ECHOLNPGM("  Correction Amount/Fade-out:     F", backlash.get_correction(), " (F1.0 = full, F0.0 = none)");
90 93
     SERIAL_ECHOPGM("  Backlash Distance (mm):        ");
91
-    LOOP_LINEAR_AXES(a) if (axis_can_calibrate(a)) {
94
+    LOOP_NUM_AXES(a) if (axis_can_calibrate(a)) {
92 95
       SERIAL_CHAR(' ', AXIS_CHAR(a));
93 96
       SERIAL_ECHO(backlash.get_distance_mm(AxisEnum(a)));
94 97
       SERIAL_EOL();
@@ -101,7 +104,7 @@ void GcodeSuite::M425() {
101 104
     #if ENABLED(MEASURE_BACKLASH_WHEN_PROBING)
102 105
       SERIAL_ECHOPGM("  Average measured backlash (mm):");
103 106
       if (backlash.has_any_measurement()) {
104
-        LOOP_LINEAR_AXES(a) if (axis_can_calibrate(a) && backlash.has_measurement(AxisEnum(a))) {
107
+        LOOP_NUM_AXES(a) if (axis_can_calibrate(a) && backlash.has_measurement(AxisEnum(a))) {
105 108
           SERIAL_CHAR(' ', AXIS_CHAR(a));
106 109
           SERIAL_ECHO(backlash.get_measurement(AxisEnum(a)));
107 110
         }
@@ -120,13 +123,16 @@ void GcodeSuite::M425_report(const bool forReplay/*=true*/) {
120 123
     #ifdef BACKLASH_SMOOTHING_MM
121 124
       , PSTR(" S"), LINEAR_UNIT(backlash.get_smoothing_mm())
122 125
     #endif
123
-    , LIST_N(DOUBLE(LINEAR_AXES),
126
+    , LIST_N(DOUBLE(NUM_AXES),
124 127
         SP_X_STR, LINEAR_UNIT(backlash.get_distance_mm(X_AXIS)),
125 128
         SP_Y_STR, LINEAR_UNIT(backlash.get_distance_mm(Y_AXIS)),
126 129
         SP_Z_STR, LINEAR_UNIT(backlash.get_distance_mm(Z_AXIS)),
127
-        SP_I_STR, LINEAR_UNIT(backlash.get_distance_mm(I_AXIS)),
128
-        SP_J_STR, LINEAR_UNIT(backlash.get_distance_mm(J_AXIS)),
129
-        SP_K_STR, LINEAR_UNIT(backlash.get_distance_mm(K_AXIS))
130
+        SP_I_STR, I_AXIS_UNIT(backlash.get_distance_mm(I_AXIS)),
131
+        SP_J_STR, J_AXIS_UNIT(backlash.get_distance_mm(J_AXIS)),
132
+        SP_K_STR, K_AXIS_UNIT(backlash.get_distance_mm(K_AXIS)),
133
+        SP_U_STR, U_AXIS_UNIT(backlash.get_distance_mm(U_AXIS)),
134
+        SP_V_STR, V_AXIS_UNIT(backlash.get_distance_mm(V_AXIS)),
135
+        SP_W_STR, W_AXIS_UNIT(backlash.get_distance_mm(W_AXIS))
130 136
       )
131 137
   );
132 138
 }

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

@@ -44,7 +44,7 @@
44 44
   void GcodeSuite::M666() {
45 45
     DEBUG_SECTION(log_M666, "M666", DEBUGGING(LEVELING));
46 46
     bool is_err = false, is_set = false;
47
-    LOOP_LINEAR_AXES(i) {
47
+    LOOP_NUM_AXES(i) {
48 48
       if (parser.seen(AXIS_CHAR(i))) {
49 49
         is_set = true;
50 50
         const float v = parser.value_linear_units();

+ 28
- 15
Marlin/src/gcode/config/M200-M205.cpp View File

@@ -135,13 +135,16 @@ void GcodeSuite::M201() {
135 135
 void GcodeSuite::M201_report(const bool forReplay/*=true*/) {
136 136
   report_heading_etc(forReplay, F(STR_MAX_ACCELERATION));
137 137
   SERIAL_ECHOLNPGM_P(
138
-    LIST_N(DOUBLE(LINEAR_AXES),
138
+    LIST_N(DOUBLE(NUM_AXES),
139 139
       PSTR("  M201 X"), LINEAR_UNIT(planner.settings.max_acceleration_mm_per_s2[X_AXIS]),
140 140
       SP_Y_STR, LINEAR_UNIT(planner.settings.max_acceleration_mm_per_s2[Y_AXIS]),
141 141
       SP_Z_STR, LINEAR_UNIT(planner.settings.max_acceleration_mm_per_s2[Z_AXIS]),
142
-      SP_I_STR, LINEAR_UNIT(planner.settings.max_acceleration_mm_per_s2[I_AXIS]),
143
-      SP_J_STR, LINEAR_UNIT(planner.settings.max_acceleration_mm_per_s2[J_AXIS]),
144
-      SP_K_STR, LINEAR_UNIT(planner.settings.max_acceleration_mm_per_s2[K_AXIS])
142
+      SP_I_STR, I_AXIS_UNIT(planner.settings.max_acceleration_mm_per_s2[I_AXIS]),
143
+      SP_J_STR, J_AXIS_UNIT(planner.settings.max_acceleration_mm_per_s2[J_AXIS]),
144
+      SP_K_STR, K_AXIS_UNIT(planner.settings.max_acceleration_mm_per_s2[K_AXIS]),
145
+      SP_U_STR, U_AXIS_UNIT(planner.settings.max_acceleration_mm_per_s2[U_AXIS]),
146
+      SP_V_STR, V_AXIS_UNIT(planner.settings.max_acceleration_mm_per_s2[V_AXIS]),
147
+      SP_W_STR, W_AXIS_UNIT(planner.settings.max_acceleration_mm_per_s2[W_AXIS]),
145 148
     )
146 149
     #if HAS_EXTRUDERS && DISABLED(DISTINCT_E_FACTORS)
147 150
       , SP_E_STR, VOLUMETRIC_UNIT(planner.settings.max_acceleration_mm_per_s2[E_AXIS])
@@ -180,13 +183,16 @@ void GcodeSuite::M203() {
180 183
 void GcodeSuite::M203_report(const bool forReplay/*=true*/) {
181 184
   report_heading_etc(forReplay, F(STR_MAX_FEEDRATES));
182 185
   SERIAL_ECHOLNPGM_P(
183
-    LIST_N(DOUBLE(LINEAR_AXES),
186
+    LIST_N(DOUBLE(NUM_AXES),
184 187
       PSTR("  M203 X"), LINEAR_UNIT(planner.settings.max_feedrate_mm_s[X_AXIS]),
185 188
       SP_Y_STR, LINEAR_UNIT(planner.settings.max_feedrate_mm_s[Y_AXIS]),
186 189
       SP_Z_STR, LINEAR_UNIT(planner.settings.max_feedrate_mm_s[Z_AXIS]),
187 190
       SP_I_STR, LINEAR_UNIT(planner.settings.max_feedrate_mm_s[I_AXIS]),
188 191
       SP_J_STR, LINEAR_UNIT(planner.settings.max_feedrate_mm_s[J_AXIS]),
189
-      SP_K_STR, LINEAR_UNIT(planner.settings.max_feedrate_mm_s[K_AXIS])
192
+      SP_K_STR, LINEAR_UNIT(planner.settings.max_feedrate_mm_s[K_AXIS]),
193
+      SP_U_STR, LINEAR_UNIT(planner.settings.max_feedrate_mm_s[U_AXIS]),
194
+      SP_V_STR, LINEAR_UNIT(planner.settings.max_feedrate_mm_s[V_AXIS]),
195
+      SP_W_STR, LINEAR_UNIT(planner.settings.max_feedrate_mm_s[W_AXIS])
190 196
     )
191 197
     #if HAS_EXTRUDERS && DISABLED(DISTINCT_E_FACTORS)
192 198
       , SP_E_STR, VOLUMETRIC_UNIT(planner.settings.max_feedrate_mm_s[E_AXIS])
@@ -273,9 +279,12 @@ void GcodeSuite::M205() {
273 279
       if (parser.seenval('X')) planner.set_max_jerk(X_AXIS, parser.value_linear_units()),
274 280
       if (parser.seenval('Y')) planner.set_max_jerk(Y_AXIS, parser.value_linear_units()),
275 281
       if ((seenZ = parser.seenval('Z'))) planner.set_max_jerk(Z_AXIS, parser.value_linear_units()),
276
-      if (parser.seenval(AXIS4_NAME)) planner.set_max_jerk(I_AXIS, parser.value_linear_units()),
277
-      if (parser.seenval(AXIS5_NAME)) planner.set_max_jerk(J_AXIS, parser.value_linear_units()),
278
-      if (parser.seenval(AXIS6_NAME)) planner.set_max_jerk(K_AXIS, parser.value_linear_units())
282
+      if (parser.seenval(AXIS4_NAME)) planner.set_max_jerk(I_AXIS, parser.TERN(AXIS4_ROTATES, value_float, value_linear_units)()),
283
+      if (parser.seenval(AXIS5_NAME)) planner.set_max_jerk(J_AXIS, parser.TERN(AXIS5_ROTATES, value_float, value_linear_units)()),
284
+      if (parser.seenval(AXIS6_NAME)) planner.set_max_jerk(K_AXIS, parser.TERN(AXIS6_ROTATES, value_float, value_linear_units)()),
285
+      if (parser.seenval(AXIS7_NAME)) planner.set_max_jerk(U_AXIS, parser.TERN(AXIS7_ROTATES, value_float, value_linear_units)()),
286
+      if (parser.seenval(AXIS8_NAME)) planner.set_max_jerk(V_AXIS, parser.TERN(AXIS8_ROTATES, value_float, value_linear_units)()),
287
+      if (parser.seenval(AXIS9_NAME)) planner.set_max_jerk(W_AXIS, parser.TERN(AXIS9_ROTATES, value_float, value_linear_units)())
279 288
     );
280 289
     #if HAS_MESH && DISABLED(LIMITED_JERK_EDITING)
281 290
       if (seenZ && planner.max_jerk.z <= 0.1f)
@@ -289,9 +298,10 @@ void GcodeSuite::M205_report(const bool forReplay/*=true*/) {
289 298
     "Advanced (B<min_segment_time_us> S<min_feedrate> T<min_travel_feedrate>"
290 299
     TERN_(HAS_JUNCTION_DEVIATION, " J<junc_dev>")
291 300
     #if HAS_CLASSIC_JERK
292
-      LINEAR_AXIS_GANG(
301
+      NUM_AXIS_GANG(
293 302
         " X<max_jerk>", " Y<max_jerk>", " Z<max_jerk>",
294
-        " " STR_I "<max_jerk>", " " STR_J "<max_jerk>", " " STR_K "<max_jerk>"
303
+        " " STR_I "<max_jerk>", " " STR_J "<max_jerk>", " " STR_K "<max_jerk>",
304
+        " " STR_U "<max_jerk>", " " STR_V "<max_jerk>", " " STR_W "<max_jerk>"
295 305
       )
296 306
     #endif
297 307
     TERN_(HAS_CLASSIC_E_JERK, " E<max_jerk>")
@@ -305,13 +315,16 @@ void GcodeSuite::M205_report(const bool forReplay/*=true*/) {
305 315
       , PSTR(" J"), LINEAR_UNIT(planner.junction_deviation_mm)
306 316
     #endif
307 317
     #if HAS_CLASSIC_JERK
308
-      , LIST_N(DOUBLE(LINEAR_AXES),
318
+      , LIST_N(DOUBLE(NUM_AXES),
309 319
         SP_X_STR, LINEAR_UNIT(planner.max_jerk.x),
310 320
         SP_Y_STR, LINEAR_UNIT(planner.max_jerk.y),
311 321
         SP_Z_STR, LINEAR_UNIT(planner.max_jerk.z),
312
-        SP_I_STR, LINEAR_UNIT(planner.max_jerk.i),
313
-        SP_J_STR, LINEAR_UNIT(planner.max_jerk.j),
314
-        SP_K_STR, LINEAR_UNIT(planner.max_jerk.k)
322
+        SP_I_STR, I_AXIS_UNIT(planner.max_jerk.i),
323
+        SP_J_STR, J_AXIS_UNIT(planner.max_jerk.j),
324
+        SP_K_STR, K_AXIS_UNIT(planner.max_jerk.k),
325
+        SP_U_STR, U_AXIS_UNIT(planner.max_jerk.u),
326
+        SP_V_STR, V_AXIS_UNIT(planner.max_jerk.v),
327
+        SP_W_STR, W_AXIS_UNIT(planner.max_jerk.w)
315 328
       )
316 329
       #if HAS_CLASSIC_E_JERK
317 330
         , SP_E_STR, LINEAR_UNIT(planner.max_jerk.e)

+ 27
- 16
Marlin/src/gcode/config/M217.cpp View File

@@ -50,9 +50,12 @@
50 50
  *  W[linear]   0/1 Enable park & Z Raise
51 51
  *  X[linear]   Park X (Requires TOOLCHANGE_PARK)
52 52
  *  Y[linear]   Park Y (Requires TOOLCHANGE_PARK)
53
- *  I[linear]   Park I (Requires TOOLCHANGE_PARK and LINEAR_AXES >= 4)
54
- *  J[linear]   Park J (Requires TOOLCHANGE_PARK and LINEAR_AXES >= 5)
55
- *  K[linear]   Park K (Requires TOOLCHANGE_PARK and LINEAR_AXES >= 6)
53
+ *  I[linear]   Park I (Requires TOOLCHANGE_PARK and NUM_AXES >= 4)
54
+ *  J[linear]   Park J (Requires TOOLCHANGE_PARK and NUM_AXES >= 5)
55
+ *  K[linear]   Park K (Requires TOOLCHANGE_PARK and NUM_AXES >= 6)
56
+ *  C[linear]   Park U (Requires TOOLCHANGE_PARK and NUM_AXES >= 7)
57
+ *  H[linear]   Park V (Requires TOOLCHANGE_PARK and NUM_AXES >= 8)
58
+ *  O[linear]   Park W (Requires TOOLCHANGE_PARK and NUM_AXES >= 9)
56 59
  *  Z[linear]   Z Raise
57 60
  *  F[linear]   Fan Speed 0-255
58 61
  *  G[linear/s] Fan time
@@ -95,13 +98,22 @@ void GcodeSuite::M217() {
95 98
       if (parser.seenval('Y')) { const int16_t v = parser.value_linear_units(); toolchange_settings.change_point.y = constrain(v, Y_MIN_POS, Y_MAX_POS); }
96 99
     #endif
97 100
     #if HAS_I_AXIS
98
-      if (parser.seenval('I')) { const int16_t v = parser.value_linear_units(); toolchange_settings.change_point.i = constrain(v, I_MIN_POS, I_MAX_POS); }
101
+      if (parser.seenval('I')) { const int16_t v = parser.TERN(AXIS4_ROTATES, value_int, value_linear_units)(); toolchange_settings.change_point.i = constrain(v, I_MIN_POS, I_MAX_POS); }
99 102
     #endif
100 103
     #if HAS_J_AXIS
101
-      if (parser.seenval('J')) { const int16_t v = parser.value_linear_units(); toolchange_settings.change_point.j = constrain(v, J_MIN_POS, J_MAX_POS); }
104
+      if (parser.seenval('J')) { const int16_t v = parser.TERN(AXIS5_ROTATES, value_int, value_linear_units)(); toolchange_settings.change_point.j = constrain(v, J_MIN_POS, J_MAX_POS); }
102 105
     #endif
103 106
     #if HAS_K_AXIS
104
-      if (parser.seenval('K')) { const int16_t v = parser.value_linear_units(); toolchange_settings.change_point.k = constrain(v, K_MIN_POS, K_MAX_POS); }
107
+      if (parser.seenval('K')) { const int16_t v = parser.TERN(AXIS6_ROTATES, value_int, value_linear_units)(); toolchange_settings.change_point.k = constrain(v, K_MIN_POS, K_MAX_POS); }
108
+    #endif
109
+    #if HAS_U_AXIS
110
+      if (parser.seenval('C')) { const int16_t v = parser.TERN(AXIS7_ROTATES, value_int, value_linear_units)(); toolchange_settings.change_point.u = constrain(v, U_MIN_POS, U_MAX_POS); }
111
+    #endif
112
+    #if HAS_V_AXIS
113
+      if (parser.seenval('H')) { const int16_t v = parser.TERN(AXIS8_ROTATES, value_int, value_linear_units)(); toolchange_settings.change_point.v = constrain(v, V_MIN_POS, V_MAX_POS); }
114
+    #endif
115
+    #if HAS_W_AXIS
116
+      if (parser.seenval('O')) { const int16_t v = parser.TERN(AXIS9_ROTATES, value_int, value_linear_units)(); toolchange_settings.change_point.w = constrain(v, W_MIN_POS, W_MAX_POS); }
105 117
     #endif
106 118
   #endif
107 119
 
@@ -167,24 +179,23 @@ void GcodeSuite::M217_report(const bool forReplay/*=true*/) {
167 179
     #endif
168 180
 
169 181
     #if ENABLED(TOOLCHANGE_PARK)
170
-    {
171 182
       SERIAL_ECHOPGM(" W", LINEAR_UNIT(toolchange_settings.enable_park));
172 183
       SERIAL_ECHOPGM_P(
173 184
             SP_X_STR, LINEAR_UNIT(toolchange_settings.change_point.x)
174 185
         #if HAS_Y_AXIS
175 186
           , SP_Y_STR, LINEAR_UNIT(toolchange_settings.change_point.y)
176 187
         #endif
177
-        #if HAS_I_AXIS
178
-          , SP_I_STR, LINEAR_UNIT(toolchange_settings.change_point.i)
179
-        #endif
180
-        #if HAS_J_AXIS
181
-          , SP_J_STR, LINEAR_UNIT(toolchange_settings.change_point.j)
182
-        #endif
183
-        #if HAS_K_AXIS
184
-          , SP_K_STR, LINEAR_UNIT(toolchange_settings.change_point.k)
188
+        #if SECONDARY_AXES >= 1
189
+          , LIST_N(DOUBLE(SECONDARY_AXES),
190
+              PSTR(" I"), I_AXIS_UNIT(toolchange_settings.change_point.i),
191
+              PSTR(" J"), J_AXIS_UNIT(toolchange_settings.change_point.j),
192
+              PSTR(" K"), K_AXIS_UNIT(toolchange_settings.change_point.k),
193
+              SP_C_STR,   U_AXIS_UNIT(toolchange_settings.change_point.u),
194
+              PSTR(" H"), V_AXIS_UNIT(toolchange_settings.change_point.v),
195
+              PSTR(" O"), W_AXIS_UNIT(toolchange_settings.change_point.w),
196
+            )
185 197
         #endif
186 198
       );
187
-    }
188 199
     #endif
189 200
 
190 201
     #if ENABLED(TOOLCHANGE_FS_PRIME_FIRST_USED)

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

@@ -24,7 +24,7 @@
24 24
 #include "../../module/planner.h"
25 25
 
26 26
 /**
27
- * M92: Set axis steps-per-unit for one or more axes, X, Y, Z, [I, [J, [K]]] and E.
27
+ * M92: Set axis steps-per-unit for one or more axes, X, Y, Z, [I, [J, [K, [U, [V, [W,]]]]]] and E.
28 28
  *      (Follows the same syntax as G92)
29 29
  *
30 30
  *      With multiple extruders use T to specify which one.
@@ -92,14 +92,17 @@ void GcodeSuite::M92() {
92 92
 
93 93
 void GcodeSuite::M92_report(const bool forReplay/*=true*/, const int8_t e/*=-1*/) {
94 94
   report_heading_etc(forReplay, F(STR_STEPS_PER_UNIT));
95
-  SERIAL_ECHOPGM_P(LIST_N(DOUBLE(LINEAR_AXES),
95
+  SERIAL_ECHOPGM_P(LIST_N(DOUBLE(NUM_AXES),
96 96
     PSTR("  M92 X"), LINEAR_UNIT(planner.settings.axis_steps_per_mm[X_AXIS]),
97 97
     SP_Y_STR, LINEAR_UNIT(planner.settings.axis_steps_per_mm[Y_AXIS]),
98 98
     SP_Z_STR, LINEAR_UNIT(planner.settings.axis_steps_per_mm[Z_AXIS]),
99
-    SP_I_STR, LINEAR_UNIT(planner.settings.axis_steps_per_mm[I_AXIS]),
100
-    SP_J_STR, LINEAR_UNIT(planner.settings.axis_steps_per_mm[J_AXIS]),
101
-    SP_K_STR, LINEAR_UNIT(planner.settings.axis_steps_per_mm[K_AXIS]))
102
-  );
99
+    SP_I_STR, I_AXIS_UNIT(planner.settings.axis_steps_per_mm[I_AXIS]),
100
+    SP_J_STR, J_AXIS_UNIT(planner.settings.axis_steps_per_mm[J_AXIS]),
101
+    SP_K_STR, K_AXIS_UNIT(planner.settings.axis_steps_per_mm[K_AXIS]),
102
+    SP_U_STR, U_AXIS_UNIT(planner.settings.axis_steps_per_mm[U_AXIS]),
103
+    SP_V_STR, V_AXIS_UNIT(planner.settings.axis_steps_per_mm[V_AXIS]),
104
+    SP_W_STR, W_AXIS_UNIT(planner.settings.axis_steps_per_mm[W_AXIS])
105
+  ));
103 106
   #if HAS_EXTRUDERS && DISABLED(DISTINCT_E_FACTORS)
104 107
     SERIAL_ECHOPGM_P(SP_E_STR, VOLUMETRIC_UNIT(planner.settings.axis_steps_per_mm[E_AXIS]));
105 108
   #endif

+ 20
- 11
Marlin/src/gcode/control/M17_M18_M84.cpp View File

@@ -46,13 +46,16 @@ inline axis_flags_t selected_axis_bits() {
46 46
         selected.bits = selected.e_bits();
47 47
     }
48 48
   #endif
49
-  selected.bits |= LINEAR_AXIS_GANG(
49
+  selected.bits |= NUM_AXIS_GANG(
50 50
       (parser.seen_test('X')        << X_AXIS),
51 51
     | (parser.seen_test('Y')        << Y_AXIS),
52 52
     | (parser.seen_test('Z')        << Z_AXIS),
53 53
     | (parser.seen_test(AXIS4_NAME) << I_AXIS),
54 54
     | (parser.seen_test(AXIS5_NAME) << J_AXIS),
55
-    | (parser.seen_test(AXIS6_NAME) << K_AXIS)
55
+    | (parser.seen_test(AXIS6_NAME) << K_AXIS),
56
+    | (parser.seen_test(AXIS7_NAME) << U_AXIS),
57
+    | (parser.seen_test(AXIS8_NAME) << V_AXIS),
58
+    | (parser.seen_test(AXIS9_NAME) << W_AXIS)
56 59
   );
57 60
   return selected;
58 61
 }
@@ -69,7 +72,7 @@ void do_enable(const axis_flags_t to_enable) {
69 72
   ena_mask_t also_enabled = 0;    // Track steppers enabled due to overlap
70 73
 
71 74
   // Enable all flagged axes
72
-  LOOP_LINEAR_AXES(a) {
75
+  LOOP_NUM_AXES(a) {
73 76
     if (TEST(shall_enable, a)) {
74 77
       stepper.enable_axis(AxisEnum(a));         // Mark and enable the requested axis
75 78
       DEBUG_ECHOLNPGM("Enabled ", axis_codes[a], " (", a, ") with overlap ", hex_word(enable_overlap[a]), " ... Enabled: ", hex_word(stepper.axis_enabled.bits));
@@ -89,7 +92,7 @@ void do_enable(const axis_flags_t to_enable) {
89 92
 
90 93
   if ((also_enabled &= ~(shall_enable | was_enabled))) {
91 94
     SERIAL_CHAR('(');
92
-    LOOP_LINEAR_AXES(a) if (TEST(also_enabled, a)) SERIAL_CHAR(axis_codes[a], ' ');
95
+    LOOP_NUM_AXES(a) if (TEST(also_enabled, a)) SERIAL_CHAR(axis_codes[a], ' ');
93 96
     #if HAS_EXTRUDERS
94 97
       #define _EN_ALSO(N) if (TEST(also_enabled, INDEX_OF_AXIS(E_AXIS, N))) SERIAL_CHAR('E', '0' + N, ' ');
95 98
       REPEAT(EXTRUDERS, _EN_ALSO)
@@ -125,13 +128,16 @@ void GcodeSuite::M17() {
125 128
             stepper.enable_e_steppers();
126 129
         }
127 130
       #endif
128
-      LINEAR_AXIS_CODE(
131
+      NUM_AXIS_CODE(
129 132
         if (parser.seen_test('X'))        stepper.enable_axis(X_AXIS),
130 133
         if (parser.seen_test('Y'))        stepper.enable_axis(Y_AXIS),
131 134
         if (parser.seen_test('Z'))        stepper.enable_axis(Z_AXIS),
132 135
         if (parser.seen_test(AXIS4_NAME)) stepper.enable_axis(I_AXIS),
133 136
         if (parser.seen_test(AXIS5_NAME)) stepper.enable_axis(J_AXIS),
134
-        if (parser.seen_test(AXIS6_NAME)) stepper.enable_axis(K_AXIS)
137
+        if (parser.seen_test(AXIS6_NAME)) stepper.enable_axis(K_AXIS),
138
+        if (parser.seen_test(AXIS7_NAME)) stepper.enable_axis(U_AXIS),
139
+        if (parser.seen_test(AXIS8_NAME)) stepper.enable_axis(V_AXIS),
140
+        if (parser.seen_test(AXIS9_NAME)) stepper.enable_axis(W_AXIS)
135 141
       );
136 142
     }
137 143
   }
@@ -149,7 +155,7 @@ void try_to_disable(const axis_flags_t to_disable) {
149 155
   if (!still_enabled) return;
150 156
 
151 157
   // Attempt to disable all flagged axes
152
-  LOOP_LINEAR_AXES(a)
158
+  LOOP_NUM_AXES(a)
153 159
     if (TEST(to_disable.bits, a)) {
154 160
       DEBUG_ECHOPGM("Try to disable ", axis_codes[a], " (", a, ") with overlap ", hex_word(enable_overlap[a]), " ... ");
155 161
       if (stepper.disable_axis(AxisEnum(a))) {            // Mark the requested axis and request to disable
@@ -178,7 +184,7 @@ void try_to_disable(const axis_flags_t to_disable) {
178 184
 
179 185
   auto overlap_warning = [](const ena_mask_t axis_bits) {
180 186
     SERIAL_ECHOPGM(" not disabled. Shared with");
181
-    LOOP_LINEAR_AXES(a) if (TEST(axis_bits, a)) SERIAL_CHAR(' ', axis_codes[a]);
187
+    LOOP_NUM_AXES(a) if (TEST(axis_bits, a)) SERIAL_CHAR(' ', axis_codes[a]);
182 188
     #if HAS_EXTRUDERS
183 189
       #define _EN_STILLON(N) if (TEST(axis_bits, INDEX_OF_AXIS(E_AXIS, N))) SERIAL_CHAR(' ', 'E', '0' + N);
184 190
       REPEAT(EXTRUDERS, _EN_STILLON)
@@ -187,7 +193,7 @@ void try_to_disable(const axis_flags_t to_disable) {
187 193
   };
188 194
 
189 195
   // If any of the requested axes are still enabled, give a warning
190
-  LOOP_LINEAR_AXES(a) {
196
+  LOOP_NUM_AXES(a) {
191 197
     if (TEST(still_enabled, a)) {
192 198
       SERIAL_CHAR(axis_codes[a]);
193 199
       overlap_warning(stepper.axis_enabled.bits & enable_overlap[a]);
@@ -229,13 +235,16 @@ void GcodeSuite::M18_M84() {
229 235
               stepper.disable_e_steppers();
230 236
           }
231 237
         #endif
232
-        LINEAR_AXIS_CODE(
238
+        NUM_AXIS_CODE(
233 239
           if (parser.seen_test('X'))        stepper.disable_axis(X_AXIS),
234 240
           if (parser.seen_test('Y'))        stepper.disable_axis(Y_AXIS),
235 241
           if (parser.seen_test('Z'))        stepper.disable_axis(Z_AXIS),
236 242
           if (parser.seen_test(AXIS4_NAME)) stepper.disable_axis(I_AXIS),
237 243
           if (parser.seen_test(AXIS5_NAME)) stepper.disable_axis(J_AXIS),
238
-          if (parser.seen_test(AXIS6_NAME)) stepper.disable_axis(K_AXIS)
244
+          if (parser.seen_test(AXIS6_NAME)) stepper.disable_axis(K_AXIS),
245
+          if (parser.seen_test(AXIS7_NAME)) stepper.disable_axis(U_AXIS),
246
+          if (parser.seen_test(AXIS8_NAME)) stepper.disable_axis(V_AXIS),
247
+          if (parser.seen_test(AXIS9_NAME)) stepper.disable_axis(W_AXIS)
239 248
         );
240 249
       }
241 250
     }

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

@@ -146,7 +146,7 @@
146 146
 
147 147
         HOTEND_LOOP() {
148 148
           DEBUG_ECHOPGM_P(SP_T_STR, e);
149
-          LOOP_LINEAR_AXES(a) DEBUG_ECHOPGM("  hotend_offset[", e, "].", AS_CHAR(AXIS_CHAR(a) | 0x20), "=", hotend_offset[e][a]);
149
+          LOOP_NUM_AXES(a) DEBUG_ECHOPGM("  hotend_offset[", e, "].", AS_CHAR(AXIS_CHAR(a) | 0x20), "=", hotend_offset[e][a]);
150 150
           DEBUG_EOL();
151 151
         }
152 152
         DEBUG_EOL();

+ 16
- 12
Marlin/src/gcode/feature/digipot/M907-M910.cpp View File

@@ -39,7 +39,7 @@
39 39
 #endif
40 40
 
41 41
 /**
42
- * M907: Set digital trimpot motor current using axis codes X [Y] [Z] [E]
42
+ * M907: Set digital trimpot motor current using axis codes X [Y] [Z] [I] [J] [K] [U] [V] [W] [E]
43 43
  *   B<current> - Special case for 4th (E) axis
44 44
  *   S<current> - Special case to set first 3 axes
45 45
  */
@@ -49,15 +49,15 @@ void GcodeSuite::M907() {
49 49
     if (!parser.seen("BS" LOGICAL_AXES_STRING))
50 50
       return M907_report();
51 51
 
52
-    LOOP_LOGICAL_AXES(i) if (parser.seenval(axis_codes[i])) stepper.set_digipot_current(i, parser.value_int());
52
+    LOOP_LOGICAL_AXES(i) if (parser.seenval(IAXIS_CHAR(i))) stepper.set_digipot_current(i, parser.value_int());
53 53
     if (parser.seenval('B')) stepper.set_digipot_current(4, parser.value_int());
54 54
     if (parser.seenval('S')) LOOP_LE_N(i, 4) stepper.set_digipot_current(i, parser.value_int());
55 55
 
56 56
   #elif HAS_MOTOR_CURRENT_PWM
57 57
 
58 58
     if (!parser.seen(
59
-      #if ANY_PIN(MOTOR_CURRENT_PWM_X, MOTOR_CURRENT_PWM_Y, MOTOR_CURRENT_PWM_XY)
60
-        "XY"
59
+      #if ANY_PIN(MOTOR_CURRENT_PWM_X, MOTOR_CURRENT_PWM_Y, MOTOR_CURRENT_PWM_XY, MOTOR_CURRENT_PWM_I, MOTOR_CURRENT_PWM_J, MOTOR_CURRENT_PWM_K, MOTOR_CURRENT_PWM_U, MOTOR_CURRENT_PWM_V, MOTOR_CURRENT_PWM_W)
60
+        "XY" SECONDARY_AXIS_GANG("I", "J", "K", "U", "V", "W")
61 61
       #endif
62 62
       #if PIN_EXISTS(MOTOR_CURRENT_PWM_Z)
63 63
         "Z"
@@ -67,8 +67,12 @@ void GcodeSuite::M907() {
67 67
       #endif
68 68
     )) return M907_report();
69 69
 
70
-    #if ANY_PIN(MOTOR_CURRENT_PWM_X, MOTOR_CURRENT_PWM_Y, MOTOR_CURRENT_PWM_XY)
71
-      if (parser.seenval('X') || parser.seenval('Y')) stepper.set_digipot_current(0, parser.value_int());
70
+    #if ANY_PIN(MOTOR_CURRENT_PWM_X, MOTOR_CURRENT_PWM_Y, MOTOR_CURRENT_PWM_XY, MOTOR_CURRENT_PWM_I, MOTOR_CURRENT_PWM_J, MOTOR_CURRENT_PWM_K, MOTOR_CURRENT_PWM_U, MOTOR_CURRENT_PWM_V, MOTOR_CURRENT_PWM_W)
71
+      if (NUM_AXIS_GANG(
72
+             parser.seenval('X'), || parser.seenval('Y'), || false,
73
+          || parser.seenval('I'), || parser.seenval('J'), || parser.seenval('K'),
74
+          || parser.seenval('U'), || parser.seenval('V'), || parser.seenval('W')
75
+      )) stepper.set_digipot_current(0, parser.value_int());
72 76
     #endif
73 77
     #if PIN_EXISTS(MOTOR_CURRENT_PWM_Z)
74 78
       if (parser.seenval('Z')) stepper.set_digipot_current(1, parser.value_int());
@@ -81,7 +85,7 @@ void GcodeSuite::M907() {
81 85
 
82 86
   #if HAS_MOTOR_CURRENT_I2C
83 87
     // this one uses actual amps in floating point
84
-    LOOP_LOGICAL_AXES(i) if (parser.seenval(axis_codes[i])) digipot_i2c.set_current(i, parser.value_float());
88
+    LOOP_LOGICAL_AXES(i) if (parser.seenval(IAXIS_CHAR(i))) digipot_i2c.set_current(i, parser.value_float());
85 89
     // Additional extruders use B,C,D for channels 4,5,6.
86 90
     // TODO: Change these parameters because 'E' is used. B<index>?
87 91
     #if HAS_EXTRUDERS
@@ -95,7 +99,7 @@ void GcodeSuite::M907() {
95 99
       const float dac_percent = parser.value_float();
96 100
       LOOP_LE_N(i, 4) stepper_dac.set_current_percent(i, dac_percent);
97 101
     }
98
-    LOOP_LOGICAL_AXES(i) if (parser.seenval(axis_codes[i])) stepper_dac.set_current_percent(i, parser.value_float());
102
+    LOOP_LOGICAL_AXES(i) if (parser.seenval(IAXIS_CHAR(i))) stepper_dac.set_current_percent(i, parser.value_float());
99 103
   #endif
100 104
 }
101 105
 
@@ -104,15 +108,15 @@ void GcodeSuite::M907() {
104 108
   void GcodeSuite::M907_report(const bool forReplay/*=true*/) {
105 109
     report_heading_etc(forReplay, F(STR_STEPPER_MOTOR_CURRENTS));
106 110
     #if HAS_MOTOR_CURRENT_PWM
107
-      SERIAL_ECHOLNPGM_P(                                    // PWM-based has 3 values:
108
-          PSTR("  M907 X"), stepper.motor_current_setting[0]  // X and Y
111
+      SERIAL_ECHOLNPGM_P(                                     // PWM-based has 3 values:
112
+          PSTR("  M907 X"), stepper.motor_current_setting[0]  // X, Y, (I, J, K, U, V, W)
109 113
         , SP_Z_STR,         stepper.motor_current_setting[1]  // Z
110 114
         , SP_E_STR,         stepper.motor_current_setting[2]  // E
111 115
       );
112 116
     #elif HAS_MOTOR_CURRENT_SPI
113 117
       SERIAL_ECHOPGM("  M907");                               // SPI-based has 5 values:
114
-      LOOP_LOGICAL_AXES(q) {                                  // X Y Z (I J K) E (map to X Y Z (I J K) E0 by default)
115
-        SERIAL_CHAR(' ', axis_codes[q]);
118
+      LOOP_LOGICAL_AXES(q) {                                  // X Y Z (I J K U V W) E (map to X Y Z (I J K U V W) E0 by default)
119
+        SERIAL_CHAR(' ', IAXIS_CHAR(q));
116 120
         SERIAL_ECHO(stepper.motor_current_setting[q]);
117 121
       }
118 122
       SERIAL_CHAR(' ', 'B');                                  // B (maps to E1 by default)

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

@@ -48,10 +48,14 @@ void GcodeSuite::G60() {
48 48
 
49 49
   #if ENABLED(SAVED_POSITIONS_DEBUG)
50 50
   {
51
-    DEBUG_ECHOPGM(STR_SAVED_POS " S", slot);
52 51
     const xyze_pos_t &pos = stored_position[slot];
52
+    DEBUG_ECHOPGM(STR_SAVED_POS " S", slot, " :");
53 53
     DEBUG_ECHOLNPAIR_F_P(
54
-      LIST_N(DOUBLE(LINEAR_AXES), PSTR(" : X"), pos.x, SP_Y_STR, pos.y, SP_Z_STR, pos.z, SP_I_STR, pos.i, SP_J_STR, pos.j, SP_K_STR, pos.k)
54
+      LIST_N(DOUBLE(NUM_AXES),
55
+        SP_Y_STR, pos.x, SP_Y_STR, pos.y, SP_Z_STR, pos.z,
56
+        SP_I_STR, pos.i, SP_J_STR, pos.j, SP_K_STR, pos.k,
57
+        SP_U_STR, pos.u, SP_V_STR, pos.v, SP_W_STR, pos.w
58
+      )
55 59
       #if HAS_EXTRUDERS
56 60
         , SP_E_STR, pos.e
57 61
       #endif

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

@@ -68,9 +68,9 @@ void GcodeSuite::G61() {
68 68
     SYNC_E(stored_position[slot].e);
69 69
   }
70 70
   else {
71
-    if (parser.seen(LINEAR_AXIS_GANG("X", "Y", "Z", STR_I, STR_J, STR_K))) {
71
+    if (parser.seen(NUM_AXIS_GANG("X", "Y", "Z", STR_I, STR_J, STR_K, STR_U, STR_V, STR_W))) {
72 72
       DEBUG_ECHOPGM(STR_RESTORING_POS " S", slot);
73
-      LOOP_LINEAR_AXES(i) {
73
+      LOOP_NUM_AXES(i) {
74 74
         destination[i] = parser.seen(AXIS_CHAR(i))
75 75
           ? stored_position[slot][i] + parser.value_axis_units((AxisEnum)i)
76 76
           : current_position[i];

+ 13
- 5
Marlin/src/gcode/feature/pause/M125.cpp View File

@@ -52,6 +52,9 @@
52 52
  *    A<pos>    = Override park position A (requires AXIS*_NAME 'A')
53 53
  *    B<pos>    = Override park position B (requires AXIS*_NAME 'B')
54 54
  *    C<pos>    = Override park position C (requires AXIS*_NAME 'C')
55
+ *    U<pos>    = Override park position U (requires AXIS*_NAME 'U')
56
+ *    V<pos>    = Override park position V (requires AXIS*_NAME 'V')
57
+ *    W<pos>    = Override park position W (requires AXIS*_NAME 'W')
55 58
  *    Z<linear> = Override Z raise
56 59
  *
57 60
  *  With an LCD menu:
@@ -64,17 +67,22 @@ void GcodeSuite::M125() {
64 67
   xyz_pos_t park_point = NOZZLE_PARK_POINT;
65 68
 
66 69
   // Move to filament change position or given position
67
-  LINEAR_AXIS_CODE(
70
+  NUM_AXIS_CODE(
68 71
     if (parser.seenval('X')) park_point.x = RAW_X_POSITION(parser.linearval('X')),
69 72
     if (parser.seenval('Y')) park_point.y = RAW_Y_POSITION(parser.linearval('Y')),
70 73
     NOOP,
71
-    if (parser.seenval(AXIS4_NAME)) park_point.i = RAW_I_POSITION(parser.linearval(AXIS4_NAME)),
72
-    if (parser.seenval(AXIS5_NAME)) park_point.j = RAW_J_POSITION(parser.linearval(AXIS5_NAME)),
73
-    if (parser.seenval(AXIS6_NAME)) park_point.k = RAW_K_POSITION(parser.linearval(AXIS6_NAME))
74
+    if (parser.seenval(AXIS4_NAME)) park_point.i = RAW_X_POSITION(parser.linearval(AXIS4_NAME)),
75
+    if (parser.seenval(AXIS5_NAME)) park_point.j = RAW_X_POSITION(parser.linearval(AXIS5_NAME)),
76
+    if (parser.seenval(AXIS6_NAME)) park_point.k = RAW_X_POSITION(parser.linearval(AXIS6_NAME)),
77
+    if (parser.seenval(AXIS7_NAME)) park_point.u = RAW_X_POSITION(parser.linearval(AXIS7_NAME)),
78
+    if (parser.seenval(AXIS8_NAME)) park_point.v = RAW_X_POSITION(parser.linearval(AXIS8_NAME)),
79
+    if (parser.seenval(AXIS9_NAME)) park_point.w = RAW_X_POSITION(parser.linearval(AXIS9_NAME))
74 80
   );
75 81
 
76 82
   // Lift Z axis
77
-  if (parser.seenval('Z')) park_point.z = parser.linearval('Z');
83
+  #if HAS_Z_AXIS
84
+    if (parser.seenval('Z')) park_point.z = parser.linearval('Z');
85
+  #endif
78 86
 
79 87
   #if HAS_HOTEND_OFFSET && NONE(DUAL_X_CARRIAGE, DELTA)
80 88
     park_point += hotend_offset[active_extruder];

+ 18
- 13
Marlin/src/gcode/feature/pause/M600.cpp View File

@@ -54,8 +54,14 @@
54 54
  *
55 55
  *  E[distance] - Retract the filament this far
56 56
  *  Z[distance] - Move the Z axis by this distance
57
- *  X[position] - Move to this X position, with Y
58
- *  Y[position] - Move to this Y position, with X
57
+ *  X[position] - Move to this X position (instead of NOZZLE_PARK_POINT.x)
58
+ *  Y[position] - Move to this Y position (instead of NOZZLE_PARK_POINT.y)
59
+ *  I[position] - Move to this I position (instead of NOZZLE_PARK_POINT.i)
60
+ *  J[position] - Move to this J position (instead of NOZZLE_PARK_POINT.j)
61
+ *  K[position] - Move to this K position (instead of NOZZLE_PARK_POINT.k)
62
+ *  C[position] - Move to this U position (instead of NOZZLE_PARK_POINT.u)
63
+ *  H[position] - Move to this V position (instead of NOZZLE_PARK_POINT.v)
64
+ *  O[position] - Move to this W position (instead of NOZZLE_PARK_POINT.w)
59 65
  *  U[distance] - Retract distance for removal (manual reload)
60 66
  *  L[distance] - Extrude distance for insertion (manual reload)
61 67
  *  B[count]    - Number of times to beep, -1 for indefinite (if equipped with a buzzer)
@@ -117,26 +123,25 @@ void GcodeSuite::M600() {
117 123
   xyz_pos_t park_point NOZZLE_PARK_POINT;
118 124
 
119 125
   // Move XY axes to filament change position or given position
120
-  LINEAR_AXIS_CODE(
126
+  NUM_AXIS_CODE(
121 127
     if (parser.seenval('X')) park_point.x = parser.linearval('X'),
122 128
     if (parser.seenval('Y')) park_point.y = parser.linearval('Y'),
123 129
     if (parser.seenval('Z')) park_point.z = parser.linearval('Z'),    // Lift Z axis
124
-    if (parser.seenval(AXIS4_NAME)) park_point.i = parser.linearval(AXIS4_NAME),
125
-    if (parser.seenval(AXIS5_NAME)) park_point.j = parser.linearval(AXIS5_NAME),
126
-    if (parser.seenval(AXIS6_NAME)) park_point.k = parser.linearval(AXIS6_NAME)
130
+    if (parser.seenval('I')) park_point.i = parser.linearval('I'),
131
+    if (parser.seenval('J')) park_point.j = parser.linearval('J'),
132
+    if (parser.seenval('K')) park_point.k = parser.linearval('K'),
133
+    if (parser.seenval('C')) park_point.u = parser.linearval('C'),    // U axis
134
+    if (parser.seenval('H')) park_point.v = parser.linearval('H'),    // V axis
135
+    if (parser.seenval('O')) park_point.w = parser.linearval('O')     // W axis
127 136
   );
128 137
 
129 138
   #if HAS_HOTEND_OFFSET && NONE(DUAL_X_CARRIAGE, DELTA)
130 139
     park_point += hotend_offset[active_extruder];
131 140
   #endif
132 141
 
133
-  #if ENABLED(MMU2_MENUS)
134
-    // For MMU2, when enabled, reset retract value so it doesn't mess with MMU filament handling
135
-    const float unload_length = standardM600 ? -ABS(parser.axisunitsval('U', E_AXIS, fc_settings[active_extruder].unload_length)) : 0.5f;
136
-  #else
137
-    // Unload filament
138
-    const float unload_length = -ABS(parser.axisunitsval('U', E_AXIS, fc_settings[active_extruder].unload_length));
139
-  #endif
142
+  // Unload filament
143
+  // For MMU2, when enabled, reset retract value so it doesn't mess with MMU filament handling
144
+  const float unload_length = standardM600 ? -ABS(parser.axisunitsval('U', E_AXIS, fc_settings[active_extruder].unload_length)) : 0.5f;
140 145
 
141 146
   const int beep_count = parser.intval('B', -1
142 147
     #ifdef FILAMENT_CHANGE_ALERT_BEEPS

+ 25
- 4
Marlin/src/gcode/feature/trinamic/M569.cpp View File

@@ -85,6 +85,15 @@ static void set_stealth_status(const bool enable, const int8_t eindex) {
85 85
       #if K_HAS_STEALTHCHOP
86 86
         case K_AXIS: TMC_SET_STEALTH(K); break;
87 87
       #endif
88
+      #if U_HAS_STEALTHCHOP
89
+        case U_AXIS: TMC_SET_STEALTH(U); break;
90
+      #endif
91
+      #if V_HAS_STEALTHCHOP
92
+        case V_AXIS: TMC_SET_STEALTH(V); break;
93
+      #endif
94
+      #if W_HAS_STEALTHCHOP
95
+        case W_AXIS: TMC_SET_STEALTH(W); break;
96
+      #endif
88 97
 
89 98
       #if E_STEPPERS
90 99
         case E_AXIS: {
@@ -115,6 +124,9 @@ static void say_stealth_status() {
115 124
   OPTCODE( I_HAS_STEALTHCHOP, TMC_SAY_STEALTH_STATUS(I))
116 125
   OPTCODE( J_HAS_STEALTHCHOP, TMC_SAY_STEALTH_STATUS(J))
117 126
   OPTCODE( K_HAS_STEALTHCHOP, TMC_SAY_STEALTH_STATUS(K))
127
+  OPTCODE( U_HAS_STEALTHCHOP, TMC_SAY_STEALTH_STATUS(U))
128
+  OPTCODE( V_HAS_STEALTHCHOP, TMC_SAY_STEALTH_STATUS(V))
129
+  OPTCODE( W_HAS_STEALTHCHOP, TMC_SAY_STEALTH_STATUS(W))
118 130
   OPTCODE(E0_HAS_STEALTHCHOP, TMC_SAY_STEALTH_STATUS(E0))
119 131
   OPTCODE(E1_HAS_STEALTHCHOP, TMC_SAY_STEALTH_STATUS(E1))
120 132
   OPTCODE(E2_HAS_STEALTHCHOP, TMC_SAY_STEALTH_STATUS(E2))
@@ -157,17 +169,23 @@ void GcodeSuite::M569_report(const bool forReplay/*=true*/) {
157 169
              chop_z = TERN0(Z_HAS_STEALTHCHOP, stepperZ.get_stored_stealthChop()),
158 170
              chop_i = TERN0(I_HAS_STEALTHCHOP, stepperI.get_stored_stealthChop()),
159 171
              chop_j = TERN0(J_HAS_STEALTHCHOP, stepperJ.get_stored_stealthChop()),
160
-             chop_k = TERN0(K_HAS_STEALTHCHOP, stepperK.get_stored_stealthChop());
172
+             chop_k = TERN0(K_HAS_STEALTHCHOP, stepperK.get_stored_stealthChop()),
173
+             chop_u = TERN0(U_HAS_STEALTHCHOP, stepperU.get_stored_stealthChop()),
174
+             chop_v = TERN0(V_HAS_STEALTHCHOP, stepperV.get_stored_stealthChop()),
175
+             chop_w = TERN0(W_HAS_STEALTHCHOP, stepperW.get_stored_stealthChop());
161 176
 
162
-  if (chop_x || chop_y || chop_z || chop_i || chop_j || chop_k) {
177
+  if (chop_x || chop_y || chop_z || chop_i || chop_j || chop_k || chop_u || chop_v || chop_w) {
163 178
     say_M569(forReplay);
164
-    LINEAR_AXIS_CODE(
179
+    NUM_AXIS_CODE(
165 180
       if (chop_x) SERIAL_ECHOPGM_P(SP_X_STR),
166 181
       if (chop_y) SERIAL_ECHOPGM_P(SP_Y_STR),
167 182
       if (chop_z) SERIAL_ECHOPGM_P(SP_Z_STR),
168 183
       if (chop_i) SERIAL_ECHOPGM_P(SP_I_STR),
169 184
       if (chop_j) SERIAL_ECHOPGM_P(SP_J_STR),
170
-      if (chop_k) SERIAL_ECHOPGM_P(SP_K_STR)
185
+      if (chop_k) SERIAL_ECHOPGM_P(SP_K_STR),
186
+      if (chop_u) SERIAL_ECHOPGM_P(SP_U_STR),
187
+      if (chop_v) SERIAL_ECHOPGM_P(SP_V_STR),
188
+      if (chop_w) SERIAL_ECHOPGM_P(SP_W_STR)
171 189
     );
172 190
     SERIAL_EOL();
173 191
   }
@@ -190,6 +208,9 @@ void GcodeSuite::M569_report(const bool forReplay/*=true*/) {
190 208
   if (TERN0( I_HAS_STEALTHCHOP, stepperI.get_stored_stealthChop()))  { say_M569(forReplay, FPSTR(SP_I_STR), true); }
191 209
   if (TERN0( J_HAS_STEALTHCHOP, stepperJ.get_stored_stealthChop()))  { say_M569(forReplay, FPSTR(SP_J_STR), true); }
192 210
   if (TERN0( K_HAS_STEALTHCHOP, stepperK.get_stored_stealthChop()))  { say_M569(forReplay, FPSTR(SP_K_STR), true); }
211
+  if (TERN0( U_HAS_STEALTHCHOP, stepperU.get_stored_stealthChop()))  { say_M569(forReplay, FPSTR(SP_U_STR), true); }
212
+  if (TERN0( V_HAS_STEALTHCHOP, stepperV.get_stored_stealthChop()))  { say_M569(forReplay, FPSTR(SP_V_STR), true); }
213
+  if (TERN0( W_HAS_STEALTHCHOP, stepperW.get_stored_stealthChop()))  { say_M569(forReplay, FPSTR(SP_W_STR), true); }
193 214
 
194 215
   if (TERN0(E0_HAS_STEALTHCHOP, stepperE0.get_stored_stealthChop())) { say_M569(forReplay, F("T0 E"), true); }
195 216
   if (TERN0(E1_HAS_STEALTHCHOP, stepperE1.get_stored_stealthChop())) { say_M569(forReplay, F("T1 E"), true); }

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

@@ -44,6 +44,9 @@ static void tmc_print_current(TMC &st) {
44 44
  *   A[current]  - Set mA current for A driver(s) (Requires AXIS*_NAME 'A')
45 45
  *   B[current]  - Set mA current for B driver(s) (Requires AXIS*_NAME 'B')
46 46
  *   C[current]  - Set mA current for C driver(s) (Requires AXIS*_NAME 'C')
47
+ *   U[current]  - Set mA current for U driver(s) (Requires AXIS*_NAME 'U')
48
+ *   V[current]  - Set mA current for V driver(s) (Requires AXIS*_NAME 'V')
49
+ *   W[current]  - Set mA current for W driver(s) (Requires AXIS*_NAME 'W')
47 50
  *   E[current]  - Set mA current for E driver(s)
48 51
  *
49 52
  *   I[index]    - Axis sub-index (Omit or 0 for X, Y, Z; 1 for X2, Y2, Z2; 2 for Z3; 3 for Z4.)
@@ -114,6 +117,15 @@ void GcodeSuite::M906() {
114 117
       #if AXIS_IS_TMC(K)
115 118
         case K_AXIS: TMC_SET_CURRENT(K); break;
116 119
       #endif
120
+      #if AXIS_IS_TMC(U)
121
+        case U_AXIS: TMC_SET_CURRENT(U); break;
122
+      #endif
123
+      #if AXIS_IS_TMC(V)
124
+        case V_AXIS: TMC_SET_CURRENT(V); break;
125
+      #endif
126
+      #if AXIS_IS_TMC(W)
127
+        case W_AXIS: TMC_SET_CURRENT(W); break;
128
+      #endif
117 129
 
118 130
       #if AXIS_IS_TMC(E0) || AXIS_IS_TMC(E1) || AXIS_IS_TMC(E2) || AXIS_IS_TMC(E3) || AXIS_IS_TMC(E4) || AXIS_IS_TMC(E5) || AXIS_IS_TMC(E6) || AXIS_IS_TMC(E7)
119 131
         case E_AXIS: {
@@ -181,6 +193,16 @@ void GcodeSuite::M906() {
181 193
     #if AXIS_IS_TMC(K)
182 194
       TMC_SAY_CURRENT(K);
183 195
     #endif
196
+    #if AXIS_IS_TMC(U)
197
+      TMC_SAY_CURRENT(U);
198
+    #endif
199
+    #if AXIS_IS_TMC(V)
200
+      TMC_SAY_CURRENT(V);
201
+    #endif
202
+    #if AXIS_IS_TMC(W)
203
+      TMC_SAY_CURRENT(W);
204
+    #endif
205
+
184 206
     #if AXIS_IS_TMC(E0)
185 207
       TMC_SAY_CURRENT(E0);
186 208
     #endif
@@ -217,7 +239,8 @@ void GcodeSuite::M906_report(const bool forReplay/*=true*/) {
217 239
   };
218 240
 
219 241
   #if  AXIS_IS_TMC(X) || AXIS_IS_TMC(Y) || AXIS_IS_TMC(Z) \
220
-    || AXIS_IS_TMC(I) || AXIS_IS_TMC(J) || AXIS_IS_TMC(K)
242
+    || AXIS_IS_TMC(I) || AXIS_IS_TMC(J) || AXIS_IS_TMC(K) \
243
+    || AXIS_IS_TMC(U) || AXIS_IS_TMC(V) || AXIS_IS_TMC(W)
221 244
     say_M906(forReplay);
222 245
     #if AXIS_IS_TMC(X)
223 246
       SERIAL_ECHOPGM_P(SP_X_STR, stepperX.getMilliamps());
@@ -237,6 +260,15 @@ void GcodeSuite::M906_report(const bool forReplay/*=true*/) {
237 260
     #if AXIS_IS_TMC(K)
238 261
       SERIAL_ECHOPGM_P(SP_K_STR, stepperK.getMilliamps());
239 262
     #endif
263
+    #if AXIS_IS_TMC(U)
264
+      SERIAL_ECHOPGM_P(SP_U_STR, stepperU.getMilliamps());
265
+    #endif
266
+    #if AXIS_IS_TMC(V)
267
+      SERIAL_ECHOPGM_P(SP_V_STR, stepperV.getMilliamps());
268
+    #endif
269
+    #if AXIS_IS_TMC(W)
270
+      SERIAL_ECHOPGM_P(SP_W_STR, stepperW.getMilliamps());
271
+    #endif
240 272
     SERIAL_EOL();
241 273
   #endif
242 274
 

+ 79
- 4
Marlin/src/gcode/feature/trinamic/M911-M914.cpp View File

@@ -53,12 +53,21 @@
53 53
   #if HAS_K_AXIS && M91x_USE(K)
54 54
     #define M91x_USE_K 1
55 55
   #endif
56
+  #if HAS_U_AXIS && M91x_USE(U)
57
+    #define M91x_USE_U 1
58
+  #endif
59
+  #if HAS_V_AXIS && M91x_USE(V)
60
+    #define M91x_USE_V 1
61
+  #endif
62
+  #if HAS_W_AXIS && M91x_USE(W)
63
+    #define M91x_USE_W 1
64
+  #endif
56 65
 
57 66
   #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)
58 67
     #define M91x_SOME_E 1
59 68
   #endif
60 69
 
61
-  #if !M91x_SOME_X && !M91x_SOME_Y && !M91x_SOME_Z && !M91x_USE_I && !M91x_USE_J && !M91x_USE_K && !M91x_SOME_E
70
+  #if !M91x_SOME_X && !M91x_SOME_Y && !M91x_SOME_Z && !M91x_USE_I && !M91x_USE_J && !M91x_USE_K && !M91x_USE_U && !M91x_USE_V && !M91x_USE_W && !M91x_SOME_E
62 71
     #error "MONITOR_DRIVER_STATUS requires at least one TMC2130, 2160, 2208, 2209, 2660, 5130, or 5160."
63 72
   #endif
64 73
 
@@ -109,6 +118,9 @@
109 118
     TERN_(M91x_USE_I, tmc_report_otpw(stepperI));
110 119
     TERN_(M91x_USE_J, tmc_report_otpw(stepperJ));
111 120
     TERN_(M91x_USE_K, tmc_report_otpw(stepperK));
121
+    TERN_(M91x_USE_U, tmc_report_otpw(stepperU));
122
+    TERN_(M91x_USE_V, tmc_report_otpw(stepperV));
123
+    TERN_(M91x_USE_W, tmc_report_otpw(stepperW));
112 124
     #if M91x_USE_E(0)
113 125
       tmc_report_otpw(stepperE0);
114 126
     #endif
@@ -137,7 +149,7 @@
137 149
 
138 150
   /**
139 151
    * M912: Clear TMC stepper driver overtemperature pre-warn flag held by the library
140
-   *       Specify one or more axes with X, Y, Z, X1, Y1, Z1, X2, Y2, Z2, Z3, Z4 and E[index].
152
+   *       Specify one or more axes with X, Y, Z, X1, Y1, Z1, X2, Y2, Z2, Z3, Z4, A, B, C, U, V, W, and E[index].
141 153
    *       If no axes are given, clear all.
142 154
    *
143 155
    * Examples:
@@ -154,9 +166,12 @@
154 166
                hasI = TERN0(M91x_USE_I,  parser.seen(axis_codes.i)),
155 167
                hasJ = TERN0(M91x_USE_J,  parser.seen(axis_codes.j)),
156 168
                hasK = TERN0(M91x_USE_K,  parser.seen(axis_codes.k)),
169
+               hasU = TERN0(M91x_USE_U,  parser.seen(axis_codes.u)),
170
+               hasV = TERN0(M91x_USE_V,  parser.seen(axis_codes.v)),
171
+               hasW = TERN0(M91x_USE_W,  parser.seen(axis_codes.w)),
157 172
                hasE = TERN0(M91x_SOME_E, parser.seen(axis_codes.e));
158 173
 
159
-    const bool hasNone = !hasE && !hasX && !hasY && !hasZ && !hasI && !hasJ && !hasK;
174
+    const bool hasNone = !hasE && !hasX && !hasY && !hasZ && !hasI && !hasJ && !hasK && !hasU && !hasV && !hasW;
160 175
 
161 176
     #if M91x_SOME_X
162 177
       const int8_t xval = int8_t(parser.byteval(axis_codes.x, 0xFF));
@@ -206,6 +221,18 @@
206 221
       const int8_t kval = int8_t(parser.byteval(axis_codes.k, 0xFF));
207 222
       if (hasNone || kval == 1 || (hasK && kval < 0)) tmc_clear_otpw(stepperK);
208 223
     #endif
224
+    #if M91x_USE_U
225
+      const int8_t uval = int8_t(parser.byteval(axis_codes.u, 0xFF));
226
+      if (hasNone || uval == 1 || (hasU && uval < 0)) tmc_clear_otpw(stepperU);
227
+    #endif
228
+    #if M91x_USE_V
229
+      const int8_t vval = int8_t(parser.byteval(axis_codes.v, 0xFF));
230
+      if (hasNone || vval == 1 || (hasV && vval < 0)) tmc_clear_otpw(stepperV);
231
+    #endif
232
+    #if M91x_USE_W
233
+      const int8_t wval = int8_t(parser.byteval(axis_codes.w, 0xFF));
234
+      if (hasNone || wval == 1 || (hasW && wval < 0)) tmc_clear_otpw(stepperW);
235
+    #endif
209 236
 
210 237
     #if M91x_SOME_E
211 238
       const int8_t eval = int8_t(parser.byteval(axis_codes.e, 0xFF));
@@ -296,6 +323,15 @@
296 323
         #if K_HAS_STEALTHCHOP
297 324
           case K_AXIS: TMC_SET_PWMTHRS(K,K); break;
298 325
         #endif
326
+        #if U_HAS_STEALTHCHOP
327
+          case U_AXIS: TMC_SET_PWMTHRS(U,U); break;
328
+        #endif
329
+        #if V_HAS_STEALTHCHOP
330
+          case V_AXIS: TMC_SET_PWMTHRS(V,V); break;
331
+        #endif
332
+        #if W_HAS_STEALTHCHOP
333
+          case W_AXIS: TMC_SET_PWMTHRS(W,W); break;
334
+        #endif
299 335
 
300 336
         #if E0_HAS_STEALTHCHOP || E1_HAS_STEALTHCHOP || E2_HAS_STEALTHCHOP || E3_HAS_STEALTHCHOP || E4_HAS_STEALTHCHOP || E5_HAS_STEALTHCHOP || E6_HAS_STEALTHCHOP || E7_HAS_STEALTHCHOP
301 337
           case E_AXIS: {
@@ -326,6 +362,9 @@
326 362
       TERN_( I_HAS_STEALTHCHOP, TMC_SAY_PWMTHRS(I,I));
327 363
       TERN_( J_HAS_STEALTHCHOP, TMC_SAY_PWMTHRS(J,J));
328 364
       TERN_( K_HAS_STEALTHCHOP, TMC_SAY_PWMTHRS(K,K));
365
+      TERN_( U_HAS_STEALTHCHOP, TMC_SAY_PWMTHRS(U,U));
366
+      TERN_( V_HAS_STEALTHCHOP, TMC_SAY_PWMTHRS(V,V));
367
+      TERN_( W_HAS_STEALTHCHOP, TMC_SAY_PWMTHRS(W,W));
329 368
 
330 369
       TERN_(E0_HAS_STEALTHCHOP, TMC_SAY_PWMTHRS_E(0));
331 370
       TERN_(E1_HAS_STEALTHCHOP, TMC_SAY_PWMTHRS_E(1));
@@ -397,6 +436,18 @@
397 436
       say_M913(forReplay);
398 437
       SERIAL_ECHOLNPGM_P(SP_K_STR, stepperK.get_pwm_thrs());
399 438
     #endif
439
+    #if U_HAS_STEALTHCHOP
440
+      say_M913(forReplay);
441
+      SERIAL_ECHOLNPGM_P(SP_U_STR, stepperU.get_pwm_thrs());
442
+    #endif
443
+    #if V_HAS_STEALTHCHOP
444
+      say_M913(forReplay);
445
+      SERIAL_ECHOLNPGM_P(SP_V_STR, stepperV.get_pwm_thrs());
446
+    #endif
447
+    #if W_HAS_STEALTHCHOP
448
+      say_M913(forReplay);
449
+      SERIAL_ECHOLNPGM_P(SP_W_STR, stepperW.get_pwm_thrs());
450
+    #endif
400 451
 
401 452
     #if E0_HAS_STEALTHCHOP
402 453
       say_M913(forReplay);
@@ -451,7 +502,7 @@
451 502
 
452 503
     bool report = true;
453 504
     const uint8_t index = parser.byteval('I');
454
-    LOOP_LINEAR_AXES(i) if (parser.seen(AXIS_CHAR(i))) {
505
+    LOOP_NUM_AXES(i) if (parser.seen(AXIS_CHAR(i))) {
455 506
       const int16_t value = parser.value_int();
456 507
       report = false;
457 508
       switch (i) {
@@ -484,6 +535,15 @@
484 535
         #if K_SENSORLESS
485 536
           case K_AXIS: stepperK.homing_threshold(value); break;
486 537
         #endif
538
+        #if U_SENSORLESS && AXIS_HAS_STALLGUARD(U)
539
+          case U_AXIS: stepperU.homing_threshold(value); break;
540
+        #endif
541
+        #if V_SENSORLESS && AXIS_HAS_STALLGUARD(V)
542
+          case V_AXIS: stepperV.homing_threshold(value); break;
543
+        #endif
544
+        #if W_SENSORLESS && AXIS_HAS_STALLGUARD(W)
545
+          case W_AXIS: stepperW.homing_threshold(value); break;
546
+        #endif
487 547
       }
488 548
     }
489 549
 
@@ -499,6 +559,9 @@
499 559
       TERN_(I_SENSORLESS, tmc_print_sgt(stepperI));
500 560
       TERN_(J_SENSORLESS, tmc_print_sgt(stepperJ));
501 561
       TERN_(K_SENSORLESS, tmc_print_sgt(stepperK));
562
+      TERN_(U_SENSORLESS, tmc_print_sgt(stepperU));
563
+      TERN_(V_SENSORLESS, tmc_print_sgt(stepperV));
564
+      TERN_(W_SENSORLESS, tmc_print_sgt(stepperW));
502 565
     }
503 566
   }
504 567
 
@@ -561,6 +624,18 @@
561 624
       say_M914(forReplay);
562 625
       SERIAL_ECHOLNPGM_P(SP_K_STR, stepperK.homing_threshold());
563 626
     #endif
627
+    #if U_SENSORLESS
628
+      say_M914(forReplay);
629
+      SERIAL_ECHOLNPGM_P(SP_U_STR, stepperU.homing_threshold());
630
+    #endif
631
+    #if V_SENSORLESS
632
+      say_M914(forReplay);
633
+      SERIAL_ECHOLNPGM_P(SP_V_STR, stepperV.homing_threshold());
634
+    #endif
635
+    #if W_SENSORLESS
636
+      say_M914(forReplay);
637
+      SERIAL_ECHOLNPGM_P(SP_W_STR, stepperW.homing_threshold());
638
+    #endif
564 639
   }
565 640
 
566 641
 #endif // USE_SENSORLESS

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

@@ -85,7 +85,10 @@ axis_bits_t GcodeSuite::axis_relative = 0 LOGICAL_AXIS_GANG(
85 85
   | (ar_init.z << REL_Z),
86 86
   | (ar_init.i << REL_I),
87 87
   | (ar_init.j << REL_J),
88
-  | (ar_init.k << REL_K)
88
+  | (ar_init.k << REL_K),
89
+  | (ar_init.u << REL_U),
90
+  | (ar_init.v << REL_V),
91
+  | (ar_init.w << REL_W)
89 92
 );
90 93
 
91 94
 #if EITHER(HAS_AUTO_REPORTING, HOST_KEEPALIVE_FEATURE)
@@ -176,7 +179,7 @@ void GcodeSuite::get_destination_from_command() {
176 179
   #endif
177 180
 
178 181
   // Get new XYZ position, whether absolute or relative
179
-  LOOP_LINEAR_AXES(i) {
182
+  LOOP_NUM_AXES(i) {
180 183
     if ( (seen[i] = parser.seenval(AXIS_CHAR(i))) ) {
181 184
       const float v = parser.value_axis_units((AxisEnum)i);
182 185
       if (skip_move)

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

@@ -337,7 +337,7 @@
337 337
 #endif
338 338
 
339 339
 enum AxisRelative : uint8_t {
340
-  LOGICAL_AXIS_LIST(REL_E, REL_X, REL_Y, REL_Z, REL_I, REL_J, REL_K)
340
+  LOGICAL_AXIS_LIST(REL_E, REL_X, REL_Y, REL_Z, REL_I, REL_J, REL_K, REL_U, REL_V, REL_W)
341 341
   #if HAS_EXTRUDERS
342 342
     , E_MODE_ABS, E_MODE_REL
343 343
   #endif
@@ -363,7 +363,8 @@ public:
363 363
     axis_relative = rel ? (0 LOGICAL_AXIS_GANG(
364 364
       | _BV(REL_E),
365 365
       | _BV(REL_X), | _BV(REL_Y), | _BV(REL_Z),
366
-      | _BV(REL_I), | _BV(REL_J), | _BV(REL_K)
366
+      | _BV(REL_I), | _BV(REL_J), | _BV(REL_K),
367
+      | _BV(REL_U), | _BV(REL_V), | _BV(REL_W)
367 368
     )) : 0;
368 369
   }
369 370
   #if HAS_EXTRUDERS

+ 1
- 1
Marlin/src/gcode/geometry/G53-G59.cpp View File

@@ -39,7 +39,7 @@ bool GcodeSuite::select_coordinate_system(const int8_t _new) {
39 39
   xyz_float_t new_offset{0};
40 40
   if (WITHIN(_new, 0, MAX_COORDINATE_SYSTEMS - 1))
41 41
     new_offset = coordinate_system[_new];
42
-  LOOP_LINEAR_AXES(i) {
42
+  LOOP_NUM_AXES(i) {
43 43
     if (position_shift[i] != new_offset[i]) {
44 44
       position_shift[i] = new_offset[i];
45 45
       update_workspace_offset((AxisEnum)i);

+ 5
- 5
Marlin/src/gcode/geometry/G92.cpp View File

@@ -29,7 +29,7 @@
29 29
 #endif
30 30
 
31 31
 /**
32
- * G92: Set the Current Position to the given X [Y [Z [A [B [C [E]]]]]] values.
32
+ * G92: Set the Current Position to the given X [Y [Z [A [B [C [U [V [W ]]]]]]]] [E] values.
33 33
  *
34 34
  * Behind the scenes the G92 command may modify the Current Position
35 35
  * or the Position Shift depending on settings and sub-commands.
@@ -37,14 +37,14 @@
37 37
  * Since E has no Workspace Offset, it is always set directly.
38 38
  *
39 39
  * Without Workspace Offsets (e.g., with NO_WORKSPACE_OFFSETS):
40
- *   G92   : Set NATIVE Current Position to the given X [Y [Z [A [B [C [E]]]]]].
40
+ *   G92   : Set NATIVE Current Position to the given X [Y [Z [A [B [C [U [V [W ]]]]]]]] [E].
41 41
  *
42 42
  * Using Workspace Offsets (default Marlin behavior):
43
- *   G92   : Modify Workspace Offsets so the reported position shows the given X [Y [Z [A [B [C [E]]]]]].
43
+ *   G92   : Modify Workspace Offsets so the reported position shows the given X [Y [Z [A [B [C [U [V [W ]]]]]]]] [E].
44 44
  *   G92.1 : Zero XYZ Workspace Offsets (so the reported position = the native position).
45 45
  *
46 46
  * With POWER_LOSS_RECOVERY:
47
- *   G92.9 : Set NATIVE Current Position to the given X [Y [Z [A [B [C [E]]]]]].
47
+ *   G92.9 : Set NATIVE Current Position to the given X [Y [Z [A [B [C [U [V [W ]]]]]]]] [E].
48 48
  */
49 49
 void GcodeSuite::G92() {
50 50
 
@@ -64,7 +64,7 @@ void GcodeSuite::G92() {
64 64
 
65 65
     #if ENABLED(CNC_COORDINATE_SYSTEMS) && !IS_SCARA
66 66
       case 1:                                                         // G92.1 - Zero the Workspace Offset
67
-        LOOP_LINEAR_AXES(i) if (position_shift[i]) {
67
+        LOOP_NUM_AXES(i) if (position_shift[i]) {
68 68
           position_shift[i] = 0;
69 69
           update_workspace_offset((AxisEnum)i);
70 70
         }

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

@@ -39,11 +39,17 @@
39 39
  */
40 40
 void GcodeSuite::M206() {
41 41
   if (!parser.seen_any()) return M206_report();
42
-
43
-  LOOP_LINEAR_AXES(i)
44
-    if (parser.seen(AXIS_CHAR(i)))
45
-      set_home_offset((AxisEnum)i, parser.value_linear_units());
46
-
42
+  NUM_AXIS_CODE(
43
+    if (parser.seen('X')) set_home_offset(X_AXIS, parser.value_linear_units()),
44
+    if (parser.seen('Y')) set_home_offset(Y_AXIS, parser.value_linear_units()),
45
+    if (parser.seen('Z')) set_home_offset(Y_AXIS, parser.value_linear_units()),
46
+    if (parser.seen(AXIS4_NAME)) set_home_offset(I_AXIS, parser.TERN(AXIS4_ROTATES, value_float, value_linear_units)()),
47
+    if (parser.seen(AXIS5_NAME)) set_home_offset(J_AXIS, parser.TERN(AXIS5_ROTATES, value_float, value_linear_units)()),
48
+    if (parser.seen(AXIS6_NAME)) set_home_offset(K_AXIS, parser.TERN(AXIS6_ROTATES, value_float, value_linear_units)()),
49
+    if (parser.seen(AXIS7_NAME)) set_home_offset(U_AXIS, parser.TERN(AXIS7_ROTATES, value_float, value_linear_units)()),
50
+    if (parser.seen(AXIS8_NAME)) set_home_offset(V_AXIS, parser.TERN(AXIS8_ROTATES, value_float, value_linear_units)()),
51
+    if (parser.seen(AXIS9_NAME)) set_home_offset(W_AXIS, parser.TERN(AXIS9_ROTATES, value_float, value_linear_units)())
52
+  );
47 53
   #if ENABLED(MORGAN_SCARA)
48 54
     if (parser.seen('T')) set_home_offset(A_AXIS, parser.value_float()); // Theta
49 55
     if (parser.seen('P')) set_home_offset(B_AXIS, parser.value_float()); // Psi
@@ -56,13 +62,16 @@ void GcodeSuite::M206_report(const bool forReplay/*=true*/) {
56 62
   report_heading_etc(forReplay, F(STR_HOME_OFFSET));
57 63
   SERIAL_ECHOLNPGM_P(
58 64
     #if IS_CARTESIAN
59
-      LIST_N(DOUBLE(LINEAR_AXES),
65
+      LIST_N(DOUBLE(NUM_AXES),
60 66
         PSTR("  M206 X"), LINEAR_UNIT(home_offset.x),
61 67
         SP_Y_STR, LINEAR_UNIT(home_offset.y),
62 68
         SP_Z_STR, LINEAR_UNIT(home_offset.z),
63
-        SP_I_STR, LINEAR_UNIT(home_offset.i),
64
-        SP_J_STR, LINEAR_UNIT(home_offset.j),
65
-        SP_K_STR, LINEAR_UNIT(home_offset.k)
69
+        SP_I_STR, I_AXIS_UNIT(home_offset.i),
70
+        SP_J_STR, J_AXIS_UNIT(home_offset.j),
71
+        SP_K_STR, K_AXIS_UNIT(home_offset.k),
72
+        SP_U_STR, U_AXIS_UNIT(home_offset.u),
73
+        SP_V_STR, V_AXIS_UNIT(home_offset.v),
74
+        SP_W_STR, W_AXIS_UNIT(home_offset.w)
66 75
       )
67 76
     #else
68 77
       PSTR("  M206 Z"), LINEAR_UNIT(home_offset.z)
@@ -85,7 +94,7 @@ void GcodeSuite::M428() {
85 94
   if (homing_needed_error()) return;
86 95
 
87 96
   xyz_float_t diff;
88
-  LOOP_LINEAR_AXES(i) {
97
+  LOOP_NUM_AXES(i) {
89 98
     diff[i] = base_home_pos((AxisEnum)i) - current_position[i];
90 99
     if (!WITHIN(diff[i], -20, 20) && home_dir((AxisEnum)i) > 0)
91 100
       diff[i] = -current_position[i];
@@ -97,7 +106,7 @@ void GcodeSuite::M428() {
97 106
     }
98 107
   }
99 108
 
100
-  LOOP_LINEAR_AXES(i) set_home_offset((AxisEnum)i, diff[i]);
109
+  LOOP_NUM_AXES(i) set_home_offset((AxisEnum)i, diff[i]);
101 110
   report_current_position();
102 111
   LCD_MESSAGE(MSG_HOME_OFFSETS_APPLIED);
103 112
   OKAY_BUZZ();

+ 14
- 2
Marlin/src/gcode/host/M114.cpp View File

@@ -47,7 +47,7 @@
47 47
 
48 48
   void report_linear_axis_pos(const xyz_pos_t &pos, const uint8_t precision=3) {
49 49
     char str[12];
50
-    LOOP_LINEAR_AXES(a) {
50
+    LOOP_NUM_AXES(a) {
51 51
       SERIAL_CHAR(' ', AXIS_CHAR(a), ':');
52 52
       SERIAL_ECHO(dtostrf(pos[a], 1, precision, str));
53 53
     }
@@ -134,6 +134,15 @@
134 134
       #if AXIS_IS_L64XX(K)
135 135
         REPORT_ABSOLUTE_POS(K);
136 136
       #endif
137
+      #if AXIS_IS_L64XX(U)
138
+        REPORT_ABSOLUTE_POS(U);
139
+      #endif
140
+      #if AXIS_IS_L64XX(V)
141
+        REPORT_ABSOLUTE_POS(V);
142
+      #endif
143
+      #if AXIS_IS_L64XX(W)
144
+        REPORT_ABSOLUTE_POS(W);
145
+      #endif
137 146
       #if AXIS_IS_L64XX(E0)
138 147
         REPORT_ABSOLUTE_POS(E0);
139 148
       #endif
@@ -184,7 +193,10 @@
184 193
       cartes.x, cartes.y, cartes.z,
185 194
       planner.get_axis_position_mm(I_AXIS),
186 195
       planner.get_axis_position_mm(J_AXIS),
187
-      planner.get_axis_position_mm(K_AXIS)
196
+      planner.get_axis_position_mm(K_AXIS),
197
+      planner.get_axis_position_mm(U_AXIS),
198
+      planner.get_axis_position_mm(V_AXIS),
199
+      planner.get_axis_position_mm(W_AXIS)
188 200
     );
189 201
     report_all_axis_pos(from_steppers);
190 202
 

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

@@ -65,8 +65,8 @@ void GcodeSuite::M115() {
65 65
     "PROTOCOL_VERSION:" PROTOCOL_VERSION " "
66 66
     "MACHINE_TYPE:" MACHINE_NAME " "
67 67
     "EXTRUDER_COUNT:" STRINGIFY(EXTRUDERS) " "
68
-    #if LINEAR_AXES != XYZ
69
-      "AXIS_COUNT:" STRINGIFY(LINEAR_AXES) " "
68
+    #if NUM_AXES != XYZ
69
+      "AXIS_COUNT:" STRINGIFY(NUM_AXES) " "
70 70
     #endif
71 71
     #ifdef MACHINE_UUID
72 72
       "UUID:" MACHINE_UUID

+ 6
- 3
Marlin/src/gcode/motion/G0_G1.cpp View File

@@ -49,13 +49,16 @@ void GcodeSuite::G0_G1(TERN_(HAS_FAST_MOVES, const bool fast_move/*=false*/)) {
49 49
   if (IsRunning()
50 50
     #if ENABLED(NO_MOTION_BEFORE_HOMING)
51 51
       && !homing_needed_error(
52
-        LINEAR_AXIS_GANG(
52
+        NUM_AXIS_GANG(
53 53
             (parser.seen_test('X') ? _BV(X_AXIS) : 0),
54 54
           | (parser.seen_test('Y') ? _BV(Y_AXIS) : 0),
55 55
           | (parser.seen_test('Z') ? _BV(Z_AXIS) : 0),
56 56
           | (parser.seen_test(AXIS4_NAME) ? _BV(I_AXIS) : 0),
57 57
           | (parser.seen_test(AXIS5_NAME) ? _BV(J_AXIS) : 0),
58
-          | (parser.seen_test(AXIS6_NAME) ? _BV(K_AXIS) : 0))
58
+          | (parser.seen_test(AXIS6_NAME) ? _BV(K_AXIS) : 0),
59
+          | (parser.seen_test(AXIS7_NAME) ? _BV(U_AXIS) : 0),
60
+          | (parser.seen_test(AXIS8_NAME) ? _BV(V_AXIS) : 0),
61
+          | (parser.seen_test(AXIS9_NAME) ? _BV(W_AXIS) : 0))
59 62
       )
60 63
     #endif
61 64
   ) {
@@ -89,7 +92,7 @@ void GcodeSuite::G0_G1(TERN_(HAS_FAST_MOVES, const bool fast_move/*=false*/)) {
89 92
       if (MIN_AUTORETRACT <= MAX_AUTORETRACT) {
90 93
         // When M209 Autoretract is enabled, convert E-only moves to firmware retract/recover moves
91 94
         if (fwretract.autoretract_enabled && parser.seen_test('E')
92
-          && !parser.seen(LINEAR_AXIS_GANG("X", "Y", "Z", STR_I, STR_J, STR_K))
95
+          && !parser.seen(NUM_AXIS_GANG("X", "Y", "Z", STR_I, STR_J, STR_K, STR_U, STR_V, STR_W))
93 96
         ) {
94 97
           const float echange = destination.e - current_position.e;
95 98
           // Is this a retract or recover move?

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

@@ -48,8 +48,8 @@
48 48
   #define MIN_ARC_SEGMENT_MM MAX_ARC_SEGMENT_MM
49 49
 #endif
50 50
 
51
-#define ARC_LIJK_CODE(L,I,J,K)    CODE_N(SUB2(LINEAR_AXES),L,I,J,K)
52
-#define ARC_LIJKE_CODE(L,I,J,K,E) ARC_LIJK_CODE(L,I,J,K); CODE_ITEM_E(E)
51
+#define ARC_LIJKUVW_CODE(L,I,J,K,U,V,W)    CODE_N(SUB2(NUM_AXES),L,I,J,K,U,V,W)
52
+#define ARC_LIJKUVWE_CODE(L,I,J,K,U,V,W,E) ARC_LIJKUVW_CODE(L,I,J,K,U,V,W); CODE_ITEM_E(E)
53 53
 
54 54
 /**
55 55
  * Plan an arc in 2 dimensions, with linear motion in the other axes.
@@ -82,11 +82,14 @@ void plan_arc(
82 82
               rt_X = cart[axis_p] - center_P,
83 83
               rt_Y = cart[axis_q] - center_Q;
84 84
 
85
-  ARC_LIJK_CODE(
85
+  ARC_LIJKUVW_CODE(
86 86
     const float start_L = current_position[axis_l],
87 87
     const float start_I = current_position.i,
88 88
     const float start_J = current_position.j,
89
-    const float start_K = current_position.k
89
+    const float start_K = current_position.k,
90
+    const float start_U = current_position.u,
91
+    const float start_V = current_position.v,
92
+    const float start_W = current_position.w
90 93
   );
91 94
 
92 95
   // Angle of rotation between position and target from the circle center.
@@ -122,11 +125,14 @@ void plan_arc(
122 125
     min_segments = CEIL((MIN_CIRCLE_SEGMENTS) * portion_of_circle);     // Minimum segments for the arc
123 126
   }
124 127
 
125
-  ARC_LIJKE_CODE(
128
+  ARC_LIJKUVWE_CODE(
126 129
     float travel_L = cart[axis_l] - start_L,
127 130
     float travel_I = cart.i       - start_I,
128 131
     float travel_J = cart.j       - start_J,
129 132
     float travel_K = cart.k       - start_K,
133
+    float travel_U = cart.u       - start_U,
134
+    float travel_V = cart.v       - start_V,
135
+    float travel_W = cart.w       - start_W,
130 136
     float travel_E = cart.e       - current_position.e
131 137
   );
132 138
 
@@ -135,30 +141,39 @@ void plan_arc(
135 141
     const float total_angular = abs_angular_travel + circles * RADIANS(360),    // Total rotation with all circles and remainder
136 142
               part_per_circle = RADIANS(360) / total_angular;                   // Each circle's part of the total
137 143
 
138
-    ARC_LIJKE_CODE(
144
+    ARC_LIJKUVWE_CODE(
139 145
       const float per_circle_L = travel_L * part_per_circle,    // L movement per circle
140 146
       const float per_circle_I = travel_I * part_per_circle,
141 147
       const float per_circle_J = travel_J * part_per_circle,
142 148
       const float per_circle_K = travel_K * part_per_circle,
149
+      const float per_circle_U = travel_U * part_per_circle,
150
+      const float per_circle_V = travel_V * part_per_circle,
151
+      const float per_circle_W = travel_W * part_per_circle,
143 152
       const float per_circle_E = travel_E * part_per_circle     // E movement per circle
144 153
     );
145 154
 
146 155
     xyze_pos_t temp_position = current_position;
147 156
     for (uint16_t n = circles; n--;) {
148
-      ARC_LIJKE_CODE(                                           // Destination Linear Axes
157
+      ARC_LIJKUVWE_CODE(                                           // Destination Linear Axes
149 158
         temp_position[axis_l] += per_circle_L,
150 159
         temp_position.i       += per_circle_I,
151 160
         temp_position.j       += per_circle_J,
152 161
         temp_position.k       += per_circle_K,
162
+        temp_position.u       += per_circle_U,
163
+        temp_position.v       += per_circle_V,
164
+        temp_position.w       += per_circle_W,
153 165
         temp_position.e       += per_circle_E                   // Destination E axis
154 166
       );
155 167
       plan_arc(temp_position, offset, clockwise, 0);            // Plan a single whole circle
156 168
     }
157
-    ARC_LIJKE_CODE(
169
+    ARC_LIJKUVWE_CODE(
158 170
       travel_L = cart[axis_l] - current_position[axis_l],
159 171
       travel_I = cart.i       - current_position.i,
160 172
       travel_J = cart.j       - current_position.j,
161 173
       travel_K = cart.k       - current_position.k,
174
+      travel_U = cart.u       - current_position.u,
175
+      travel_V = cart.v       - current_position.v,
176
+      travel_W = cart.w       - current_position.w,
162 177
       travel_E = cart.e       - current_position.e
163 178
     );
164 179
   }
@@ -168,11 +183,14 @@ void plan_arc(
168 183
 
169 184
   // Return if the move is near zero
170 185
   if (flat_mm < 0.0001f
171
-    GANG_N(SUB2(LINEAR_AXES),
186
+    GANG_N(SUB2(NUM_AXES),
172 187
       && travel_L < 0.0001f,
173 188
       && travel_I < 0.0001f,
174 189
       && travel_J < 0.0001f,
175
-      && travel_K < 0.0001f
190
+      && travel_K < 0.0001f,
191
+      && travel_U < 0.0001f,
192
+      && travel_V < 0.0001f,
193
+      && travel_W < 0.0001f
176 194
     )
177 195
   ) return;
178 196
 
@@ -236,11 +254,14 @@ void plan_arc(
236 254
               cos_T = 1 - 0.5f * sq_theta_per_segment; // Small angle approximation
237 255
 
238 256
   #if DISABLED(AUTO_BED_LEVELING_UBL)
239
-    ARC_LIJK_CODE(
257
+    ARC_LIJKUVW_CODE(
240 258
       const float per_segment_L = proportion * travel_L / segments,
241 259
       const float per_segment_I = proportion * travel_I / segments,
242 260
       const float per_segment_J = proportion * travel_J / segments,
243
-      const float per_segment_K = proportion * travel_K / segments
261
+      const float per_segment_K = proportion * travel_K / segments,
262
+      const float per_segment_U = proportion * travel_U / segments,
263
+      const float per_segment_V = proportion * travel_V / segments,
264
+      const float per_segment_W = proportion * travel_W / segments
244 265
     );
245 266
   #endif
246 267
 
@@ -250,11 +271,14 @@ void plan_arc(
250 271
   if (tooshort) segments++;
251 272
 
252 273
   // Initialize all linear axes and E
253
-  ARC_LIJKE_CODE(
274
+  ARC_LIJKUVWE_CODE(
254 275
     raw[axis_l] = current_position[axis_l],
255 276
     raw.i       = current_position.i,
256 277
     raw.j       = current_position.j,
257 278
     raw.k       = current_position.k,
279
+    raw.u       = current_position.u,
280
+    raw.v       = current_position.v,
281
+    raw.w       = current_position.w,
258 282
     raw.e       = current_position.e
259 283
   );
260 284
 
@@ -303,11 +327,15 @@ void plan_arc(
303 327
     // Update raw location
304 328
     raw[axis_p] = center_P + rvec.a;
305 329
     raw[axis_q] = center_Q + rvec.b;
306
-    ARC_LIJKE_CODE(
330
+    ARC_LIJKUVWE_CODE(
307 331
       #if ENABLED(AUTO_BED_LEVELING_UBL)
308
-        raw[axis_l] = start_L, raw.i = start_I, raw.j = start_J, raw.k = start_K
332
+        raw[axis_l] = start_L,
333
+        raw.i = start_I, raw.j = start_J, raw.k = start_K,
334
+        raw.u = start_U, raw.v = start_V, raw.w = start_V
309 335
       #else
310
-        raw[axis_l] += per_segment_L, raw.i += per_segment_I, raw.j += per_segment_J, raw.k += per_segment_K
336
+        raw[axis_l] += per_segment_L,
337
+        raw.i += per_segment_I, raw.j += per_segment_J, raw.k += per_segment_K,
338
+        raw.u += per_segment_U, raw.v += per_segment_V, raw.w += per_segment_W
311 339
       #endif
312 340
       , raw.e += extruder_per_segment
313 341
     );
@@ -325,7 +353,11 @@ void plan_arc(
325 353
   // Ensure last segment arrives at target location.
326 354
   raw = cart;
327 355
   #if ENABLED(AUTO_BED_LEVELING_UBL)
328
-    ARC_LIJK_CODE(raw[axis_l] = start_L, raw.i = start_I, raw.j = start_J, raw.k = start_K);
356
+    ARC_LIJKUVW_CODE(
357
+      raw[axis_l] = start_L,
358
+      raw.i = start_I, raw.j = start_J, raw.k = start_K,
359
+      raw.u = start_U, raw.v = start_V, raw.w = start_W
360
+    );
329 361
   #endif
330 362
 
331 363
   apply_motion_limits(raw);
@@ -337,7 +369,11 @@ void plan_arc(
337 369
   planner.buffer_line(raw, scaled_fr_mm_s, active_extruder, 0 OPTARG(SCARA_FEEDRATE_SCALING, inv_duration));
338 370
 
339 371
   #if ENABLED(AUTO_BED_LEVELING_UBL)
340
-    ARC_LIJK_CODE(raw[axis_l] = start_L, raw.i = start_I, raw.j = start_J, raw.k = start_K);
372
+    ARC_LIJKUVW_CODE(
373
+      raw[axis_l] = start_L,
374
+      raw.i = start_I, raw.j = start_J, raw.k = start_K,
375
+      raw.u = start_U, raw.v = start_V, raw.w = start_W
376
+    );
341 377
   #endif
342 378
   current_position = raw;
343 379
 
@@ -380,7 +416,7 @@ void GcodeSuite::G2_G3(const bool clockwise) {
380 416
       relative_mode = true;
381 417
     #endif
382 418
 
383
-    get_destination_from_command();   // Get X Y [Z[I[J[K]]]] [E] F (and set cutter power)
419
+    get_destination_from_command();   // Get X Y [Z[I[J[K...]]]] [E] F (and set cutter power)
384 420
 
385 421
     TERN_(SF_ARC_FIX, relative_mode = relative_mode_backup);
386 422
 

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

@@ -69,7 +69,7 @@
69 69
  */
70 70
 void GcodeSuite::M290() {
71 71
   #if ENABLED(BABYSTEP_XY)
72
-    LOOP_LINEAR_AXES(a)
72
+    LOOP_NUM_AXES(a)
73 73
       if (parser.seenval(AXIS_CHAR(a)) || (a == Z_AXIS && parser.seenval('S'))) {
74 74
         const float offs = constrain(parser.value_axis_units((AxisEnum)a), -2, 2);
75 75
         babystep.add_mm((AxisEnum)a, offs);
@@ -87,7 +87,7 @@ void GcodeSuite::M290() {
87 87
     }
88 88
   #endif
89 89
 
90
-  if (!parser.seen(LINEAR_AXIS_GANG("X", "Y", "Z", STR_I, STR_J, STR_K)) || parser.seen('R')) {
90
+  if (!parser.seen(NUM_AXIS_GANG("X", "Y", "Z", STR_I, STR_J, STR_K, STR_U, STR_V, STR_W)) || 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':, case AXIS4_NAME:, case AXIS5_NAME:, case AXIS6_NAME:)
251
+      LOGICAL_AXIS_GANG(case 'E':, case 'X':, case 'Y':, case 'Z':, case AXIS4_NAME:, case AXIS5_NAME:, case AXIS6_NAME:, case AXIS7_NAME:, case AXIS8_NAME:, case AXIS9_NAME:)
252 252
       case 'F':
253 253
         if (motion_mode_codenum < 0) return;
254 254
         command_letter = 'G';

+ 19
- 7
Marlin/src/gcode/parser.h View File

@@ -309,13 +309,18 @@ public:
309 309
     }
310 310
 
311 311
     static float axis_unit_factor(const AxisEnum axis) {
312
-      return (
313
-        #if HAS_EXTRUDERS
314
-          axis >= E_AXIS && volumetric_enabled ? volumetric_unit_factor : linear_unit_factor
315
-        #else
316
-          linear_unit_factor
317
-        #endif
318
-      );
312
+      if (false
313
+        || TERN0(AXIS4_ROTATES, axis == I_AXIS)
314
+        || TERN0(AXIS5_ROTATES, axis == J_AXIS)
315
+        || TERN0(AXIS6_ROTATES, axis == K_AXIS)
316
+        || TERN0(AXIS7_ROTATES, axis == U_AXIS)
317
+        || TERN0(AXIS8_ROTATES, axis == V_AXIS)
318
+        || TERN0(AXIS9_ROTATES, axis == W_AXIS)
319
+      ) return 1.0f;
320
+      #if HAS_EXTRUDERS
321
+        if (axis >= E_AXIS && volumetric_enabled) return volumetric_unit_factor;
322
+      #endif
323
+      return linear_unit_factor;
319 324
     }
320 325
 
321 326
     static float linear_value_to_mm(const_float_t v)                  { return v * linear_unit_factor; }
@@ -340,6 +345,13 @@ public:
340 345
   #define LINEAR_UNIT(V)     parser.mm_to_linear_unit(V)
341 346
   #define VOLUMETRIC_UNIT(V) parser.mm_to_volumetric_unit(V)
342 347
 
348
+  #define I_AXIS_UNIT(V) TERN(AXIS4_ROTATES, (V), LINEAR_UNIT(V))
349
+  #define J_AXIS_UNIT(V) TERN(AXIS5_ROTATES, (V), LINEAR_UNIT(V))
350
+  #define K_AXIS_UNIT(V) TERN(AXIS6_ROTATES, (V), LINEAR_UNIT(V))
351
+  #define U_AXIS_UNIT(V) TERN(AXIS7_ROTATES, (V), LINEAR_UNIT(V))
352
+  #define V_AXIS_UNIT(V) TERN(AXIS8_ROTATES, (V), LINEAR_UNIT(V))
353
+  #define W_AXIS_UNIT(V) TERN(AXIS9_ROTATES, (V), LINEAR_UNIT(V))
354
+
343 355
   static float value_linear_units()                      { return linear_value_to_mm(value_float()); }
344 356
   static float value_axis_units(const AxisEnum axis)     { return axis_value_to_mm(axis, value_float()); }
345 357
   static float value_per_axis_units(const AxisEnum axis) { return per_axis_value(axis, value_float()); }

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

@@ -49,7 +49,7 @@ inline bool G38_run_probe() {
49 49
   #if MULTIPLE_PROBING > 1
50 50
     // Get direction of move and retract
51 51
     xyz_float_t retract_mm;
52
-    LOOP_LINEAR_AXES(i) {
52
+    LOOP_NUM_AXES(i) {
53 53
       const float dist = destination[i] - current_position[i];
54 54
       retract_mm[i] = ABS(dist) < G38_MINIMUM_MOVE ? 0 : home_bump_mm((AxisEnum)i) * (dist > 0 ? -1 : 1);
55 55
     }
@@ -119,7 +119,7 @@ void GcodeSuite::G38(const int8_t subcode) {
119 119
   ;
120 120
 
121 121
   // If any axis has enough movement, do the move
122
-  LOOP_LINEAR_AXES(i)
122
+  LOOP_NUM_AXES(i)
123 123
     if (ABS(destination[i] - current_position[i]) >= G38_MINIMUM_MOVE) {
124 124
       if (!parser.seenval('F')) feedrate_mm_s = homing_feedrate((AxisEnum)i);
125 125
       // If G38.2 fails throw an error

+ 90
- 13
Marlin/src/inc/Conditionals_LCD.h View File

@@ -677,22 +677,31 @@
677 677
 #endif
678 678
 
679 679
 /**
680
- * Number of Linear Axes (e.g., XYZ)
680
+ * Number of Linear Axes (e.g., XYZIJKUVW)
681 681
  * All the logical axes except for the tool (E) axis
682 682
  */
683
-#ifndef LINEAR_AXES
684
-  #define LINEAR_AXES XYZ
683
+#ifndef NUM_AXES
684
+  #define NUM_AXES XYZ
685 685
 #endif
686
-#if LINEAR_AXES >= XY
686
+#if NUM_AXES >= XY
687 687
   #define HAS_Y_AXIS 1
688
-  #if LINEAR_AXES >= XYZ
688
+  #if NUM_AXES >= XYZ
689 689
     #define HAS_Z_AXIS 1
690
-    #if LINEAR_AXES >= 4
690
+    #if NUM_AXES >= 4
691 691
       #define HAS_I_AXIS 1
692
-      #if LINEAR_AXES >= 5
692
+      #if NUM_AXES >= 5
693 693
         #define HAS_J_AXIS 1
694
-        #if LINEAR_AXES >= 6
694
+        #if NUM_AXES >= 6
695 695
           #define HAS_K_AXIS 1
696
+          #if NUM_AXES >= 7
697
+            #define HAS_U_AXIS 1
698
+            #if NUM_AXES >= 8
699
+              #define HAS_V_AXIS 1
700
+              #if NUM_AXES >= 9
701
+                #define HAS_W_AXIS 1
702
+              #endif
703
+            #endif
704
+          #endif
696 705
         #endif
697 706
       #endif
698 707
     #endif
@@ -700,14 +709,58 @@
700 709
 #endif
701 710
 
702 711
 /**
703
- * Number of Logical Axes (e.g., XYZE)
704
- * All the logical axes that can be commanded directly by G-code.
712
+ * Number of Primary Linear Axes (e.g., XYZ)
713
+ * X, XY, or XYZ axes. Excluding duplicate axes (X2, Y2. Z2. Z3, Z4)
714
+ */
715
+#if HAS_I_AXIS
716
+  #define PRIMARY_LINEAR_AXES 3
717
+#else
718
+  #define PRIMARY_LINEAR_AXES NUM_AXES
719
+#endif
720
+
721
+/**
722
+ * Number of Secondary Axes (e.g., IJKUVW)
723
+ * All linear/rotational axes between XYZ and E.
724
+ */
725
+#define SECONDARY_AXES SUB3(NUM_AXES)
726
+
727
+/**
728
+ * Number of Rotational Axes (e.g., IJK)
729
+ * All axes for which AXIS*_ROTATES is defined.
730
+ * For these axes, positions are specified in angular degrees.
731
+ */
732
+#if ENABLED(AXIS9_ROTATES)
733
+  #define ROTATIONAL_AXES 6
734
+#elif ENABLED(AXIS8_ROTATES)
735
+  #define ROTATIONAL_AXES 5
736
+#elif ENABLED(AXIS7_ROTATES)
737
+  #define ROTATIONAL_AXES 4
738
+#elif ENABLED(AXIS6_ROTATES)
739
+  #define ROTATIONAL_AXES 3
740
+#elif ENABLED(AXIS5_ROTATES)
741
+  #define ROTATIONAL_AXES 2
742
+#elif ENABLED(AXIS4_ROTATES)
743
+  #define ROTATIONAL_AXES 1
744
+#else
745
+  #define ROTATIONAL_AXES 0
746
+#endif
747
+
748
+/**
749
+ * Number of Secondary Linear Axes (e.g., UVW)
750
+ * All secondary axes for which AXIS*_ROTATES is not defined.
751
+ * Excluding primary axes and excluding duplicate axes (X2, Y2, Z2, Z3, Z4)
752
+ */
753
+#define SECONDARY_LINEAR_AXES (NUM_AXES - PRIMARY_LINEAR_AXES - ROTATIONAL_AXES)
754
+
755
+/**
756
+ * Number of Logical Axes (e.g., XYZIJKUVWE)
757
+ * All logical axes that can be commanded directly by G-code.
705 758
  * Delta maps stepper-specific values to ABC steppers.
706 759
  */
707 760
 #if HAS_EXTRUDERS
708
-  #define LOGICAL_AXES INCREMENT(LINEAR_AXES)
761
+  #define LOGICAL_AXES INCREMENT(NUM_AXES)
709 762
 #else
710
-  #define LOGICAL_AXES LINEAR_AXES
763
+  #define LOGICAL_AXES NUM_AXES
711 764
 #endif
712 765
 
713 766
 /**
@@ -725,7 +778,7 @@
725 778
  *  distinguished.
726 779
  */
727 780
 #if ENABLED(DISTINCT_E_FACTORS) && E_STEPPERS > 1
728
-  #define DISTINCT_AXES (LINEAR_AXES + E_STEPPERS)
781
+  #define DISTINCT_AXES (NUM_AXES + E_STEPPERS)
729 782
   #define DISTINCT_E E_STEPPERS
730 783
   #define E_INDEX_N(E) (E)
731 784
 #else
@@ -955,6 +1008,21 @@
955 1008
 #elif K_HOME_DIR < 0
956 1009
   #define K_HOME_TO_MIN 1
957 1010
 #endif
1011
+#if U_HOME_DIR > 0
1012
+  #define U_HOME_TO_MAX 1
1013
+#elif U_HOME_DIR < 0
1014
+  #define U_HOME_TO_MIN 1
1015
+#endif
1016
+#if V_HOME_DIR > 0
1017
+  #define V_HOME_TO_MAX 1
1018
+#elif V_HOME_DIR < 0
1019
+  #define V_HOME_TO_MIN 1
1020
+#endif
1021
+#if W_HOME_DIR > 0
1022
+  #define W_HOME_TO_MAX 1
1023
+#elif W_HOME_DIR < 0
1024
+  #define W_HOME_TO_MIN 1
1025
+#endif
958 1026
 
959 1027
 /**
960 1028
  * Conditionals based on the type of Bed Probe
@@ -1228,6 +1296,15 @@
1228 1296
 #if HAS_K_AXIS && !defined(INVERT_K_DIR)
1229 1297
   #define INVERT_K_DIR false
1230 1298
 #endif
1299
+#if HAS_U_AXIS && !defined(INVERT_U_DIR)
1300
+  #define INVERT_U_DIR false
1301
+#endif
1302
+#if HAS_V_AXIS && !defined(INVERT_V_DIR)
1303
+  #define INVERT_V_DIR false
1304
+#endif
1305
+#if HAS_W_AXIS && !defined(INVERT_W_DIR)
1306
+  #define INVERT_W_DIR false
1307
+#endif
1231 1308
 #if HAS_EXTRUDERS && !defined(INVERT_E_DIR)
1232 1309
   #define INVERT_E_DIR false
1233 1310
 #endif

+ 39
- 24
Marlin/src/inc/Conditionals_adv.h View File

@@ -914,30 +914,45 @@
914 914
 #endif
915 915
 
916 916
 // Remove unused STEALTHCHOP flags
917
-#if LINEAR_AXES < 6
918
-  #undef STEALTHCHOP_K
919
-  #undef CALIBRATION_MEASURE_KMIN
920
-  #undef CALIBRATION_MEASURE_KMAX
921
-  #if LINEAR_AXES < 5
922
-    #undef STEALTHCHOP_J
923
-    #undef CALIBRATION_MEASURE_JMIN
924
-    #undef CALIBRATION_MEASURE_JMAX
925
-    #if LINEAR_AXES < 4
926
-      #undef STEALTHCHOP_I
927
-      #undef CALIBRATION_MEASURE_IMIN
928
-      #undef CALIBRATION_MEASURE_IMAX
929
-      #if LINEAR_AXES < 3
930
-        #undef Z_IDLE_HEIGHT
931
-        #undef STEALTHCHOP_Z
932
-        #undef Z_PROBE_SLED
933
-        #undef Z_SAFE_HOMING
934
-        #undef HOME_Z_FIRST
935
-        #undef HOMING_Z_WITH_PROBE
936
-        #undef ENABLE_LEVELING_FADE_HEIGHT
937
-        #undef NUM_Z_STEPPER_DRIVERS
938
-        #undef CNC_WORKSPACE_PLANES
939
-        #if LINEAR_AXES < 2
940
-          #undef STEALTHCHOP_Y
917
+#if NUM_AXES < 9
918
+  #undef STEALTHCHOP_W
919
+  #undef CALIBRATION_MEASURE_WMIN
920
+  #undef CALIBRATION_MEASURE_WMAX
921
+  #if NUM_AXES < 8
922
+    #undef STEALTHCHOP_V
923
+    #undef CALIBRATION_MEASURE_VMIN
924
+    #undef CALIBRATION_MEASURE_VMAX
925
+    #if NUM_AXES < 7
926
+      #undef STEALTHCHOP_U
927
+      #undef CALIBRATION_MEASURE_UMIN
928
+      #undef CALIBRATION_MEASURE_UMAX
929
+      #if NUM_AXES < 6
930
+        #undef STEALTHCHOP_K
931
+        #undef CALIBRATION_MEASURE_KMIN
932
+        #undef CALIBRATION_MEASURE_KMAX
933
+        #if NUM_AXES < 5
934
+          #undef STEALTHCHOP_J
935
+          #undef CALIBRATION_MEASURE_JMIN
936
+          #undef CALIBRATION_MEASURE_JMAX
937
+          #if NUM_AXES < 4
938
+            #undef STEALTHCHOP_I
939
+            #undef CALIBRATION_MEASURE_IMIN
940
+            #undef CALIBRATION_MEASURE_IMAX
941
+            #if NUM_AXES < 3
942
+              #undef Z_IDLE_HEIGHT
943
+              #undef STEALTHCHOP_Z
944
+              #undef Z_PROBE_SLED
945
+              #undef Z_SAFE_HOMING
946
+              #undef HOME_Z_FIRST
947
+              #undef HOMING_Z_WITH_PROBE
948
+              #undef ENABLE_LEVELING_FADE_HEIGHT
949
+              #undef NUM_Z_STEPPER_DRIVERS
950
+              #undef CNC_WORKSPACE_PLANES
951
+              #if NUM_AXES < 2
952
+                #undef STEALTHCHOP_Y
953
+              #endif
954
+            #endif
955
+          #endif
941 956
         #endif
942 957
       #endif
943 958
     #endif

+ 254
- 3
Marlin/src/inc/Conditionals_post.h View File

@@ -87,6 +87,19 @@
87 87
 #if HAS_K_AXIS && !defined(AXIS6_NAME)
88 88
   #define AXIS6_NAME 'C'
89 89
 #endif
90
+#if HAS_U_AXIS && !defined(AXIS7_NAME)
91
+  #define AXIS7_NAME 'U'
92
+#endif
93
+#if HAS_V_AXIS && !defined(AXIS8_NAME)
94
+  #define AXIS8_NAME 'V'
95
+#endif
96
+#if HAS_W_AXIS && !defined(AXIS9_NAME)
97
+  #define AXIS9_NAME 'W'
98
+#endif
99
+
100
+#if ANY(AXIS4_ROTATES, AXIS5_ROTATES, AXIS6_ROTATES, AXIS7_ROTATES, AXIS8_ROTATES, AXIS9_ROTATES)
101
+  #define HAS_ROTATIONAL_AXES 1
102
+#endif
90 103
 
91 104
 #define X_MAX_LENGTH (X_MAX_POS - (X_MIN_POS))
92 105
 #if HAS_Y_AXIS
@@ -106,6 +119,15 @@
106 119
 #if HAS_K_AXIS
107 120
   #define K_MAX_LENGTH (K_MAX_POS - (K_MIN_POS))
108 121
 #endif
122
+#if HAS_U_AXIS
123
+  #define U_MAX_LENGTH (U_MAX_POS - (U_MIN_POS))
124
+#endif
125
+#if HAS_V_AXIS
126
+  #define V_MAX_LENGTH (V_MAX_POS - (V_MIN_POS))
127
+#endif
128
+#if HAS_W_AXIS
129
+  #define W_MAX_LENGTH (W_MAX_POS - (W_MIN_POS))
130
+#endif
109 131
 
110 132
 // Defined only if the sanity-check is bypassed
111 133
 #ifndef X_BED_SIZE
@@ -123,6 +145,15 @@
123 145
 #if HAS_K_AXIS && !defined(K_BED_SIZE)
124 146
   #define K_BED_SIZE K_MAX_LENGTH
125 147
 #endif
148
+#if HAS_U_AXIS && !defined(U_BED_SIZE)
149
+  #define U_BED_SIZE U_MAX_LENGTH
150
+#endif
151
+#if HAS_V_AXIS && !defined(V_BED_SIZE)
152
+  #define V_BED_SIZE V_MAX_LENGTH
153
+#endif
154
+#if HAS_W_AXIS && !defined(W_BED_SIZE)
155
+  #define W_BED_SIZE W_MAX_LENGTH
156
+#endif
126 157
 
127 158
 // Require 0,0 bed center for Delta and SCARA
128 159
 #if IS_KINEMATIC
@@ -143,6 +174,15 @@
143 174
 #if HAS_K_AXIS
144 175
   #define _K_HALF_KMAX ((K_BED_SIZE) / 2)
145 176
 #endif
177
+#if HAS_U_AXIS
178
+  #define _U_HALF_UMAX ((U_BED_SIZE) / 2)
179
+#endif
180
+#if HAS_V_AXIS
181
+  #define _V_HALF_VMAX ((V_BED_SIZE) / 2)
182
+#endif
183
+#if HAS_W_AXIS
184
+  #define _W_HALF_WMAX ((W_BED_SIZE) / 2)
185
+#endif
146 186
 
147 187
 #define X_CENTER TERN(BED_CENTER_AT_0_0, 0, _X_HALF_BED)
148 188
 #if HAS_Y_AXIS
@@ -158,6 +198,15 @@
158 198
 #if HAS_K_AXIS
159 199
   #define K_CENTER TERN(BED_CENTER_AT_0_0, 0, _K_HALF_BED)
160 200
 #endif
201
+#if HAS_U_AXIS
202
+  #define U_CENTER TERN(BED_CENTER_AT_0_0, 0, _U_HALF_BED)
203
+#endif
204
+#if HAS_V_AXIS
205
+  #define V_CENTER TERN(BED_CENTER_AT_0_0, 0, _V_HALF_BED)
206
+#endif
207
+#if HAS_W_AXIS
208
+  #define W_CENTER TERN(BED_CENTER_AT_0_0, 0, _W_HALF_BED)
209
+#endif
161 210
 
162 211
 // Get the linear boundaries of the bed
163 212
 #define X_MIN_BED (X_CENTER - _X_HALF_BED)
@@ -178,6 +227,18 @@
178 227
   #define K_MINIM (K_CENTER - _K_HALF_BED_SIZE)
179 228
   #define K_MAXIM (K_MINIM + K_BED_SIZE)
180 229
 #endif
230
+#if HAS_U_AXIS
231
+  #define U_MINIM (U_CENTER - _U_HALF_BED_SIZE)
232
+  #define U_MAXIM (U_MINIM + U_BED_SIZE)
233
+#endif
234
+#if HAS_V_AXIS
235
+  #define V_MINIM (V_CENTER - _V_HALF_BED_SIZE)
236
+  #define V_MAXIM (V_MINIM + V_BED_SIZE)
237
+#endif
238
+#if HAS_W_AXIS
239
+  #define W_MINIM (W_CENTER - _W_HALF_BED_SIZE)
240
+  #define W_MAXIM (W_MINIM + W_BED_SIZE)
241
+#endif
181 242
 
182 243
 /**
183 244
  * Dual X Carriage
@@ -274,6 +335,27 @@
274 335
     #define K_HOME_POS TERN(K_HOME_TO_MIN, K_MIN_POS, K_MAX_POS)
275 336
   #endif
276 337
 #endif
338
+#if HAS_U_AXIS
339
+  #ifdef MANUAL_U_HOME_POS
340
+    #define U_HOME_POS MANUAL_U_HOME_POS
341
+  #else
342
+    #define U_HOME_POS (U_HOME_DIR < 0 ? U_MIN_POS : U_MAX_POS)
343
+  #endif
344
+#endif
345
+#if HAS_V_AXIS
346
+  #ifdef MANUAL_V_HOME_POS
347
+    #define V_HOME_POS MANUAL_V_HOME_POS
348
+  #else
349
+    #define V_HOME_POS (V_HOME_DIR < 0 ? V_MIN_POS : V_MAX_POS)
350
+  #endif
351
+#endif
352
+#if HAS_W_AXIS
353
+  #ifdef MANUAL_W_HOME_POS
354
+    #define W_HOME_POS MANUAL_W_HOME_POS
355
+  #else
356
+    #define W_HOME_POS (W_HOME_DIR < 0 ? W_MIN_POS : W_MAX_POS)
357
+  #endif
358
+#endif
277 359
 
278 360
 /**
279 361
  * If DELTA_HEIGHT isn't defined use the old setting
@@ -1440,6 +1522,15 @@
1440 1522
   #if ENABLED(USE_KMAX_PLUG)
1441 1523
     #define ENDSTOPPULLUP_KMAX
1442 1524
   #endif
1525
+  #if ENABLED(USE_UMAX_PLUG)
1526
+    #define ENDSTOPPULLUP_UMAX
1527
+  #endif
1528
+  #if ENABLED(USE_VMAX_PLUG)
1529
+    #define ENDSTOPPULLUP_VMAX
1530
+  #endif
1531
+  #if ENABLED(USE_WMAX_PLUG)
1532
+    #define ENDSTOPPULLUP_WMAX
1533
+  #endif
1443 1534
   #if ENABLED(USE_XMIN_PLUG)
1444 1535
     #define ENDSTOPPULLUP_XMIN
1445 1536
   #endif
@@ -1458,6 +1549,15 @@
1458 1549
   #if ENABLED(USE_KMIN_PLUG)
1459 1550
     #define ENDSTOPPULLUP_KMIN
1460 1551
   #endif
1552
+  #if ENABLED(USE_UMIN_PLUG)
1553
+    #define ENDSTOPPULLUP_UMIN
1554
+  #endif
1555
+  #if ENABLED(USE_VMIN_PLUG)
1556
+    #define ENDSTOPPULLUP_VMIN
1557
+  #endif
1558
+  #if ENABLED(USE_WMIN_PLUG)
1559
+    #define ENDSTOPPULLUP_WMIN
1560
+  #endif
1461 1561
 #endif
1462 1562
 
1463 1563
 /**
@@ -1680,6 +1780,66 @@
1680 1780
   #undef DISABLE_INACTIVE_K
1681 1781
 #endif
1682 1782
 
1783
+#if HAS_U_AXIS
1784
+  #if PIN_EXISTS(U_ENABLE) || AXIS_IS_L64XX(U) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(U))
1785
+    #define HAS_U_ENABLE 1
1786
+  #endif
1787
+  #if PIN_EXISTS(U_DIR)
1788
+    #define HAS_U_DIR 1
1789
+  #endif
1790
+  #if PIN_EXISTS(U_STEP)
1791
+    #define HAS_U_STEP 1
1792
+  #endif
1793
+  #if PIN_EXISTS(U_MS1)
1794
+    #define HAS_U_MS_PINS 1
1795
+  #endif
1796
+  #if !defined(DISABLE_INACTIVE_U) && ENABLED(DISABLE_U)
1797
+    #define DISABLE_INACTIVE_U 1
1798
+  #endif
1799
+#else
1800
+  #undef DISABLE_INACTIVE_U
1801
+#endif
1802
+
1803
+#if HAS_V_AXIS
1804
+  #if PIN_EXISTS(V_ENABLE) || AXIS_IS_L64XX(V) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(V))
1805
+    #define HAS_V_ENABLE 1
1806
+  #endif
1807
+  #if PIN_EXISTS(V_DIR)
1808
+    #define HAS_V_DIR 1
1809
+  #endif
1810
+  #if PIN_EXISTS(V_STEP)
1811
+    #define HAS_V_STEP 1
1812
+  #endif
1813
+  #if PIN_EXISTS(V_MS1)
1814
+    #define HAS_V_MS_PINS 1
1815
+  #endif
1816
+  #if !defined(DISABLE_INACTIVE_V) && ENABLED(DISABLE_V)
1817
+    #define DISABLE_INACTIVE_V 1
1818
+  #endif
1819
+#else
1820
+  #undef DISABLE_INACTIVE_V
1821
+#endif
1822
+
1823
+#if HAS_W_AXIS
1824
+  #if PIN_EXISTS(W_ENABLE) || AXIS_IS_L64XX(W) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(W))
1825
+    #define HAS_W_ENABLE 1
1826
+  #endif
1827
+  #if PIN_EXISTS(W_DIR)
1828
+    #define HAS_W_DIR 1
1829
+  #endif
1830
+  #if PIN_EXISTS(W_STEP)
1831
+    #define HAS_W_STEP 1
1832
+  #endif
1833
+  #if PIN_EXISTS(W_MS1)
1834
+    #define HAS_W_MS_PINS 1
1835
+  #endif
1836
+  #if !defined(DISABLE_INACTIVE_W) && ENABLED(DISABLE_W)
1837
+    #define DISABLE_INACTIVE_W 1
1838
+  #endif
1839
+#else
1840
+  #undef DISABLE_INACTIVE_W
1841
+#endif
1842
+
1683 1843
 // Extruder steppers and solenoids
1684 1844
 #if HAS_EXTRUDERS
1685 1845
 
@@ -1848,7 +2008,7 @@
1848 2008
 //
1849 2009
 
1850 2010
 #if HAS_TRINAMIC_CONFIG
1851
-  #if ANY(STEALTHCHOP_E, STEALTHCHOP_XY, STEALTHCHOP_Z, STEALTHCHOP_I, STEALTHCHOP_J, STEALTHCHOP_K)
2011
+  #if ANY(STEALTHCHOP_E, STEALTHCHOP_XY, STEALTHCHOP_Z, STEALTHCHOP_I, STEALTHCHOP_J, STEALTHCHOP_K, STEALTHCHOP_U, STEALTHCHOP_V, STEALTHCHOP_W)
1852 2012
     #define STEALTHCHOP_ENABLED 1
1853 2013
   #endif
1854 2014
   #if EITHER(SENSORLESS_HOMING, SENSORLESS_PROBING)
@@ -1937,6 +2097,15 @@
1937 2097
         #define Y2_SLAVE_ADDRESS 0
1938 2098
       #endif
1939 2099
     #endif
2100
+    #if HAS_U_AXIS
2101
+      #define U_SPI_SENSORLESS U_SENSORLESS
2102
+    #endif
2103
+    #if HAS_V_AXIS
2104
+      #define V_SPI_SENSORLESS V_SENSORLESS
2105
+    #endif
2106
+    #if HAS_W_AXIS
2107
+      #define W_SPI_SENSORLESS W_SENSORLESS
2108
+    #endif
1940 2109
   #endif
1941 2110
 
1942 2111
   #if AXIS_IS_TMC(Z)
@@ -2074,6 +2243,69 @@
2074 2243
     #endif
2075 2244
   #endif
2076 2245
 
2246
+  #if AXIS_IS_TMC(U)
2247
+    #if defined(U_STALL_SENSITIVITY) && AXIS_HAS_STALLGUARD(U)
2248
+      #define U_SENSORLESS 1
2249
+    #endif
2250
+    #if AXIS_HAS_STEALTHCHOP(U)
2251
+      #define U_HAS_STEALTHCHOP 1
2252
+    #endif
2253
+    #if ENABLED(SPI_ENDSTOPS)
2254
+      #define U_SPI_SENSORLESS U_SENSORLESS
2255
+    #endif
2256
+    #ifndef U_INTERPOLATE
2257
+      #define U_INTERPOLATE INTERPOLATE
2258
+    #endif
2259
+    #ifndef U_HOLD_MULTIPLIER
2260
+      #define U_HOLD_MULTIPLIER HOLD_MULTIPLIER
2261
+    #endif
2262
+    #ifndef U_SLAVE_ADDRESS
2263
+      #define U_SLAVE_ADDRESS 0
2264
+    #endif
2265
+  #endif
2266
+
2267
+  #if AXIS_IS_TMC(V)
2268
+    #if defined(V_STALL_SENSITIVITY) && AXIS_HAS_STALLGUARD(V)
2269
+      #define V_SENSORLESS 1
2270
+    #endif
2271
+    #if AXIS_HAS_STEALTHCHOP(V)
2272
+      #define V_HAS_STEALTHCHOP 1
2273
+    #endif
2274
+    #if ENABLED(SPI_ENDSTOPS)
2275
+      #define V_SPI_SENSORLESS V_SENSORLESS
2276
+    #endif
2277
+    #ifndef V_INTERPOLATE
2278
+      #define V_INTERPOLATE INTERPOLATE
2279
+    #endif
2280
+    #ifndef V_HOLD_MULTIPLIER
2281
+      #define V_HOLD_MULTIPLIER HOLD_MULTIPLIER
2282
+    #endif
2283
+    #ifndef V_SLAVE_ADDRESS
2284
+      #define V_SLAVE_ADDRESS 0
2285
+    #endif
2286
+  #endif
2287
+
2288
+  #if AXIS_IS_TMC(W)
2289
+    #if defined(W_STALL_SENSITIVITY) && AXIS_HAS_STALLGUARD(W)
2290
+      #define W_SENSORLESS 1
2291
+    #endif
2292
+    #if AXIS_HAS_STEALTHCHOP(W)
2293
+      #define W_HAS_STEALTHCHOP 1
2294
+    #endif
2295
+    #if ENABLED(SPI_ENDSTOPS)
2296
+      #define W_SPI_SENSORLESS W_SENSORLESS
2297
+    #endif
2298
+    #ifndef W_INTERPOLATE
2299
+      #define W_INTERPOLATE INTERPOLATE
2300
+    #endif
2301
+    #ifndef W_HOLD_MULTIPLIER
2302
+      #define W_HOLD_MULTIPLIER HOLD_MULTIPLIER
2303
+    #endif
2304
+    #ifndef W_SLAVE_ADDRESS
2305
+      #define W_SLAVE_ADDRESS 0
2306
+    #endif
2307
+  #endif
2308
+
2077 2309
   #if AXIS_IS_TMC(E0)
2078 2310
     #if AXIS_HAS_STEALTHCHOP(E0)
2079 2311
       #define E0_HAS_STEALTHCHOP 1
@@ -2215,6 +2447,7 @@
2215 2447
 #define ANY_SERIAL_IS(N) (  CONF_SERIAL_IS(N) \
2216 2448
                          || TMC_UART_IS(X,  N) || TMC_UART_IS(Y , N) || TMC_UART_IS(Z , N) \
2217 2449
                          || TMC_UART_IS(I,  N) || TMC_UART_IS(J , N) || TMC_UART_IS(K , N) \
2450
+                         || TMC_UART_IS(U,  N) || TMC_UART_IS(V , N) || TMC_UART_IS(W , N) \
2218 2451
                          || TMC_UART_IS(X2, N) || TMC_UART_IS(Y2, N) || TMC_UART_IS(Z2, N) || TMC_UART_IS(Z3, N) || TMC_UART_IS(Z4, N) \
2219 2452
                          || TMC_UART_IS(E0, N) || TMC_UART_IS(E1, N) || TMC_UART_IS(E2, N) || TMC_UART_IS(E3, N) || TMC_UART_IS(E4, N) )
2220 2453
 
@@ -2349,6 +2582,24 @@
2349 2582
 #if _HAS_STOP(K,MAX)
2350 2583
   #define HAS_K_MAX 1
2351 2584
 #endif
2585
+#if _HAS_STOP(U,MIN)
2586
+  #define HAS_U_MIN 1
2587
+#endif
2588
+#if _HAS_STOP(U,MAX)
2589
+  #define HAS_U_MAX 1
2590
+#endif
2591
+#if _HAS_STOP(V,MIN)
2592
+  #define HAS_V_MIN 1
2593
+#endif
2594
+#if _HAS_STOP(V,MAX)
2595
+  #define HAS_V_MAX 1
2596
+#endif
2597
+#if _HAS_STOP(W,MIN)
2598
+  #define HAS_W_MIN 1
2599
+#endif
2600
+#if _HAS_STOP(W,MAX)
2601
+  #define HAS_W_MAX 1
2602
+#endif
2352 2603
 #if PIN_EXISTS(X2_MIN)
2353 2604
   #define HAS_X2_MIN 1
2354 2605
 #endif
@@ -2849,7 +3100,7 @@
2849 3100
 #if HAS_EXTRUDERS && PIN_EXISTS(MOTOR_CURRENT_PWM_E)
2850 3101
   #define HAS_MOTOR_CURRENT_PWM_E 1
2851 3102
 #endif
2852
-#if HAS_MOTOR_CURRENT_PWM_E || ANY_PIN(MOTOR_CURRENT_PWM_X, MOTOR_CURRENT_PWM_Y, MOTOR_CURRENT_PWM_XY, MOTOR_CURRENT_PWM_Z, MOTOR_CURRENT_PWM_I, MOTOR_CURRENT_PWM_J, MOTOR_CURRENT_PWM_K)
3103
+#if HAS_MOTOR_CURRENT_PWM_E || ANY_PIN(MOTOR_CURRENT_PWM_X, MOTOR_CURRENT_PWM_Y, MOTOR_CURRENT_PWM_XY, MOTOR_CURRENT_PWM_Z, MOTOR_CURRENT_PWM_I, MOTOR_CURRENT_PWM_J, MOTOR_CURRENT_PWM_K, MOTOR_CURRENT_PWM_U, MOTOR_CURRENT_PWM_V, MOTOR_CURRENT_PWM_W)
2853 3104
   #define HAS_MOTOR_CURRENT_PWM 1
2854 3105
 #endif
2855 3106
 
@@ -2859,7 +3110,7 @@
2859 3110
 #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)
2860 3111
   #define HAS_SOME_E_MS_PINS 1
2861 3112
 #endif
2862
-#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)
3113
+#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_U_MS_PINS, HAS_V_MS_PINS, HAS_W_MS_PINS, HAS_SOME_E_MS_PINS)
2863 3114
   #define HAS_MICROSTEPS 1
2864 3115
 #endif
2865 3116
 

+ 233
- 37
Marlin/src/inc/SanityCheck.h View File

@@ -35,8 +35,8 @@
35 35
 #endif
36 36
 
37 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 ")
38
+#define _NUM_AXES_STR NUM_AXIS_GANG("X ", "Y ", "Z ", "I ", "J ", "K ", "U ", "V ", "W ")
39
+#define _LOGICAL_AXES_STR LOGICAL_AXIS_GANG("E ", "X ", "Y ", "Z ", "I ", "J ", "K ", "U ", "V ", "W ")
40 40
 
41 41
 // Make sure macros aren't borked
42 42
 #define TEST1
@@ -617,6 +617,8 @@
617 617
   #error "Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS is now just Z_STEPPER_ALIGN_STEPPER_XY."
618 618
 #elif defined(DWIN_CREALITY_LCD_ENHANCED)
619 619
   #error "DWIN_CREALITY_LCD_ENHANCED is now DWIN_LCD_PROUI."
620
+#elif defined(LINEAR_AXES)
621
+  #error "LINEAR_AXES is now NUM_AXES (to account for rotational axes)."
620 622
 #endif
621 623
 
622 624
 constexpr float arm[] = AXIS_RELATIVE_MODES;
@@ -798,6 +800,12 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS
798 800
   #error "Enable only one of ENDSTOPPULLUP_J_MAX or ENDSTOPPULLDOWN_J_MAX."
799 801
 #elif BOTH(ENDSTOPPULLUP_KMAX, ENDSTOPPULLDOWN_KMAX)
800 802
   #error "Enable only one of ENDSTOPPULLUP_K_MAX or ENDSTOPPULLDOWN_K_MAX."
803
+#elif BOTH(ENDSTOPPULLUP_UMAX, ENDSTOPPULLDOWN_UMAX)
804
+  #error "Enable only one of ENDSTOPPULLUP_U_MAX or ENDSTOPPULLDOWN_U_MAX."
805
+#elif BOTH(ENDSTOPPULLUP_VMAX, ENDSTOPPULLDOWN_VMAX)
806
+  #error "Enable only one of ENDSTOPPULLUP_V_MAX or ENDSTOPPULLDOWN_V_MAX."
807
+#elif BOTH(ENDSTOPPULLUP_WMAX, ENDSTOPPULLDOWN_WMAX)
808
+  #error "Enable only one of ENDSTOPPULLUP_W_MAX or ENDSTOPPULLDOWN_W_MAX."
801 809
 #elif BOTH(ENDSTOPPULLUP_XMIN, ENDSTOPPULLDOWN_XMIN)
802 810
   #error "Enable only one of ENDSTOPPULLUP_X_MIN or ENDSTOPPULLDOWN_X_MIN."
803 811
 #elif BOTH(ENDSTOPPULLUP_YMIN, ENDSTOPPULLDOWN_YMIN)
@@ -810,6 +818,12 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS
810 818
   #error "Enable only one of ENDSTOPPULLUP_J_MIN or ENDSTOPPULLDOWN_J_MIN."
811 819
 #elif BOTH(ENDSTOPPULLUP_KMIN, ENDSTOPPULLDOWN_KMIN)
812 820
   #error "Enable only one of ENDSTOPPULLUP_K_MIN or ENDSTOPPULLDOWN_K_MIN."
821
+#elif BOTH(ENDSTOPPULLUP_UMIN, ENDSTOPPULLDOWN_UMIN)
822
+  #error "Enable only one of ENDSTOPPULLUP_U_MIN or ENDSTOPPULLDOWN_U_MIN."
823
+#elif BOTH(ENDSTOPPULLUP_VMIN, ENDSTOPPULLDOWN_VMIN)
824
+  #error "Enable only one of ENDSTOPPULLUP_V_MIN or ENDSTOPPULLDOWN_V_MIN."
825
+#elif BOTH(ENDSTOPPULLUP_WMIN, ENDSTOPPULLDOWN_WMIN)
826
+  #error "Enable only one of ENDSTOPPULLUP_W_MIN or ENDSTOPPULLDOWN_W_MIN."
813 827
 #endif
814 828
 
815 829
 /**
@@ -1417,16 +1431,18 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS
1417 1431
 #endif
1418 1432
 
1419 1433
 /**
1420
- * Features that require a min/max/specific LINEAR_AXES
1434
+ * Features that require a min/max/specific NUM_AXES
1421 1435
  */
1422 1436
 #if HAS_LEVELING && !HAS_Z_AXIS
1423 1437
   #error "Leveling in Marlin requires three or more axes, with Z as the vertical axis."
1424 1438
 #elif ENABLED(CNC_WORKSPACE_PLANES) && !HAS_Z_AXIS
1425
-  #error "CNC_WORKSPACE_PLANES currently requires LINEAR_AXES >= 3"
1426
-#elif ENABLED(DIRECT_STEPPING) && LINEAR_AXES > XYZ
1427
-  #error "DIRECT_STEPPING currently requires LINEAR_AXES 3"
1428
-#elif ENABLED(FOAMCUTTER_XYUV) && LINEAR_AXES < 5
1429
-  #error "FOAMCUTTER_XYUV requires LINEAR_AXES >= 5."
1439
+  #error "CNC_WORKSPACE_PLANES currently requires NUM_AXES >= 3"
1440
+#elif ENABLED(DIRECT_STEPPING) && NUM_AXES > XYZ
1441
+  #error "DIRECT_STEPPING currently requires NUM_AXES 3"
1442
+#elif ENABLED(FOAMCUTTER_XYUV) && NUM_AXES < 5
1443
+  #error "FOAMCUTTER_XYUV requires NUM_AXES >= 5."
1444
+#elif ENABLED(LINEAR_ADVANCE) && HAS_I_AXIS
1445
+  #error "LINEAR_ADVANCE currently requires NUM_AXES <= 3."
1430 1446
 #endif
1431 1447
 
1432 1448
 /**
@@ -1434,33 +1450,76 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS
1434 1450
  */
1435 1451
 #if HAS_I_AXIS
1436 1452
   #if !defined(I_MIN_POS) || !defined(I_MAX_POS)
1437
-    #error "I_MIN_POS and I_MAX_POS are required with LINEAR_AXES >= 4."
1453
+    #error "I_MIN_POS and I_MAX_POS are required with NUM_AXES >= 4."
1438 1454
   #elif !defined(I_HOME_DIR)
1439
-    #error "I_HOME_DIR is required with LINEAR_AXES >= 4."
1455
+    #error "I_HOME_DIR is required with NUM_AXES >= 4."
1440 1456
   #elif HAS_I_ENABLE && !defined(I_ENABLE_ON)
1441
-    #error "I_ENABLE_ON is required for your I driver with LINEAR_AXES >= 4."
1457
+    #error "I_ENABLE_ON is required for your I driver with NUM_AXES >= 4."
1442 1458
   #endif
1443 1459
 #endif
1444 1460
 #if HAS_J_AXIS
1445 1461
   #if AXIS5_NAME == AXIS4_NAME
1446 1462
     #error "AXIS5_NAME must be unique."
1463
+  #elif ENABLED(AXIS5_ROTATES) && DISABLED(AXIS4_ROTATES)
1464
+    #error "AXIS5_ROTATES requires AXIS4_ROTATES."
1447 1465
   #elif !defined(J_MIN_POS) || !defined(J_MAX_POS)
1448
-    #error "J_MIN_POS and J_MAX_POS are required with LINEAR_AXES >= 5."
1466
+    #error "J_MIN_POS and J_MAX_POS are required with NUM_AXES >= 5."
1449 1467
   #elif !defined(J_HOME_DIR)
1450
-    #error "J_HOME_DIR is required with LINEAR_AXES >= 5."
1468
+    #error "J_HOME_DIR is required with NUM_AXES >= 5."
1451 1469
   #elif HAS_J_ENABLE && !defined(J_ENABLE_ON)
1452
-    #error "J_ENABLE_ON is required for your J driver with LINEAR_AXES >= 5."
1470
+    #error "J_ENABLE_ON is required for your J driver with NUM_AXES >= 5."
1453 1471
   #endif
1454 1472
 #endif
1455 1473
 #if HAS_K_AXIS
1456 1474
   #if AXIS6_NAME == AXIS5_NAME || AXIS6_NAME == AXIS4_NAME
1457 1475
     #error "AXIS6_NAME must be unique."
1476
+  #elif ENABLED(AXIS6_ROTATES) && DISABLED(AXIS5_ROTATES)
1477
+    #error "AXIS6_ROTATES requires AXIS5_ROTATES."
1458 1478
   #elif !defined(K_MIN_POS) || !defined(K_MAX_POS)
1459
-    #error "K_MIN_POS and K_MAX_POS are required with LINEAR_AXES >= 6."
1479
+    #error "K_MIN_POS and K_MAX_POS are required with NUM_AXES >= 6."
1460 1480
   #elif !defined(K_HOME_DIR)
1461
-    #error "K_HOME_DIR is required with LINEAR_AXES >= 6."
1481
+    #error "K_HOME_DIR is required with NUM_AXES >= 6."
1462 1482
   #elif HAS_K_ENABLE && !defined(K_ENABLE_ON)
1463
-    #error "K_ENABLE_ON is required for your K driver with LINEAR_AXES >= 6."
1483
+    #error "K_ENABLE_ON is required for your K driver with NUM_AXES >= 6."
1484
+  #endif
1485
+#endif
1486
+#if HAS_U_AXIS
1487
+  #if AXIS7_NAME == AXIS6_NAME || AXIS7_NAME == AXIS5_NAME || AXIS7_NAME == AXIS4_NAME
1488
+    #error "AXIS7_NAME must be unique."
1489
+  #elif ENABLED(AXIS7_ROTATES) && DISABLED(AXIS6_ROTATES)
1490
+    #error "AXIS7_ROTATES requires AXIS6_ROTATES."
1491
+  #elif !defined(U_MIN_POS) || !defined(U_MAX_POS)
1492
+    #error "U_MIN_POS and U_MAX_POS are required with NUM_AXES >= 7."
1493
+  #elif !defined(U_HOME_DIR)
1494
+    #error "U_HOME_DIR is required with NUM_AXES >= 7."
1495
+  #elif HAS_U_ENABLE && !defined(U_ENABLE_ON)
1496
+    #error "U_ENABLE_ON is required for your U driver with NUM_AXES >= 7."
1497
+  #endif
1498
+#endif
1499
+#if HAS_V_AXIS
1500
+  #if AXIS8_NAME == AXIS7_NAME || AXIS8_NAME == AXIS6_NAME || AXIS8_NAME == AXIS5_NAME || AXIS8_NAME == AXIS4_NAME
1501
+    #error "AXIS8_NAME must be unique."
1502
+  #elif ENABLED(AXIS8_ROTATES) && DISABLED(AXIS7_ROTATES)
1503
+    #error "AXIS8_ROTATES requires AXIS7_ROTATES."
1504
+  #elif !defined(V_MIN_POS) || !defined(V_MAX_POS)
1505
+    #error "V_MIN_POS and V_MAX_POS are required with NUM_AXES >= 8."
1506
+  #elif !defined(V_HOME_DIR)
1507
+    #error "V_HOME_DIR is required with NUM_AXES >= 8."
1508
+  #elif HAS_V_ENABLE && !defined(V_ENABLE_ON)
1509
+    #error "V_ENABLE_ON is required for your V driver with NUM_AXES >= 8."
1510
+  #endif
1511
+#endif
1512
+#if HAS_W_AXIS
1513
+  #if AXIS9_NAME == AXIS8_NAME || AXIS9_NAME == AXIS7_NAME || AXIS9_NAME == AXIS6_NAME || AXIS9_NAME == AXIS5_NAME || AXIS9_NAME == AXIS4_NAME
1514
+    #error "AXIS9_NAME must be unique."
1515
+  #elif ENABLED(AXIS9_ROTATES) && DISABLED(AXIS8_ROTATES)
1516
+    #error "AXIS9_ROTATES requires AXIS8_ROTATES."
1517
+  #elif !defined(W_MIN_POS) || !defined(W_MAX_POS)
1518
+    #error "W_MIN_POS and W_MAX_POS are required with NUM_AXES >= 9."
1519
+  #elif !defined(W_HOME_DIR)
1520
+    #error "W_HOME_DIR is required with NUM_AXES >= 9."
1521
+  #elif HAS_W_ENABLE && !defined(W_ENABLE_ON)
1522
+    #error "W_ENABLE_ON is required for your W driver with NUM_AXES >= 9."
1464 1523
   #endif
1465 1524
 #endif
1466 1525
 
@@ -1850,49 +1909,61 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS
1850 1909
   #error "Required setting HOMING_BUMP_DIVISOR is missing!"
1851 1910
 #else
1852 1911
   constexpr float hbm[] = HOMING_BUMP_MM, hbd[] = HOMING_BUMP_DIVISOR;
1853
-  static_assert(COUNT(hbm) == LINEAR_AXES, "HOMING_BUMP_MM must have " _LINEAR_AXES_STR "elements (and no others).");
1854
-  LINEAR_AXIS_CODE(
1912
+  static_assert(COUNT(hbm) == NUM_AXES, "HOMING_BUMP_MM must have " _NUM_AXES_STR "elements (and no others).");
1913
+  NUM_AXIS_CODE(
1855 1914
     static_assert(hbm[X_AXIS] >= 0, "HOMING_BUMP_MM.X must be greater than or equal to 0."),
1856 1915
     static_assert(hbm[Y_AXIS] >= 0, "HOMING_BUMP_MM.Y must be greater than or equal to 0."),
1857 1916
     static_assert(hbm[Z_AXIS] >= 0, "HOMING_BUMP_MM.Z must be greater than or equal to 0."),
1858 1917
     static_assert(hbm[I_AXIS] >= 0, "HOMING_BUMP_MM.I must be greater than or equal to 0."),
1859 1918
     static_assert(hbm[J_AXIS] >= 0, "HOMING_BUMP_MM.J must be greater than or equal to 0."),
1860
-    static_assert(hbm[K_AXIS] >= 0, "HOMING_BUMP_MM.K must be greater than or equal to 0.")
1919
+    static_assert(hbm[K_AXIS] >= 0, "HOMING_BUMP_MM.K must be greater than or equal to 0."),
1920
+    static_assert(hbm[U_AXIS] >= 0, "HOMING_BUMP_MM.U must be greater than or equal to 0."),
1921
+    static_assert(hbm[V_AXIS] >= 0, "HOMING_BUMP_MM.V must be greater than or equal to 0."),
1922
+    static_assert(hbm[W_AXIS] >= 0, "HOMING_BUMP_MM.W must be greater than or equal to 0.")
1861 1923
   );
1862
-  static_assert(COUNT(hbd) == LINEAR_AXES, "HOMING_BUMP_DIVISOR must have " _LINEAR_AXES_STR "elements (and no others).");
1863
-  LINEAR_AXIS_CODE(
1924
+  static_assert(COUNT(hbd) == NUM_AXES, "HOMING_BUMP_DIVISOR must have " _NUM_AXES_STR "elements (and no others).");
1925
+  NUM_AXIS_CODE(
1864 1926
     static_assert(hbd[X_AXIS] >= 1, "HOMING_BUMP_DIVISOR.X must be greater than or equal to 1."),
1865 1927
     static_assert(hbd[Y_AXIS] >= 1, "HOMING_BUMP_DIVISOR.Y must be greater than or equal to 1."),
1866 1928
     static_assert(hbd[Z_AXIS] >= 1, "HOMING_BUMP_DIVISOR.Z must be greater than or equal to 1."),
1867 1929
     static_assert(hbd[I_AXIS] >= 1, "HOMING_BUMP_DIVISOR.I must be greater than or equal to 1."),
1868 1930
     static_assert(hbd[J_AXIS] >= 1, "HOMING_BUMP_DIVISOR.J must be greater than or equal to 1."),
1869
-    static_assert(hbd[K_AXIS] >= 1, "HOMING_BUMP_DIVISOR.K must be greater than or equal to 1.")
1931
+    static_assert(hbd[K_AXIS] >= 1, "HOMING_BUMP_DIVISOR.K must be greater than or equal to 1."),
1932
+    static_assert(hbd[U_AXIS] >= 1, "HOMING_BUMP_DIVISOR.U must be greater than or equal to 1."),
1933
+    static_assert(hbd[V_AXIS] >= 1, "HOMING_BUMP_DIVISOR.V must be greater than or equal to 1."),
1934
+    static_assert(hbd[W_AXIS] >= 1, "HOMING_BUMP_DIVISOR.W must be greater than or equal to 1.")
1870 1935
   );
1871 1936
 #endif
1872 1937
 
1873 1938
 #ifdef HOMING_BACKOFF_POST_MM
1874 1939
   constexpr float hbp[] = HOMING_BACKOFF_POST_MM;
1875
-  static_assert(COUNT(hbp) == LINEAR_AXES, "HOMING_BACKOFF_POST_MM must have " _LINEAR_AXES_STR "elements (and no others).");
1876
-  LINEAR_AXIS_CODE(
1940
+  static_assert(COUNT(hbp) == NUM_AXES, "HOMING_BACKOFF_POST_MM must have " _NUM_AXES_STR "elements (and no others).");
1941
+  NUM_AXIS_CODE(
1877 1942
     static_assert(hbp[X_AXIS] >= 0, "HOMING_BACKOFF_POST_MM.X must be greater than or equal to 0."),
1878 1943
     static_assert(hbp[Y_AXIS] >= 0, "HOMING_BACKOFF_POST_MM.Y must be greater than or equal to 0."),
1879 1944
     static_assert(hbp[Z_AXIS] >= 0, "HOMING_BACKOFF_POST_MM.Z must be greater than or equal to 0."),
1880 1945
     static_assert(hbp[I_AXIS] >= 0, "HOMING_BACKOFF_POST_MM.I must be greater than or equal to 0."),
1881 1946
     static_assert(hbp[J_AXIS] >= 0, "HOMING_BACKOFF_POST_MM.J must be greater than or equal to 0."),
1882
-    static_assert(hbp[K_AXIS] >= 0, "HOMING_BACKOFF_POST_MM.K must be greater than or equal to 0.")
1947
+    static_assert(hbp[K_AXIS] >= 0, "HOMING_BACKOFF_POST_MM.K must be greater than or equal to 0."),
1948
+    static_assert(hbp[U_AXIS] >= 0, "HOMING_BACKOFF_POST_MM.U must be greater than or equal to 0."),
1949
+    static_assert(hbp[V_AXIS] >= 0, "HOMING_BACKOFF_POST_MM.V must be greater than or equal to 0."),
1950
+    static_assert(hbp[W_AXIS] >= 0, "HOMING_BACKOFF_POST_MM.W must be greater than or equal to 0.")
1883 1951
   );
1884 1952
 #endif
1885 1953
 
1886 1954
 #ifdef SENSORLESS_BACKOFF_MM
1887 1955
   constexpr float sbm[] = SENSORLESS_BACKOFF_MM;
1888
-  static_assert(COUNT(sbm) == LINEAR_AXES, "SENSORLESS_BACKOFF_MM must have " _LINEAR_AXES_STR "elements (and no others).");
1889
-  LINEAR_AXIS_CODE(
1956
+  static_assert(COUNT(sbm) == NUM_AXES, "SENSORLESS_BACKOFF_MM must have " _NUM_AXES_STR "elements (and no others).");
1957
+  NUM_AXIS_CODE(
1890 1958
     static_assert(sbm[X_AXIS] >= 0, "SENSORLESS_BACKOFF_MM.X must be greater than or equal to 0."),
1891 1959
     static_assert(sbm[Y_AXIS] >= 0, "SENSORLESS_BACKOFF_MM.Y must be greater than or equal to 0."),
1892 1960
     static_assert(sbm[Z_AXIS] >= 0, "SENSORLESS_BACKOFF_MM.Z must be greater than or equal to 0."),
1893 1961
     static_assert(sbm[I_AXIS] >= 0, "SENSORLESS_BACKOFF_MM.I must be greater than or equal to 0."),
1894 1962
     static_assert(sbm[J_AXIS] >= 0, "SENSORLESS_BACKOFF_MM.J must be greater than or equal to 0."),
1895
-    static_assert(sbm[K_AXIS] >= 0, "SENSORLESS_BACKOFF_MM.K must be greater than or equal to 0.")
1963
+    static_assert(sbm[K_AXIS] >= 0, "SENSORLESS_BACKOFF_MM.K must be greater than or equal to 0."),
1964
+    static_assert(sbm[U_AXIS] >= 0, "SENSORLESS_BACKOFF_MM.U must be greater than or equal to 0."),
1965
+    static_assert(sbm[V_AXIS] >= 0, "SENSORLESS_BACKOFF_MM.V must be greater than or equal to 0."),
1966
+    static_assert(sbm[W_AXIS] >= 0, "SENSORLESS_BACKOFF_MM.W must be greater than or equal to 0.")
1896 1967
   );
1897 1968
 #endif
1898 1969
 
@@ -1915,9 +1986,9 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS
1915 1986
 /**
1916 1987
  * Make sure DISABLE_[XYZ] compatible with selected homing options
1917 1988
  */
1918
-#if ANY(DISABLE_X, DISABLE_Y, DISABLE_Z, DISABLE_I, DISABLE_J, DISABLE_K)
1989
+#if ANY(DISABLE_X, DISABLE_Y, DISABLE_Z, DISABLE_I, DISABLE_J, DISABLE_K, DISABLE_U, DISABLE_V, DISABLE_W)
1919 1990
   #if EITHER(HOME_AFTER_DEACTIVATE, Z_SAFE_HOMING)
1920
-    #error "DISABLE_[XYZIJK] is not compatible with HOME_AFTER_DEACTIVATE or Z_SAFE_HOMING."
1991
+    #error "DISABLE_[XYZIJKUVW] is not compatible with HOME_AFTER_DEACTIVATE or Z_SAFE_HOMING."
1921 1992
   #endif
1922 1993
 #endif
1923 1994
 
@@ -2431,7 +2502,9 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS
2431 2502
 #define _PLUG_UNUSED_TEST(A,P) (DISABLED(USE_##P##MIN_PLUG, USE_##P##MAX_PLUG) \
2432 2503
   && !(ENABLED(A##_DUAL_ENDSTOPS) && WITHIN(A##2_USE_ENDSTOP, _##P##MAX_, _##P##MIN_)) \
2433 2504
   && !(ENABLED(A##_MULTI_ENDSTOPS) && WITHIN(A##2_USE_ENDSTOP, _##P##MAX_, _##P##MIN_)) )
2434
-#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) ) )
2505
+#define _AXIS_PLUG_UNUSED_TEST(A) (1 NUM_AXIS_GANG(&& _PLUG_UNUSED_TEST(A,X), && _PLUG_UNUSED_TEST(A,Y), && _PLUG_UNUSED_TEST(A,Z), \
2506
+                                                      && _PLUG_UNUSED_TEST(A,I), && _PLUG_UNUSED_TEST(A,J), && _PLUG_UNUSED_TEST(A,K), \
2507
+                                                      && _PLUG_UNUSED_TEST(A,U), && _PLUG_UNUSED_TEST(A,V), && _PLUG_UNUSED_TEST(A,W) ) )
2435 2508
 
2436 2509
 // A machine with endstops must have a minimum of 3
2437 2510
 #if HAS_ENDSTOPS
@@ -2453,6 +2526,15 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS
2453 2526
   #if HAS_K_AXIS && _AXIS_PLUG_UNUSED_TEST(K)
2454 2527
     #error "You must enable USE_KMIN_PLUG or USE_KMAX_PLUG."
2455 2528
   #endif
2529
+  #if HAS_U_AXIS && _AXIS_PLUG_UNUSED_TEST(U)
2530
+    #error "You must enable USE_UMIN_PLUG or USE_UMAX_PLUG."
2531
+  #endif
2532
+  #if HAS_V_AXIS && _AXIS_PLUG_UNUSED_TEST(V)
2533
+    #error "You must enable USE_VMIN_PLUG or USE_VMAX_PLUG."
2534
+  #endif
2535
+  #if HAS_W_AXIS && _AXIS_PLUG_UNUSED_TEST(W)
2536
+    #error "You must enable USE_WMIN_PLUG or USE_WMAX_PLUG."
2537
+  #endif
2456 2538
 
2457 2539
   // Delta and Cartesian use 3 homing endstops
2458 2540
   #if NONE(IS_SCARA, SPI_ENDSTOPS)
@@ -2476,6 +2558,18 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS
2476 2558
       #error "Enable USE_KMIN_PLUG when homing K to MIN."
2477 2559
     #elif HAS_K_AXIS && K_HOME_TO_MAX && DISABLED(USE_KMAX_PLUG)
2478 2560
       #error "Enable USE_KMAX_PLUG when homing K to MAX."
2561
+    #elif HAS_U_AXIS && U_HOME_TO_MIN && DISABLED(USE_UMIN_PLUG)
2562
+      #error "Enable USE_UMIN_PLUG when homing U to MIN."
2563
+    #elif HAS_U_AXIS && U_HOME_TO_MAX && DISABLED(USE_UMAX_PLUG)
2564
+      #error "Enable USE_UMAX_PLUG when homing U to MAX."
2565
+    #elif HAS_V_AXIS && V_HOME_TO_MIN && DISABLED(USE_VMIN_PLUG)
2566
+      #error "Enable USE_VMIN_PLUG when homing V to MIN."
2567
+    #elif HAS_V_AXIS && V_HOME_TO_MAX && DISABLED(USE_VMAX_PLUG)
2568
+      #error "Enable USE_VMAX_PLUG when homing V to MAX."
2569
+    #elif HAS_W_AXIS && W_HOME_TO_MIN && DISABLED(USE_WMIN_PLUG)
2570
+      #error "Enable USE_WMIN_PLUG when homing W to MIN."
2571
+    #elif HAS_W_AXIS && W_HOME_TO_MAX && DISABLED(USE_WMAX_PLUG)
2572
+      #error "Enable USE_WMAX_PLUG when homing W to MAX."
2479 2573
     #endif
2480 2574
   #endif
2481 2575
 
@@ -2959,6 +3053,12 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS
2959 3053
   #error "An SPI driven TMC on J requires J_CS_PIN."
2960 3054
 #elif INVALID_TMC_SPI(K)
2961 3055
   #error "An SPI driven TMC on K requires K_CS_PIN."
3056
+#elif INVALID_TMC_SPI(U)
3057
+  #error "An SPI driven TMC on U requires U_CS_PIN."
3058
+#elif INVALID_TMC_SPI(V)
3059
+  #error "An SPI driven TMC on V requires V_CS_PIN."
3060
+#elif INVALID_TMC_SPI(W)
3061
+  #error "An SPI driven TMC on W requires W_CS_PIN."
2962 3062
 #endif
2963 3063
 #undef INVALID_TMC_SPI
2964 3064
 
@@ -3004,6 +3104,13 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS
3004 3104
   #error "TMC2208 or TMC2209 on J requires J_HARDWARE_SERIAL or J_SERIAL_(RX|TX)_PIN."
3005 3105
 #elif HAS_K_AXIS && INVALID_TMC_UART(K)
3006 3106
   #error "TMC2208 or TMC2209 on K requires K_HARDWARE_SERIAL or K_SERIAL_(RX|TX)_PIN."
3107
+#elif HAS_U_AXIS && INVALID_TMC_UART(U)
3108
+  #error "TMC2208 or TMC2209 on U requires U_HARDWARE_SERIAL or U_SERIAL_(RX|TX)_PIN."
3109
+#elif HAS_V_AXIS && INVALID_TMC_UART(V)
3110
+  #error "TMC2208 or TMC2209 on V requires V_HARDWARE_SERIAL or V_SERIAL_(RX|TX)_PIN."
3111
+#elif HAS_W_AXIS && INVALID_TMC_UART(W)
3112
+  #error "TMC2208 or TMC2209 on W requires W_HARDWARE_SERIAL or W_SERIAL_(RX|TX)_PIN."
3113
+
3007 3114
 #endif
3008 3115
 #undef INVALID_TMC_UART
3009 3116
 
@@ -3033,6 +3140,12 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS
3033 3140
   INVALID_TMC_ADDRESS(J);
3034 3141
 #elif AXIS_DRIVER_TYPE_K(TMC2209)
3035 3142
   INVALID_TMC_ADDRESS(K);
3143
+#elif AXIS_DRIVER_TYPE_U(TMC2209)
3144
+  INVALID_TMC_ADDRESS(U);
3145
+#elif AXIS_DRIVER_TYPE_V(TMC2209)
3146
+  INVALID_TMC_ADDRESS(V);
3147
+#elif AXIS_DRIVER_TYPE_W(TMC2209)
3148
+  INVALID_TMC_ADDRESS(W);
3036 3149
 #elif AXIS_DRIVER_TYPE_E0(TMC2209)
3037 3150
   INVALID_TMC_ADDRESS(E0);
3038 3151
 #elif AXIS_DRIVER_TYPE_E1(TMC2209)
@@ -3094,6 +3207,12 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS
3094 3207
   INVALID_TMC_MS(J)
3095 3208
 #elif HAS_K_AXIS && !TMC_MICROSTEP_IS_VALID(K)
3096 3209
   INVALID_TMC_MS(K)
3210
+#elif HAS_U_AXIS && !TMC_MICROSTEP_IS_VALID(U)
3211
+  INVALID_TMC_MS(U)
3212
+#elif HAS_V_AXIS && !TMC_MICROSTEP_IS_VALID(V)
3213
+  INVALID_TMC_MS(V)
3214
+#elif HAS_W_AXIS && !TMC_MICROSTEP_IS_VALID(W)
3215
+  INVALID_TMC_MS(W)
3097 3216
 #endif
3098 3217
 #undef INVALID_TMC_MS
3099 3218
 #undef TMC_MICROSTEP_IS_VALID
@@ -3123,6 +3242,15 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS
3123 3242
   #if HAS_K_AXIS
3124 3243
     #define K_ENDSTOP_INVERTING !AXIS_DRIVER_TYPE(K,TMC2209)
3125 3244
   #endif
3245
+  #if HAS_U_AXIS
3246
+    #define U_ENDSTOP_INVERTING !AXIS_DRIVER_TYPE(U,TMC2209)
3247
+  #endif
3248
+  #if HAS_V_AXIS
3249
+    #define V_ENDSTOP_INVERTING !AXIS_DRIVER_TYPE(V,TMC2209)
3250
+  #endif
3251
+  #if HAS_W_AXIS
3252
+    #define W_ENDSTOP_INVERTING !AXIS_DRIVER_TYPE(W,TMC2209)
3253
+  #endif
3126 3254
 
3127 3255
   #if NONE(SPI_ENDSTOPS, ONBOARD_ENDSTOPPULLUPS, ENDSTOPPULLUPS)
3128 3256
     #if   X_SENSORLESS && X_HOME_TO_MIN && DISABLED(ENDSTOPPULLUP_XMIN)
@@ -3149,6 +3277,19 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS
3149 3277
       #error "SENSORLESS_HOMING requires ENDSTOPPULLUP_KMIN (or ENDSTOPPULLUPS) when homing to K_MIN."
3150 3278
     #elif ALL(HAS_K_AXIS, K_SENSORLESS, K_HOME_TO_MAX) && DISABLED(ENDSTOPPULLUP_KMAX)
3151 3279
       #error "SENSORLESS_HOMING requires ENDSTOPPULLUP_KMAX (or ENDSTOPPULLUPS) when homing to K_MAX."
3280
+    #elif HAS_U_AXIS && U_SENSORLESS && U_HOME_TO_MIN && DISABLED(ENDSTOPPULLUP_UMIN)
3281
+      #error "SENSORLESS_HOMING requires ENDSTOPPULLUP_UMIN (or ENDSTOPPULLUPS) when homing to U_MIN."
3282
+    #elif HAS_U_AXIS && U_SENSORLESS && U_HOME_TO_MAX && DISABLED(ENDSTOPPULLUP_UMAX)
3283
+      #error "SENSORLESS_HOMING requires ENDSTOPPULLUP_UMAX (or ENDSTOPPULLUPS) when homing to U_MAX."
3284
+    #elif HAS_V_AXIS && V_SENSORLESS && V_HOME_TO_MIN && DISABLED(ENDSTOPPULLUP_VMIN)
3285
+      #error "SENSORLESS_HOMING requires ENDSTOPPULLUP_VMIN (or ENDSTOPPULLUPS) when homing to V_MIN."
3286
+    #elif HAS_V_AXIS && V_SENSORLESS && V_HOME_TO_MAX && DISABLED(ENDSTOPPULLUP_VMAX)
3287
+      #error "SENSORLESS_HOMING requires ENDSTOPPULLUP_VMAX (or ENDSTOPPULLUPS) when homing to V_MAX."
3288
+    #elif HAS_W_AXIS && W_SENSORLESS && W_HOME_TO_MIN && DISABLED(ENDSTOPPULLUP_WMIN)
3289
+      #error "SENSORLESS_HOMING requires ENDSTOPPULLUP_WMIN (or ENDSTOPPULLUPS) when homing to W_MIN."
3290
+    #elif HAS_W_AXIS && W_SENSORLESS && W_HOME_TO_MAX && DISABLED(ENDSTOPPULLUP_WMAX)
3291
+      #error "SENSORLESS_HOMING requires ENDSTOPPULLUP_WMAX (or ENDSTOPPULLUPS) when homing to W_MAX."
3292
+
3152 3293
     #endif
3153 3294
   #endif
3154 3295
 
@@ -3229,6 +3370,42 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS
3229 3370
       #else
3230 3371
         #error "SENSORLESS_HOMING requires K_MAX_ENDSTOP_INVERTING = false when homing TMC2209 to K_MAX."
3231 3372
       #endif
3373
+    #elif ALL(HAS_U_AXIS, U_SENSORLESS, U_HOME_TO_MIN) && U_MIN_ENDSTOP_INVERTING != U_ENDSTOP_INVERTING
3374
+      #if U_ENDSTOP_INVERTING
3375
+        #error "SENSORLESS_HOMING requires U_MIN_ENDSTOP_INVERTING = true when homing to U_MIN."
3376
+      #else
3377
+        #error "SENSORLESS_HOMING requires U_MIN_ENDSTOP_INVERTING = false when homing TMC2209 to U_MIN."
3378
+      #endif
3379
+    #elif ALL(HAS_U_AXIS, U_SENSORLESS, U_HOME_TO_MAX) && U_MAX_ENDSTOP_INVERTING != U_ENDSTOP_INVERTING
3380
+      #if U_ENDSTOP_INVERTING
3381
+        #error "SENSORLESS_HOMING requires U_MAX_ENDSTOP_INVERTING = true when homing to U_MAX."
3382
+      #else
3383
+        #error "SENSORLESS_HOMING requires U_MAX_ENDSTOP_INVERTING = false when homing TMC2209 to U_MAX."
3384
+      #endif
3385
+    #elif ALL(HAS_V_AXIS, V_SENSORLESS, V_HOME_TO_MIN) && V_MIN_ENDSTOP_INVERTING != V_ENDSTOP_INVERTING
3386
+      #if V_ENDSTOP_INVERTING
3387
+        #error "SENSORLESS_HOMING requires V_MIN_ENDSTOP_INVERTING = true when homing to V_MIN."
3388
+      #else
3389
+        #error "SENSORLESS_HOMING requires V_MIN_ENDSTOP_INVERTING = false when homing TMC2209 to V_MIN."
3390
+      #endif
3391
+    #elif ALL(HAS_V_AXIS, V_SENSORLESS, V_HOME_TO_MAX) && V_MAX_ENDSTOP_INVERTING != V_ENDSTOP_INVERTING
3392
+      #if V_ENDSTOP_INVERTING
3393
+        #error "SENSORLESS_HOMING requires V_MAX_ENDSTOP_INVERTING = true when homing to V_MAX."
3394
+      #else
3395
+        #error "SENSORLESS_HOMING requires V_MAX_ENDSTOP_INVERTING = false when homing TMC2209 to V_MAX."
3396
+      #endif
3397
+    #elif ALL(HAS_W_AXIS, W_SENSORLESS, W_HOME_TO_MIN) && W_MIN_ENDSTOP_INVERTING != W_ENDSTOP_INVERTING
3398
+      #if W_ENDSTOP_INVERTING
3399
+        #error "SENSORLESS_HOMING requires W_MIN_ENDSTOP_INVERTING = true when homing to W_MIN."
3400
+      #else
3401
+        #error "SENSORLESS_HOMING requires W_MIN_ENDSTOP_INVERTING = false when homing TMC2209 to W_MIN."
3402
+      #endif
3403
+    #elif ALL(HAS_W_AXIS, W_SENSORLESS, W_HOME_TO_MAX0) && W_MAX_ENDSTOP_INVERTING != W_ENDSTOP_INVERTING
3404
+      #if W_ENDSTOP_INVERTING
3405
+        #error "SENSORLESS_HOMING requires W_MAX_ENDSTOP_INVERTING = true when homing to W_MAX."
3406
+      #else
3407
+        #error "SENSORLESS_HOMING requires W_MAX_ENDSTOP_INVERTING = false when homing TMC2209 to W_MAX."
3408
+      #endif
3232 3409
     #endif
3233 3410
   #endif
3234 3411
 
@@ -3246,6 +3423,9 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS
3246 3423
   #undef I_ENDSTOP_INVERTING
3247 3424
   #undef J_ENDSTOP_INVERTING
3248 3425
   #undef K_ENDSTOP_INVERTING
3426
+  #undef U_ENDSTOP_INVERTING
3427
+  #undef V_ENDSTOP_INVERTING
3428
+  #undef W_ENDSTOP_INVERTING
3249 3429
 #endif
3250 3430
 
3251 3431
 // Sensorless probing requirements
@@ -3314,6 +3494,12 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS
3314 3494
       #define CS_COMPARE J_CS_PIN
3315 3495
     #elif IN_CHAIN(K)
3316 3496
       #define CS_COMPARE K_CS_PIN
3497
+    #elif IN_CHAIN(U)
3498
+      #define CS_COMPARE U_CS_PIN
3499
+    #elif IN_CHAIN(V)
3500
+      #define CS_COMPARE V_CS_PIN
3501
+    #elif IN_CHAIN(W)
3502
+      #define CS_COMPARE W_CS_PIN
3317 3503
     #elif IN_CHAIN(E0)
3318 3504
       #define CS_COMPARE E0_CS_PIN
3319 3505
     #elif IN_CHAIN(E1)
@@ -3334,6 +3520,7 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS
3334 3520
     #define BAD_CS_PIN(A) (IN_CHAIN(A) && A##_CS_PIN != CS_COMPARE)
3335 3521
     #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) \
3336 3522
       || BAD_CS_PIN(I) || BAD_CS_PIN(J) || BAD_CS_PIN(K) \
3523
+      || BAD_CS_PIN(U) || BAD_CS_PIN(V) || BAD_CS_PIN(W) \
3337 3524
       || 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)
3338 3525
       #error "All chained TMC drivers must use the same CS pin."
3339 3526
     #endif
@@ -3347,8 +3534,8 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS
3347 3534
 /**
3348 3535
  * L64XX requirement
3349 3536
  */
3350
-#if HAS_L64XX && HAS_I_AXIS
3351
-  #error "L64XX requires LINEAR_AXES <= 3. Homing with L64XX is not yet implemented for LINEAR_AXES > 3."
3537
+#if HAS_L64XX && NUM_AXES > 3
3538
+  #error "L64XX requires NUM_AXES <= 3. Homing with L64XX is not yet implemented for NUM_AXES > 3."
3352 3539
 #endif
3353 3540
 
3354 3541
 /**
@@ -3372,7 +3559,7 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS
3372 3559
 #if HAS_MULTI_EXTRUDER
3373 3560
   #define _EXTRA_NOTE " (Did you forget to enable DISTINCT_E_FACTORS?)"
3374 3561
 #else
3375
-  #define _EXTRA_NOTE " (Should be " STRINGIFY(LINEAR_AXES) "+" STRINGIFY(E_STEPPERS) ")"
3562
+  #define _EXTRA_NOTE " (Should be " STRINGIFY(NUM_AXES) "+" STRINGIFY(E_STEPPERS) ")"
3376 3563
 #endif
3377 3564
 
3378 3565
 constexpr float sanity_arr_1[] = DEFAULT_AXIS_STEPS_PER_UNIT;
@@ -3391,7 +3578,7 @@ static_assert(COUNT(sanity_arr_3) <= DISTINCT_AXES, "DEFAULT_MAX_ACCELERATION ha
3391 3578
 static_assert(_PLUS_TEST(3), "DEFAULT_MAX_ACCELERATION values must be positive.");
3392 3579
 
3393 3580
 constexpr float sanity_arr_4[] = HOMING_FEEDRATE_MM_M;
3394
-static_assert(COUNT(sanity_arr_4) == LINEAR_AXES,  "HOMING_FEEDRATE_MM_M requires " _LINEAR_AXES_STR "elements (and no others).");
3581
+static_assert(COUNT(sanity_arr_4) == NUM_AXES,  "HOMING_FEEDRATE_MM_M requires " _NUM_AXES_STR "elements (and no others).");
3395 3582
 static_assert(_PLUS_TEST(4), "HOMING_FEEDRATE_MM_M values must be positive.");
3396 3583
 
3397 3584
 #ifdef MAX_ACCEL_EDIT_VALUES
@@ -3831,6 +4018,15 @@ static_assert(_PLUS_TEST(4), "HOMING_FEEDRATE_MM_M values must be positive.");
3831 4018
 #if _BAD_DRIVER(K)
3832 4019
   #error "K_DRIVER_TYPE is not recognized."
3833 4020
 #endif
4021
+#if _BAD_DRIVER(U)
4022
+  #error "U_DRIVER_TYPE is not recognized."
4023
+#endif
4024
+#if _BAD_DRIVER(V)
4025
+  #error "V_DRIVER_TYPE is not recognized."
4026
+#endif
4027
+#if _BAD_DRIVER(W)
4028
+  #error "W_DRIVER_TYPE is not recognized."
4029
+#endif
3834 4030
 #if _BAD_DRIVER(X2)
3835 4031
   #error "X2_DRIVER_TYPE is not recognized."
3836 4032
 #endif
@@ -3903,7 +4099,7 @@ static_assert(_PLUS_TEST(4), "HOMING_FEEDRATE_MM_M values must be positive.");
3903 4099
 
3904 4100
 // Misc. Cleanup
3905 4101
 #undef _TEST_PWM
3906
-#undef _LINEAR_AXES_STR
4102
+#undef _NUM_AXES_STR
3907 4103
 #undef _LOGICAL_AXES_STR
3908 4104
 
3909 4105
 // JTAG support in the HAL

+ 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 02000903
55
+#define MARLIN_HEX_VERSION 02010000
56 56
 #ifndef REQUIRED_CONFIGURATION_H_VERSION
57 57
   #define REQUIRED_CONFIGURATION_H_VERSION MARLIN_HEX_VERSION
58 58
 #endif

+ 157
- 0
Marlin/src/inc/Warnings.cpp View File

@@ -532,6 +532,163 @@
532 532
     #endif
533 533
   #endif
534 534
 
535
+  #if AUTO_ASSIGNED_U_STEPPER
536
+    #warning "Note: Auto-assigned U STEP/DIR/ENABLE_PINs to unused En_STEP/DIR/ENABLE_PINs. (Define NO_AUTO_ASSIGN_WARNING to suppress this warning.)"
537
+  #endif
538
+  #if AUTO_ASSIGNED_U_CS
539
+    #warning "Note: Auto-assigned U_CS_PIN to an unused En_CS_PIN. (Define NO_AUTO_ASSIGN_WARNING to suppress this warning.)"
540
+  #endif
541
+  #if AUTO_ASSIGNED_U_MS1
542
+    #warning "Note: Auto-assigned U_MS1_PIN to an unused En_MS1_PIN. (Define NO_AUTO_ASSIGN_WARNING to suppress this warning.)"
543
+  #endif
544
+  #if AUTO_ASSIGNED_U_MS2
545
+    #warning "Note: Auto-assigned U_MS2_PIN to an unused En_MS2_PIN. (Define NO_AUTO_ASSIGN_WARNING to suppress this warning.)"
546
+  #endif
547
+  #if AUTO_ASSIGNED_U_MS3
548
+    #warning "Note: Auto-assigned U_MS3_PIN to an unused En_MS3_PIN. (Define NO_AUTO_ASSIGN_WARNING to suppress this warning.)"
549
+  #endif
550
+  #if AUTO_ASSIGNED_U_DIAG
551
+    #if U_USE_ENDSTOP == _XMIN_
552
+      #warning "Note: Auto-assigned U_DIAG_PIN to X_MIN_PIN. (Define NO_AUTO_ASSIGN_WARNING to suppress this warning.)"
553
+    #elif U_USE_ENDSTOP == _XMAX_
554
+      #warning "Note: Auto-assigned U_DIAG_PIN to X_MAX_PIN. (Define NO_AUTO_ASSIGN_WARNING to suppress this warning.)"
555
+    #elif K_USE_ENDSTOP == _YMIN_
556
+      #warning "Note: Auto-assigned U_DIAG_PIN to Y_MIN_PIN. (Define NO_AUTO_ASSIGN_WARNING to suppress this warning.)"
557
+    #elif U_USE_ENDSTOP == _YMAX_
558
+      #warning "Note: Auto-assigned U_DIAG_PIN to Y_MAX_PIN. (Define NO_AUTO_ASSIGN_WARNING to suppress this warning.)"
559
+    #elif U_USE_ENDSTOP == _ZMIN_
560
+      #warning "Note: Auto-assigned U_DIAG_PIN to Z_MIN_PIN. (Define NO_AUTO_ASSIGN_WARNING to suppress this warning.)"
561
+    #elif U_USE_ENDSTOP == _ZMAX_
562
+      #warning "Note: Auto-assigned U_DIAG_PIN to Z_MAX_PIN. (Define NO_AUTO_ASSIGN_WARNING to suppress this warning.)"
563
+    #elif U_USE_ENDSTOP == _XDIAG_
564
+      #warning "Note: Auto-assigned U_DIAG_PIN to X_DIAG_PIN. (Define NO_AUTO_ASSIGN_WARNING to suppress this warning.)"
565
+    #elif U_USE_ENDSTOP == _YDIAG_
566
+      #warning "Note: Auto-assigned U_DIAG_PIN to Y_DIAG_PIN. (Define NO_AUTO_ASSIGN_WARNING to suppress this warning.)"
567
+    #elif U_USE_ENDSTOP == _ZDIAG_
568
+      #warning "Note: Auto-assigned U_DIAG_PIN to Z_DIAG_PIN. (Define NO_AUTO_ASSIGN_WARNING to suppress this warning.)"
569
+    #elif U_USE_ENDSTOP == _E0DIAG_
570
+      #warning "Note: Auto-assigned U_DIAG_PIN to E0_DIAG_PIN. (Define NO_AUTO_ASSIGN_WARNING to suppress this warning.)"
571
+    #elif U_USE_ENDSTOP == _E1DIAG_
572
+      #warning "Note: Auto-assigned U_DIAG_PIN to E1_DIAG_PIN. (Define NO_AUTO_ASSIGN_WARNING to suppress this warning.)"
573
+    #elif U_USE_ENDSTOP == _E2DIAG_
574
+      #warning "Note: Auto-assigned U_DIAG_PIN to E2_DIAG_PIN. (Define NO_AUTO_ASSIGN_WARNING to suppress this warning.)"
575
+    #elif U_USE_ENDSTOP == _E3DIAG_
576
+      #warning "Note: Auto-assigned U_DIAG_PIN to E3_DIAG_PIN. (Define NO_AUTO_ASSIGN_WARNING to suppress this warning.)"
577
+    #elif U_USE_ENDSTOP == _E4DIAG_
578
+      #warning "Note: Auto-assigned U_DIAG_PIN to E4_DIAG_PIN. (Define NO_AUTO_ASSIGN_WARNING to suppress this warning.)"
579
+    #elif U_USE_ENDSTOP == _E5DIAG_
580
+      #warning "Note: Auto-assigned U_DIAG_PIN to E5_DIAG_PIN. (Define NO_AUTO_ASSIGN_WARNING to suppress this warning.)"
581
+    #elif U_USE_ENDSTOP == _E6DIAG_
582
+      #warning "Note: Auto-assigned U_DIAG_PIN to E6_DIAG_PIN. (Define NO_AUTO_ASSIGN_WARNING to suppress this warning.)"
583
+    #elif U_USE_ENDSTOP == _E7DIAG_
584
+      #warning "Note: Auto-assigned U_DIAG_PIN to E7_DIAG_PIN. (Define NO_AUTO_ASSIGN_WARNING to suppress this warning.)"
585
+    #endif
586
+  #endif
587
+  #if AUTO_ASSIGNED_V_STEPPER
588
+    #warning "Note: Auto-assigned V STEP/DIR/ENABLE_PINs to unused En_STEP/DIR/ENABLE_PINs. (Define NO_AUTO_ASSIGN_WARNING to suppress this warning.)"
589
+  #endif
590
+  #if AUTO_ASSIGNED_V_CS
591
+    #warning "Note: Auto-assigned V_CS_PIN to an unused En_CS_PIN. (Define NO_AUTO_ASSIGN_WARNING to suppress this warning.)"
592
+  #endif
593
+  #if AUTO_ASSIGNED_V_MS1
594
+    #warning "Note: Auto-assigned V_MS1_PIN to an unused En_MS1_PIN. (Define NO_AUTO_ASSIGN_WARNING to suppress this warning.)"
595
+  #endif
596
+  #if AUTO_ASSIGNED_V_MS2
597
+    #warning "Note: Auto-assigned V_MS2_PIN to an unused En_MS2_PIN. (Define NO_AUTO_ASSIGN_WARNING to suppress this warning.)"
598
+  #endif
599
+  #if AUTO_ASSIGNED_V_MS3
600
+    #warning "Note: Auto-assigned V_MS3_PIN to an unused En_MS3_PIN. (Define NO_AUTO_ASSIGN_WARNING to suppress this warning.)"
601
+  #endif
602
+  #if AUTO_ASSIGNED_V_DIAG
603
+    #if V_USE_ENDSTOP == _XMIN_
604
+      #warning "Note: Auto-assigned V_DIAG_PIN to X_MIN_PIN. (Define NO_AUTO_ASSIGN_WARNING to suppress this warning.)"
605
+    #elif V_USE_ENDSTOP == _XMAX_
606
+      #warning "Note: Auto-assigned V_DIAG_PIN to X_MAX_PIN. (Define NO_AUTO_ASSIGN_WARNING to suppress this warning.)"
607
+    #elif V_USE_ENDSTOP == _YMIN_
608
+      #warning "Note: Auto-assigned V_DIAG_PIN to Y_MIN_PIN. (Define NO_AUTO_ASSIGN_WARNING to suppress this warning.)"
609
+    #elif V_USE_ENDSTOP == _YMAX_
610
+      #warning "Note: Auto-assigned V_DIAG_PIN to Y_MAX_PIN. (Define NO_AUTO_ASSIGN_WARNING to suppress this warning.)"
611
+    #elif V_USE_ENDSTOP == _ZMIN_
612
+      #warning "Note: Auto-assigned V_DIAG_PIN to Z_MIN_PIN. (Define NO_AUTO_ASSIGN_WARNING to suppress this warning.)"
613
+    #elif V_USE_ENDSTOP == _ZMAX_
614
+      #warning "Note: Auto-assigned V_DIAG_PIN to Z_MAX_PIN. (Define NO_AUTO_ASSIGN_WARNING to suppress this warning.)"
615
+    #elif V_USE_ENDSTOP == _XDIAG_
616
+      #warning "Note: Auto-assigned V_DIAG_PIN to X_DIAG_PIN. (Define NO_AUTO_ASSIGN_WARNING to suppress this warning.)"
617
+    #elif V_USE_ENDSTOP == _YDIAG_
618
+      #warning "Note: Auto-assigned V_DIAG_PIN to Y_DIAG_PIN. (Define NO_AUTO_ASSIGN_WARNING to suppress this warning.)"
619
+    #elif V_USE_ENDSTOP == _ZDIAG_
620
+      #warning "Note: Auto-assigned V_DIAG_PIN to Z_DIAG_PIN. (Define NO_AUTO_ASSIGN_WARNING to suppress this warning.)"
621
+    #elif V_USE_ENDSTOP == _E0DIAG_
622
+      #warning "Note: Auto-assigned V_DIAG_PIN to E0_DIAG_PIN. (Define NO_AUTO_ASSIGN_WARNING to suppress this warning.)"
623
+    #elif V_USE_ENDSTOP == _E1DIAG_
624
+      #warning "Note: Auto-assigned V_DIAG_PIN to E1_DIAG_PIN. (Define NO_AUTO_ASSIGN_WARNING to suppress this warning.)"
625
+    #elif V_USE_ENDSTOP == _E2DIAG_
626
+      #warning "Note: Auto-assigned V_DIAG_PIN to E2_DIAG_PIN. (Define NO_AUTO_ASSIGN_WARNING to suppress this warning.)"
627
+    #elif V_USE_ENDSTOP == _E3DIAG_
628
+      #warning "Note: Auto-assigned V_DIAG_PIN to E3_DIAG_PIN. (Define NO_AUTO_ASSIGN_WARNING to suppress this warning.)"
629
+    #elif V_USE_ENDSTOP == _E4DIAG_
630
+      #warning "Note: Auto-assigned V_DIAG_PIN to E4_DIAG_PIN. (Define NO_AUTO_ASSIGN_WARNING to suppress this warning.)"
631
+    #elif V_USE_ENDSTOP == _E5DIAG_
632
+      #warning "Note: Auto-assigned V_DIAG_PIN to E5_DIAG_PIN. (Define NO_AUTO_ASSIGN_WARNING to suppress this warning.)"
633
+    #elif V_USE_ENDSTOP == _E6DIAG_
634
+      #warning "Note: Auto-assigned V_DIAG_PIN to E6_DIAG_PIN. (Define NO_AUTO_ASSIGN_WARNING to suppress this warning.)"
635
+    #elif V_USE_ENDSTOP == _E7DIAG_
636
+      #warning "Note: Auto-assigned V_DIAG_PIN to E7_DIAG_PIN. (Define NO_AUTO_ASSIGN_WARNING to suppress this warning.)"
637
+    #endif
638
+  #endif
639
+  #if AUTO_ASSIGNED_W_STEPPER
640
+    #warning "Note: Auto-assigned W STEP/DIR/ENABLE_PINs to unused En_STEP/DIR/ENABLE_PINs. (Define NO_AUTO_ASSIGN_WARNING to suppress this warning.)"
641
+  #endif
642
+  #if AUTO_ASSIGNED_W_CS
643
+    #warning "Note: Auto-assigned W_CS_PIN to an unused En_CS_PIN. (Define NO_AUTO_ASSIGN_WARNING to suppress this warning.)"
644
+  #endif
645
+  #if AUTO_ASSIGNED_W_MS1
646
+    #warning "Note: Auto-assigned W_MS1_PIN to an unused En_MS1_PIN. (Define NO_AUTO_ASSIGN_WARNING to suppress this warning.)"
647
+  #endif
648
+  #if AUTO_ASSIGNED_W_MS2
649
+    #warning "Note: Auto-assigned W_MS2_PIN to an unused En_MS2_PIN. (Define NO_AUTO_ASSIGN_WARNING to suppress this warning.)"
650
+  #endif
651
+  #if AUTO_ASSIGNED_W_MS3
652
+    #warning "Note: Auto-assigned W_MS3_PIN to an unused En_MS3_PIN. (Define NO_AUTO_ASSIGN_WARNING to suppress this warning.)"
653
+  #endif
654
+  #if AUTO_ASSIGNED_W_DIAG
655
+    #if W_USE_ENDSTOP == _XMIN_
656
+      #warning "Note: Auto-assigned W_DIAG_PIN to X_MIN_PIN. (Define NO_AUTO_ASSIGN_WARNING to suppress this warning.)"
657
+    #elif W_USE_ENDSTOP == _XMAX_
658
+      #warning "Note: Auto-assigned W_DIAG_PIN to X_MAX_PIN. (Define NO_AUTO_ASSIGN_WARNING to suppress this warning.)"
659
+    #elif W_USE_ENDSTOP == _YMIN_
660
+      #warning "Note: Auto-assigned W_DIAG_PIN to Y_MIN_PIN. (Define NO_AUTO_ASSIGN_WARNING to suppress this warning.)"
661
+    #elif W_USE_ENDSTOP == _YMAX_
662
+      #warning "Note: Auto-assigned W_DIAG_PIN to Y_MAX_PIN. (Define NO_AUTO_ASSIGN_WARNING to suppress this warning.)"
663
+    #elif W_USE_ENDSTOP == _ZMIN_
664
+      #warning "Note: Auto-assigned W_DIAG_PIN to Z_MIN_PIN. (Define NO_AUTO_ASSIGN_WARNING to suppress this warning.)"
665
+    #elif W_USE_ENDSTOP == _ZMAX_
666
+      #warning "Note: Auto-assigned W_DIAG_PIN to Z_MAX_PIN. (Define NO_AUTO_ASSIGN_WARNING to suppress this warning.)"
667
+    #elif W_USE_ENDSTOP == _XDIAG_
668
+      #warning "Note: Auto-assigned W_DIAG_PIN to X_DIAG_PIN. (Define NO_AUTO_ASSIGN_WARNING to suppress this warning.)"
669
+    #elif W_USE_ENDSTOP == _YDIAG_
670
+      #warning "Note: Auto-assigned W_DIAG_PIN to Y_DIAG_PIN. (Define NO_AUTO_ASSIGN_WARNING to suppress this warning.)"
671
+    #elif W_USE_ENDSTOP == _ZDIAG_
672
+      #warning "Note: Auto-assigned W_DIAG_PIN to Z_DIAG_PIN. (Define NO_AUTO_ASSIGN_WARNING to suppress this warning.)"
673
+    #elif W_USE_ENDSTOP == _E0DIAG_
674
+      #warning "Note: Auto-assigned W_DIAG_PIN to E0_DIAG_PIN. (Define NO_AUTO_ASSIGN_WARNING to suppress this warning.)"
675
+    #elif W_USE_ENDSTOP == _E1DIAG_
676
+      #warning "Note: Auto-assigned W_DIAG_PIN to E1_DIAG_PIN. (Define NO_AUTO_ASSIGN_WARNING to suppress this warning.)"
677
+    #elif W_USE_ENDSTOP == _E2DIAG_
678
+      #warning "Note: Auto-assigned W_DIAG_PIN to E2_DIAG_PIN. (Define NO_AUTO_ASSIGN_WARNING to suppress this warning.)"
679
+    #elif W_USE_ENDSTOP == _E3DIAG_
680
+      #warning "Note: Auto-assigned W_DIAG_PIN to E3_DIAG_PIN. (Define NO_AUTO_ASSIGN_WARNING to suppress this warning.)"
681
+    #elif W_USE_ENDSTOP == _E4DIAG_
682
+      #warning "Note: Auto-assigned W_DIAG_PIN to E4_DIAG_PIN. (Define NO_AUTO_ASSIGN_WARNING to suppress this warning.)"
683
+    #elif W_USE_ENDSTOP == _E5DIAG_
684
+      #warning "Note: Auto-assigned W_DIAG_PIN to E5_DIAG_PIN. (Define NO_AUTO_ASSIGN_WARNING to suppress this warning.)"
685
+    #elif W_USE_ENDSTOP == _E6DIAG_
686
+      #warning "Note: Auto-assigned W_DIAG_PIN to E6_DIAG_PIN. (Define NO_AUTO_ASSIGN_WARNING to suppress this warning.)"
687
+    #elif W_USE_ENDSTOP == _E7DIAG_
688
+      #warning "Note: Auto-assigned W_DIAG_PIN to E7_DIAG_PIN. (Define NO_AUTO_ASSIGN_WARNING to suppress this warning.)"
689
+    #endif
690
+  #endif
691
+
535 692
   #if ENABLED(CHAMBER_FAN) && !defined(CHAMBER_FAN_INDEX)
536 693
     #warning "Note: Auto-assigned CHAMBER_FAN_INDEX to the first free FAN pin. (Define NO_AUTO_ASSIGN_WARNING to suppress this warning.)"
537 694
   #endif

+ 1
- 1
Marlin/src/lcd/extui/dgus_reloaded/DGUSTxHandler.cpp View File

@@ -286,7 +286,7 @@ void DGUSTxHandler::TempMax(DGUS_VP &vp) {
286 286
 }
287 287
 
288 288
 void DGUSTxHandler::StepperStatus(DGUS_VP &vp) {
289
-  const bool motor_on = stepper.axis_enabled.bits & (_BV(LINEAR_AXES) - 1);
289
+  const bool motor_on = stepper.axis_enabled.bits & (_BV(NUM_AXES) - 1);
290 290
   dgus_display.Write((uint16_t)vp.addr, Swap16(uint16_t(motor_on ? DGUS_Data::Status::ENABLED : DGUS_Data::Status::DISABLED)));
291 291
 }
292 292
 

+ 30
- 0
Marlin/src/lcd/extui/ui_api.cpp View File

@@ -420,6 +420,15 @@ namespace ExtUI {
420 420
         #if AXIS_IS_TMC(K)
421 421
           case K: return stepperK.getMilliamps();
422 422
         #endif
423
+        #if AXIS_IS_TMC(U)
424
+          case U: return stepperU.getMilliamps();
425
+        #endif
426
+        #if AXIS_IS_TMC(V)
427
+          case V: return stepperV.getMilliamps();
428
+        #endif
429
+        #if AXIS_IS_TMC(W)
430
+          case W: return stepperW.getMilliamps();
431
+        #endif
423 432
         #if AXIS_IS_TMC(X2)
424 433
           case X2: return stepperX2.getMilliamps();
425 434
         #endif
@@ -489,6 +498,15 @@ namespace ExtUI {
489 498
         #if AXIS_IS_TMC(K)
490 499
           case K: stepperK.rms_current(constrain(mA, 400, 1500)); break;
491 500
         #endif
501
+        #if AXIS_IS_TMC(U)
502
+          case U: stepperU.rms_current(constrain(mA, 400, 1500)); break;
503
+        #endif
504
+        #if AXIS_IS_TMC(V)
505
+          case V: stepperV.rms_current(constrain(mA, 400, 1500)); break;
506
+        #endif
507
+        #if AXIS_IS_TMC(W)
508
+          case W: stepperW.rms_current(constrain(mA, 400, 1500)); break;
509
+        #endif
492 510
         #if AXIS_IS_TMC(X2)
493 511
           case X2: stepperX2.rms_current(constrain(mA, 400, 1500)); break;
494 512
         #endif
@@ -546,6 +564,9 @@ namespace ExtUI {
546 564
         OPTCODE(I_SENSORLESS,  case I:  return stepperI.homing_threshold())
547 565
         OPTCODE(J_SENSORLESS,  case J:  return stepperJ.homing_threshold())
548 566
         OPTCODE(K_SENSORLESS,  case K:  return stepperK.homing_threshold())
567
+        OPTCODE(U_SENSORLESS,  case U:  return stepperU.homing_threshold())
568
+        OPTCODE(V_SENSORLESS,  case V:  return stepperV.homing_threshold())
569
+        OPTCODE(W_SENSORLESS,  case W:  return stepperW.homing_threshold())
549 570
         OPTCODE(X2_SENSORLESS, case X2: return stepperX2.homing_threshold())
550 571
         OPTCODE(Y2_SENSORLESS, case Y2: return stepperY2.homing_threshold())
551 572
         OPTCODE(Z2_SENSORLESS, case Z2: return stepperZ2.homing_threshold())
@@ -575,6 +596,15 @@ namespace ExtUI {
575 596
         #if K_SENSORLESS
576 597
           case K: stepperK.homing_threshold(value); break;
577 598
         #endif
599
+        #if U_SENSORLESS
600
+          case U: stepperU.homing_threshold(value); break;
601
+        #endif
602
+        #if V_SENSORLESS
603
+          case V: stepperV.homing_threshold(value); break;
604
+        #endif
605
+        #if W_SENSORLESS
606
+          case W: stepperW.homing_threshold(value); break;
607
+        #endif
578 608
         #if X2_SENSORLESS
579 609
           case X2: stepperX2.homing_threshold(value); break;
580 610
         #endif

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

@@ -57,7 +57,7 @@ namespace ExtUI {
57 57
 
58 58
   static constexpr size_t eeprom_data_size = 48;
59 59
 
60
-  enum axis_t     : uint8_t { X, Y, Z, I, J, K, X2, Y2, Z2, Z3, Z4 };
60
+  enum axis_t     : uint8_t { X, Y, Z, I, J, K, U, V, W, X2, Y2, Z2, Z3, Z4 };
61 61
   enum extruder_t : uint8_t { E0, E1, E2, E3, E4, E5, E6, E7 };
62 62
   enum heater_t   : uint8_t { H0, H1, H2, H3, H4, H5, BED, CHAMBER, COOLER };
63 63
   enum fan_t      : uint8_t { FAN0, FAN1, FAN2, FAN3, FAN4, FAN5, FAN6, FAN7 };

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

@@ -103,6 +103,9 @@ namespace Language_en {
103 103
   LSTR MSG_HOME_OFFSET_I                  = _UxGT("Home Offset ") STR_I;
104 104
   LSTR MSG_HOME_OFFSET_J                  = _UxGT("Home Offset ") STR_J;
105 105
   LSTR MSG_HOME_OFFSET_K                  = _UxGT("Home Offset ") STR_K;
106
+  LSTR MSG_HOME_OFFSET_U                  = _UxGT("Home Offset ") STR_U;
107
+  LSTR MSG_HOME_OFFSET_V                  = _UxGT("Home Offset ") STR_V;
108
+  LSTR MSG_HOME_OFFSET_W                  = _UxGT("Home Offset ") STR_W;
106 109
   LSTR MSG_HOME_OFFSETS_APPLIED           = _UxGT("Offsets Applied");
107 110
   LSTR MSG_SET_ORIGIN                     = _UxGT("Set Origin");
108 111
   LSTR MSG_TRAMMING_WIZARD                = _UxGT("Tramming Wizard");
@@ -288,6 +291,9 @@ namespace Language_en {
288 291
   LSTR MSG_MOVE_I                         = _UxGT("Move ") STR_I;
289 292
   LSTR MSG_MOVE_J                         = _UxGT("Move ") STR_J;
290 293
   LSTR MSG_MOVE_K                         = _UxGT("Move ") STR_K;
294
+  LSTR MSG_MOVE_U                         = _UxGT("Move ") STR_U;
295
+  LSTR MSG_MOVE_V                         = _UxGT("Move ") STR_V;
296
+  LSTR MSG_MOVE_W                         = _UxGT("Move ") STR_W;
291 297
   LSTR MSG_MOVE_E                         = _UxGT("Move Extruder");
292 298
   LSTR MSG_MOVE_EN                        = _UxGT("Move E*");
293 299
   LSTR MSG_HOTEND_TOO_COLD                = _UxGT("Hotend too cold");
@@ -354,6 +360,9 @@ namespace Language_en {
354 360
   LSTR MSG_VI_JERK                        = _UxGT("Max ") STR_I _UxGT(" Jerk");
355 361
   LSTR MSG_VJ_JERK                        = _UxGT("Max ") STR_J _UxGT(" Jerk");
356 362
   LSTR MSG_VK_JERK                        = _UxGT("Max ") STR_K _UxGT(" Jerk");
363
+  LSTR MSG_VU_JERK                        = _UxGT("Max ") STR_U _UxGT(" Jerk");
364
+  LSTR MSG_VV_JERK                        = _UxGT("Max ") STR_V _UxGT(" Jerk");
365
+  LSTR MSG_VW_JERK                        = _UxGT("Max ") STR_W _UxGT(" Jerk");
357 366
   LSTR MSG_VE_JERK                        = _UxGT("Max E Jerk");
358 367
   LSTR MSG_JUNCTION_DEVIATION             = _UxGT("Junction Dev");
359 368
   LSTR MSG_VELOCITY                       = _UxGT("Velocity");
@@ -363,6 +372,9 @@ namespace Language_en {
363 372
   LSTR MSG_VMAX_I                         = _UxGT("Max ") STR_I _UxGT(" Vel");
364 373
   LSTR MSG_VMAX_J                         = _UxGT("Max ") STR_J _UxGT(" Vel");
365 374
   LSTR MSG_VMAX_K                         = _UxGT("Max ") STR_K _UxGT(" Vel");
375
+  LSTR MSG_VMAX_U                         = _UxGT("Max ") STR_U _UxGT(" Vel");
376
+  LSTR MSG_VMAX_V                         = _UxGT("Max ") STR_V _UxGT(" Vel");
377
+  LSTR MSG_VMAX_W                         = _UxGT("Max ") STR_W _UxGT(" Vel");
366 378
   LSTR MSG_VMAX_E                         = _UxGT("Max ") STR_E _UxGT(" Vel");
367 379
   LSTR MSG_VMAX_EN                        = _UxGT("Max * Vel");
368 380
   LSTR MSG_VMIN                           = _UxGT("Min Velocity");
@@ -374,6 +386,9 @@ namespace Language_en {
374 386
   LSTR MSG_AMAX_I                         = _UxGT("Max ") STR_I _UxGT(" Accel");
375 387
   LSTR MSG_AMAX_J                         = _UxGT("Max ") STR_J _UxGT(" Accel");
376 388
   LSTR MSG_AMAX_K                         = _UxGT("Max ") STR_K _UxGT(" Accel");
389
+  LSTR MSG_AMAX_U                         = _UxGT("Max ") STR_U _UxGT(" Accel");
390
+  LSTR MSG_AMAX_V                         = _UxGT("Max ") STR_V _UxGT(" Accel");
391
+  LSTR MSG_AMAX_W                         = _UxGT("Max ") STR_W _UxGT(" Accel");
377 392
   LSTR MSG_AMAX_E                         = _UxGT("Max ") STR_E _UxGT(" Accel");
378 393
   LSTR MSG_AMAX_EN                        = _UxGT("Max * Accel");
379 394
   LSTR MSG_A_RETRACT                      = _UxGT("Retract Accel");
@@ -387,6 +402,9 @@ namespace Language_en {
387 402
   LSTR MSG_I_STEPS                        = STR_I _UxGT(" Steps/mm");
388 403
   LSTR MSG_J_STEPS                        = STR_J _UxGT(" Steps/mm");
389 404
   LSTR MSG_K_STEPS                        = STR_K _UxGT(" Steps/mm");
405
+  LSTR MSG_U_STEPS                        = STR_U _UxGT(" Steps/mm");
406
+  LSTR MSG_V_STEPS                        = STR_V _UxGT(" Steps/mm");
407
+  LSTR MSG_W_STEPS                        = STR_W _UxGT(" Steps/mm");
390 408
   LSTR MSG_E_STEPS                        = _UxGT("E steps/mm");
391 409
   LSTR MSG_EN_STEPS                       = _UxGT("* Steps/mm");
392 410
   LSTR MSG_TEMPERATURE                    = _UxGT("Temperature");
@@ -540,6 +558,9 @@ namespace Language_en {
540 558
   LSTR MSG_BABYSTEP_I                     = _UxGT("Babystep ") STR_I;
541 559
   LSTR MSG_BABYSTEP_J                     = _UxGT("Babystep ") STR_J;
542 560
   LSTR MSG_BABYSTEP_K                     = _UxGT("Babystep ") STR_K;
561
+  LSTR MSG_BABYSTEP_U                     = _UxGT("Babystep ") STR_U;
562
+  LSTR MSG_BABYSTEP_V                     = _UxGT("Babystep ") STR_V;
563
+  LSTR MSG_BABYSTEP_W                     = _UxGT("Babystep ") STR_W;
543 564
   LSTR MSG_BABYSTEP_TOTAL                 = _UxGT("Total");
544 565
   LSTR MSG_ENDSTOP_ABORT                  = _UxGT("Endstop Abort");
545 566
   LSTR MSG_HEATING_FAILED_LCD             = _UxGT("Heating Failed");
@@ -639,6 +660,9 @@ namespace Language_en {
639 660
   LSTR MSG_DAC_PERCENT_I                  = STR_I _UxGT(" Driver %");
640 661
   LSTR MSG_DAC_PERCENT_J                  = STR_J _UxGT(" Driver %");
641 662
   LSTR MSG_DAC_PERCENT_K                  = STR_K _UxGT(" Driver %");
663
+  LSTR MSG_DAC_PERCENT_U                  = STR_U _UxGT(" Driver %");
664
+  LSTR MSG_DAC_PERCENT_V                  = STR_V _UxGT(" Driver %");
665
+  LSTR MSG_DAC_PERCENT_W                  = STR_W _UxGT(" Driver %");
642 666
   LSTR MSG_DAC_PERCENT_E                  = _UxGT("E Driver %");
643 667
   LSTR MSG_ERROR_TMC                      = _UxGT("TMC CONNECTION ERROR");
644 668
   LSTR MSG_DAC_EEPROM_WRITE               = _UxGT("DAC EEPROM Write");
@@ -814,6 +838,9 @@ namespace Language_en {
814 838
   LSTR MSG_BACKLASH_I                     = STR_I;
815 839
   LSTR MSG_BACKLASH_J                     = STR_J;
816 840
   LSTR MSG_BACKLASH_K                     = STR_K;
841
+  LSTR MSG_BACKLASH_U                     = STR_U;
842
+  LSTR MSG_BACKLASH_V                     = STR_V;
843
+  LSTR MSG_BACKLASH_W                     = STR_W;
817 844
 }
818 845
 
819 846
 #if FAN_COUNT == 1

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

@@ -68,7 +68,7 @@ void menu_backlash();
68 68
     START_MENU();
69 69
     BACK_ITEM(MSG_ADVANCED_SETTINGS);
70 70
     #define EDIT_DAC_PERCENT(A) EDIT_ITEM(uint8, MSG_DAC_PERCENT_##A, &driverPercent[_AXIS(A)], 0, 100, []{ stepper_dac.set_current_percents(driverPercent); })
71
-    LOGICAL_AXIS_CODE(EDIT_DAC_PERCENT(E), EDIT_DAC_PERCENT(A), EDIT_DAC_PERCENT(B), EDIT_DAC_PERCENT(C), EDIT_DAC_PERCENT(I), EDIT_DAC_PERCENT(J), EDIT_DAC_PERCENT(K));
71
+    LOGICAL_AXIS_CODE(EDIT_DAC_PERCENT(E), EDIT_DAC_PERCENT(A), EDIT_DAC_PERCENT(B), EDIT_DAC_PERCENT(C), EDIT_DAC_PERCENT(I), EDIT_DAC_PERCENT(J), EDIT_DAC_PERCENT(K), EDIT_DAC_PERCENT(U), EDIT_DAC_PERCENT(V), EDIT_DAC_PERCENT(W));
72 72
     ACTION_ITEM(MSG_DAC_EEPROM_WRITE, stepper_dac.commit_eeprom);
73 73
     END_MENU();
74 74
   }
@@ -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, 9999, 9999, 9999)
359
+        LOGICAL_AXIS_ARRAY(9999, 9999, 9999, 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)
@@ -369,7 +369,7 @@ void menu_backlash();
369 369
     BACK_ITEM(MSG_ADVANCED_SETTINGS);
370 370
 
371 371
     #define EDIT_VMAX(N) EDIT_ITEM_FAST(float5, MSG_VMAX_##N, &planner.settings.max_feedrate_mm_s[_AXIS(N)], 1, max_fr_edit_scaled[_AXIS(N)])
372
-    LINEAR_AXIS_CODE(EDIT_VMAX(A), EDIT_VMAX(B), EDIT_VMAX(C), EDIT_VMAX(I), EDIT_VMAX(J), EDIT_VMAX(K));
372
+    NUM_AXIS_CODE(EDIT_VMAX(A), EDIT_VMAX(B), EDIT_VMAX(C), EDIT_VMAX(I), EDIT_VMAX(J), EDIT_VMAX(K), EDIT_VMAX(U), EDIT_VMAX(V), EDIT_VMAX(W));
373 373
 
374 374
     #if E_STEPPERS
375 375
       EDIT_ITEM_FAST(float5, MSG_VMAX_E, &planner.settings.max_feedrate_mm_s[E_AXIS_N(active_extruder)], 1, max_fr_edit_scaled.e);
@@ -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, 99000, 99000, 99000)
402
+        LOGICAL_AXIS_ARRAY(99000, 99000, 99000, 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)
@@ -423,9 +423,10 @@ void menu_backlash();
423 423
     EDIT_ITEM_FAST(float5_25, MSG_A_TRAVEL, &planner.settings.travel_acceleration, 25, max_accel);
424 424
 
425 425
     #define EDIT_AMAX(Q,L) EDIT_ITEM_FAST(long5_25, MSG_AMAX_##Q, &planner.settings.max_acceleration_mm_per_s2[_AXIS(Q)], L, max_accel_edit_scaled[_AXIS(Q)], []{ planner.reset_acceleration_rates(); })
426
-    LINEAR_AXIS_CODE(
426
+    NUM_AXIS_CODE(
427 427
       EDIT_AMAX(A, 100), EDIT_AMAX(B, 100), EDIT_AMAX(C, 10),
428
-      EDIT_AMAX(I,  10), EDIT_AMAX(J,  10), EDIT_AMAX(K, 10)
428
+      EDIT_AMAX(I,  10), EDIT_AMAX(J,  10), EDIT_AMAX(K, 10),
429
+      EDIT_AMAX(U,  10), EDIT_AMAX(V,  10), EDIT_AMAX(W, 10)
429 430
     );
430 431
 
431 432
     #if ENABLED(DISTINCT_E_FACTORS)
@@ -468,9 +469,10 @@ void menu_backlash();
468 469
         #elif ENABLED(LIMITED_JERK_EDITING)
469 470
           { LOGICAL_AXIS_LIST((DEFAULT_EJERK) * 2,
470 471
                               (DEFAULT_XJERK) * 2, (DEFAULT_YJERK) * 2, (DEFAULT_ZJERK) * 2,
471
-                              (DEFAULT_IJERK) * 2, (DEFAULT_JJERK) * 2, (DEFAULT_KJERK) * 2) }
472
+                              (DEFAULT_IJERK) * 2, (DEFAULT_JJERK) * 2, (DEFAULT_KJERK) * 2,
473
+                              (DEFAULT_UJERK) * 2, (DEFAULT_VJERK) * 2, (DEFAULT_WJERK) * 2) }
472 474
         #else
473
-          { LOGICAL_AXIS_LIST(990, 990, 990, 990, 990, 990, 990) }
475
+          { LOGICAL_AXIS_LIST(990, 990, 990, 990, 990, 990, 990, 990, 990, 990) }
474 476
         #endif
475 477
       ;
476 478
       #define EDIT_JERK(N) EDIT_ITEM_FAST(float3, MSG_V##N##_JERK, &planner.max_jerk[_AXIS(N)], 1, max_jerk_edit[_AXIS(N)])
@@ -479,9 +481,10 @@ void menu_backlash();
479 481
       #else
480 482
         #define EDIT_JERK_C() EDIT_ITEM_FAST(float52sign, MSG_VC_JERK, &planner.max_jerk.c, 0.1f, max_jerk_edit.c)
481 483
       #endif
482
-      LINEAR_AXIS_CODE(
484
+      NUM_AXIS_CODE(
483 485
         EDIT_JERK(A), EDIT_JERK(B), EDIT_JERK_C(),
484
-        EDIT_JERK(I), EDIT_JERK(J), EDIT_JERK(K)
486
+        EDIT_JERK(I), EDIT_JERK(J), EDIT_JERK(K),
487
+        EDIT_JERK(U), EDIT_JERK(V), EDIT_JERK(W)
485 488
       );
486 489
 
487 490
       #if HAS_EXTRUDERS
@@ -524,9 +527,10 @@ void menu_advanced_steps_per_mm() {
524 527
   BACK_ITEM(MSG_ADVANCED_SETTINGS);
525 528
 
526 529
   #define EDIT_QSTEPS(Q) EDIT_ITEM_FAST(float61, MSG_##Q##_STEPS, &planner.settings.axis_steps_per_mm[_AXIS(Q)], 5, 9999, []{ planner.refresh_positioning(); })
527
-  LINEAR_AXIS_CODE(
530
+  NUM_AXIS_CODE(
528 531
     EDIT_QSTEPS(A), EDIT_QSTEPS(B), EDIT_QSTEPS(C),
529
-    EDIT_QSTEPS(I), EDIT_QSTEPS(J), EDIT_QSTEPS(K)
532
+    EDIT_QSTEPS(I), EDIT_QSTEPS(J), EDIT_QSTEPS(K),
533
+    EDIT_QSTEPS(U), EDIT_QSTEPS(V), EDIT_QSTEPS(W)
530 534
   );
531 535
 
532 536
   #if ENABLED(DISTINCT_E_FACTORS)

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

@@ -66,6 +66,15 @@ void menu_backlash() {
66 66
   #if HAS_K_AXIS && _CAN_CALI(K)
67 67
     EDIT_BACKLASH_DISTANCE(K);
68 68
   #endif
69
+  #if HAS_U_AXIS && _CAN_CALI(U)
70
+    EDIT_BACKLASH_DISTANCE(U);
71
+  #endif
72
+  #if HAS_V_AXIS && _CAN_CALI(V)
73
+    EDIT_BACKLASH_DISTANCE(V);
74
+  #endif
75
+  #if HAS_W_AXIS && _CAN_CALI(W)
76
+    EDIT_BACKLASH_DISTANCE(W);
77
+  #endif
69 78
 
70 79
   #ifdef BACKLASH_SMOOTHING_MM
71 80
     editable.decimal = backlash.get_smoothing_mm();

+ 36
- 0
Marlin/src/lcd/menu/menu_motion.cpp View File

@@ -106,6 +106,15 @@ void lcd_move_x() { _lcd_move_xyz(GET_TEXT(MSG_MOVE_X), X_AXIS); }
106 106
 #if HAS_K_AXIS
107 107
   void lcd_move_k() { _lcd_move_xyz(GET_TEXT(MSG_MOVE_K), K_AXIS); }
108 108
 #endif
109
+#if HAS_U_AXIS
110
+  void lcd_move_u() { _lcd_move_xyz(GET_TEXT(MSG_MOVE_U), U_AXIS); }
111
+#endif
112
+#if HAS_V_AXIS
113
+  void lcd_move_v() { _lcd_move_xyz(GET_TEXT(MSG_MOVE_V), V_AXIS); }
114
+#endif
115
+#if HAS_W_AXIS
116
+  void lcd_move_w() { _lcd_move_xyz(GET_TEXT(MSG_MOVE_W), W_AXIS); }
117
+#endif
109 118
 
110 119
 #if E_MANUAL
111 120
 
@@ -263,6 +272,15 @@ void menu_move() {
263 272
     #if HAS_K_AXIS
264 273
       SUBMENU(MSG_MOVE_K, []{ _menu_move_distance(K_AXIS, lcd_move_k); });
265 274
     #endif
275
+    #if HAS_U_AXIS
276
+      SUBMENU(MSG_MOVE_U, []{ _menu_move_distance(U_AXIS, lcd_move_u); });
277
+    #endif
278
+    #if HAS_V_AXIS
279
+      SUBMENU(MSG_MOVE_V, []{ _menu_move_distance(V_AXIS, lcd_move_v); });
280
+    #endif
281
+    #if HAS_W_AXIS
282
+      SUBMENU(MSG_MOVE_W, []{ _menu_move_distance(W_AXIS, lcd_move_w); });
283
+    #endif
266 284
   }
267 285
   else
268 286
     GCODES_ITEM(MSG_AUTO_HOME, G28_STR);
@@ -354,6 +372,15 @@ void menu_move() {
354 372
     #if HAS_K_AXIS
355 373
       GCODES_ITEM_N(K_AXIS, MSG_AUTO_HOME_A, PSTR("G28" STR_K));
356 374
     #endif
375
+    #if HAS_U_AXIS
376
+      GCODES_ITEM_N(U_AXIS, MSG_AUTO_HOME_A, PSTR("G28" STR_U));
377
+    #endif
378
+    #if HAS_V_AXIS
379
+      GCODES_ITEM_N(V_AXIS, MSG_AUTO_HOME_A, PSTR("G28" STR_V));
380
+    #endif
381
+    #if HAS_W_AXIS
382
+      GCODES_ITEM_N(W_AXIS, MSG_AUTO_HOME_A, PSTR("G28" STR_W));
383
+    #endif
357 384
 
358 385
     END_MENU();
359 386
   }
@@ -407,6 +434,15 @@ void menu_motion() {
407 434
       #if HAS_K_AXIS
408 435
         GCODES_ITEM_N(K_AXIS, MSG_AUTO_HOME_A, PSTR("G28" STR_K));
409 436
       #endif
437
+      #if HAS_U_AXIS
438
+        GCODES_ITEM_N(U_AXIS, MSG_AUTO_HOME_A, PSTR("G28" STR_U));
439
+      #endif
440
+      #if HAS_V_AXIS
441
+        GCODES_ITEM_N(V_AXIS, MSG_AUTO_HOME_A, PSTR("G28" STR_V));
442
+      #endif
443
+      #if HAS_W_AXIS
444
+        GCODES_ITEM_N(W_AXIS, MSG_AUTO_HOME_A, PSTR("G28" STR_W));
445
+      #endif
410 446
     #endif
411 447
   #endif
412 448
 

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

@@ -134,6 +134,9 @@ void menu_tmc_current() {
134 134
     TERN_( I_SENSORLESS, TMC_EDIT_STORED_SGT(I));
135 135
     TERN_( J_SENSORLESS, TMC_EDIT_STORED_SGT(J));
136 136
     TERN_( K_SENSORLESS, TMC_EDIT_STORED_SGT(K));
137
+    TERN_( U_SENSORLESS, TMC_EDIT_STORED_SGT(U));
138
+    TERN_( V_SENSORLESS, TMC_EDIT_STORED_SGT(V));
139
+    TERN_( W_SENSORLESS, TMC_EDIT_STORED_SGT(W));
137 140
     END_MENU();
138 141
   }
139 142
 

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

@@ -37,7 +37,7 @@ L64XX_Marlin L64xxManager;
37 37
 #include "../../module/planner.h"
38 38
 #include "../../HAL/shared/Delay.h"
39 39
 
40
-static const char LINEAR_AXIS_LIST(
40
+static const char NUM_AXIS_LIST(
41 41
                    str_X[] PROGMEM = "X ",          str_Y[] PROGMEM = "Y ",          str_Z[] PROGMEM = "Z ",
42 42
                    str_I[] PROGMEM = STR_I " ", str_J[] PROGMEM = STR_J " ", str_K[] PROGMEM = STR_K " "
43 43
                  ),
@@ -53,7 +53,7 @@ static const char LINEAR_AXIS_LIST(
53 53
 
54 54
 #define _EN_ITEM(N) , str_E##N
55 55
 PGM_P const L64XX_Marlin::index_to_axis[] PROGMEM = {
56
-  LINEAR_AXIS_LIST(str_X, str_Y, str_Z, str_I, str_J, str_K),
56
+  NUM_AXIS_LIST(str_X, str_Y, str_Z, str_I, str_J, str_K),
57 57
   str_X2, str_Y2, str_Z2, str_Z3, str_Z4
58 58
   REPEAT(E_STEPPERS, _EN_ITEM)
59 59
 };
@@ -68,7 +68,7 @@ uint8_t L64XX_Marlin::dir_commands[MAX_L64XX];  // array to hold direction comma
68 68
 
69 69
 #define _EN_ITEM(N) , INVERT_E##N##_DIR
70 70
 const uint8_t L64XX_Marlin::index_to_dir[MAX_L64XX] = {
71
-    LINEAR_AXIS_LIST(INVERT_X_DIR, INVERT_Y_DIR, INVERT_Z_DIR, INVERT_I_DIR, INVERT_J_DIR, INVERT_K_DIR)
71
+    NUM_AXIS_LIST(INVERT_X_DIR, INVERT_Y_DIR, INVERT_Z_DIR, INVERT_I_DIR, INVERT_J_DIR, INVERT_K_DIR)
72 72
   , (INVERT_X_DIR) ^ BOTH(X_DUAL_STEPPER_DRIVERS, INVERT_X2_VS_X_DIR) // X2
73 73
   , (INVERT_Y_DIR) ^ BOTH(Y_DUAL_STEPPER_DRIVERS, INVERT_Y2_VS_Y_DIR) // Y2
74 74
   , (INVERT_Z_DIR) ^ ENABLED(INVERT_Z2_VS_Z_DIR) // Z2

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

@@ -36,7 +36,7 @@
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 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 };
39
+enum L64XX_axis_t : uint8_t { NUM_AXIS_LIST(X, Y, Z, I, J, K), X2, Y2, Z2, Z3, Z4 REPEAT(E_STEPPERS, _EN_ITEM), MAX_L64XX };
40 40
 #undef _EN_ITEM
41 41
 
42 42
 class L64XX_Marlin : public L64XXHelper {

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

@@ -233,6 +233,9 @@ void home_delta() {
233 233
     TERN_(I_SENSORLESS, sensorless_t stealth_states_i = start_sensorless_homing_per_axis(I_AXIS));
234 234
     TERN_(J_SENSORLESS, sensorless_t stealth_states_j = start_sensorless_homing_per_axis(J_AXIS));
235 235
     TERN_(K_SENSORLESS, sensorless_t stealth_states_k = start_sensorless_homing_per_axis(K_AXIS));
236
+    TERN_(U_SENSORLESS, sensorless_t stealth_states_u = start_sensorless_homing_per_axis(U_AXIS));
237
+    TERN_(V_SENSORLESS, sensorless_t stealth_states_v = start_sensorless_homing_per_axis(V_AXIS));
238
+    TERN_(W_SENSORLESS, sensorless_t stealth_states_w = start_sensorless_homing_per_axis(W_AXIS));
236 239
   #endif
237 240
 
238 241
   // Move all carriages together linearly until an endstop is hit.
@@ -249,6 +252,9 @@ void home_delta() {
249 252
     TERN_(I_SENSORLESS, end_sensorless_homing_per_axis(I_AXIS, stealth_states_i));
250 253
     TERN_(J_SENSORLESS, end_sensorless_homing_per_axis(J_AXIS, stealth_states_j));
251 254
     TERN_(K_SENSORLESS, end_sensorless_homing_per_axis(K_AXIS, stealth_states_k));
255
+    TERN_(U_SENSORLESS, end_sensorless_homing_per_axis(U_AXIS, stealth_states_u));
256
+    TERN_(V_SENSORLESS, end_sensorless_homing_per_axis(V_AXIS, stealth_states_v));
257
+    TERN_(W_SENSORLESS, end_sensorless_homing_per_axis(W_AXIS, stealth_states_w));
252 258
   #endif
253 259
 
254 260
   endstops.validate_homing_move();

+ 272
- 6
Marlin/src/module/endstops.cpp View File

@@ -319,6 +319,66 @@ void Endstops::init() {
319 319
     #endif
320 320
   #endif
321 321
 
322
+  #if HAS_U_MIN
323
+    #if ENABLED(ENDSTOPPULLUP_UMIN)
324
+      SET_INPUT_PULLUP(U_MIN_PIN);
325
+    #elif ENABLED(ENDSTOPPULLDOWN_UMIN)
326
+      SET_INPUT_PULLDOWN(U_MIN_PIN);
327
+    #else
328
+      SET_INPUT(U_MIN_PIN);
329
+    #endif
330
+  #endif
331
+
332
+  #if HAS_U_MAX
333
+    #if ENABLED(ENDSTOPPULLUP_UMAX)
334
+      SET_INPUT_PULLUP(U_MAX_PIN);
335
+    #elif ENABLED(ENDSTOPPULLDOWN_UMIN)
336
+      SET_INPUT_PULLDOWN(U_MAX_PIN);
337
+    #else
338
+      SET_INPUT(U_MAX_PIN);
339
+    #endif
340
+  #endif
341
+
342
+  #if HAS_V_MIN
343
+    #if ENABLED(ENDSTOPPULLUP_VMIN)
344
+      SET_INPUT_PULLUP(V_MIN_PIN);
345
+    #elif ENABLED(ENDSTOPPULLDOWN_VMIN)
346
+      SET_INPUT_PULLDOWN(V_MIN_PIN);
347
+    #else
348
+      SET_INPUT(V_MIN_PIN);
349
+    #endif
350
+  #endif
351
+
352
+  #if HAS_V_MAX
353
+    #if ENABLED(ENDSTOPPULLUP_VMAX)
354
+      SET_INPUT_PULLUP(V_MAX_PIN);
355
+    #elif ENABLED(ENDSTOPPULLDOWN_VMIN)
356
+      SET_INPUT_PULLDOWN(V_MAX_PIN);
357
+    #else
358
+      SET_INPUT(V_MAX_PIN);
359
+    #endif
360
+  #endif
361
+
362
+  #if HAS_W_MIN
363
+    #if ENABLED(ENDSTOPPULLUP_WMIN)
364
+      SET_INPUT_PULLUP(W_MIN_PIN);
365
+    #elif ENABLED(ENDSTOPPULLDOWN_WMIN)
366
+      SET_INPUT_PULLDOWN(W_MIN_PIN);
367
+    #else
368
+      SET_INPUT(W_MIN_PIN);
369
+    #endif
370
+  #endif
371
+
372
+  #if HAS_W_MAX
373
+    #if ENABLED(ENDSTOPPULLUP_WMAX)
374
+      SET_INPUT_PULLUP(W_MAX_PIN);
375
+    #elif ENABLED(ENDSTOPPULLDOWN_WMIN)
376
+      SET_INPUT_PULLDOWN(W_MAX_PIN);
377
+    #else
378
+      SET_INPUT(W_MAX_PIN);
379
+    #endif
380
+  #endif
381
+
322 382
   #if PIN_EXISTS(CALIBRATION)
323 383
     #if ENABLED(CALIBRATION_PIN_PULLUP)
324 384
       SET_INPUT_PULLUP(CALIBRATION_PIN);
@@ -424,7 +484,7 @@ void Endstops::event_handler() {
424 484
   prev_hit_state = hit_state;
425 485
   if (hit_state) {
426 486
     #if HAS_STATUS_MESSAGE
427
-      char LINEAR_AXIS_LIST(chrX = ' ', chrY = ' ', chrZ = ' ', chrI = ' ', chrJ = ' ', chrK = ' '),
487
+      char NUM_AXIS_LIST(chrX = ' ', chrY = ' ', chrZ = ' ', chrI = ' ', chrJ = ' ', chrK = ' ', chrU = ' ', chrV = ' ', chrW = ' '),
428 488
            chrP = ' ';
429 489
       #define _SET_STOP_CHAR(A,C) (chr## A = C)
430 490
     #else
@@ -444,16 +504,22 @@ void Endstops::event_handler() {
444 504
     #define ENDSTOP_HIT_TEST_I() _ENDSTOP_HIT_TEST(I,'I')
445 505
     #define ENDSTOP_HIT_TEST_J() _ENDSTOP_HIT_TEST(J,'J')
446 506
     #define ENDSTOP_HIT_TEST_K() _ENDSTOP_HIT_TEST(K,'K')
507
+    #define ENDSTOP_HIT_TEST_U() _ENDSTOP_HIT_TEST(U,'U')
508
+    #define ENDSTOP_HIT_TEST_V() _ENDSTOP_HIT_TEST(V,'V')
509
+    #define ENDSTOP_HIT_TEST_W() _ENDSTOP_HIT_TEST(W,'W')
447 510
 
448 511
     SERIAL_ECHO_START();
449 512
     SERIAL_ECHOPGM(STR_ENDSTOPS_HIT);
450
-    LINEAR_AXIS_CODE(
513
+    NUM_AXIS_CODE(
451 514
        ENDSTOP_HIT_TEST_X(),
452 515
        ENDSTOP_HIT_TEST_Y(),
453 516
        ENDSTOP_HIT_TEST_Z(),
454 517
       _ENDSTOP_HIT_TEST(I,'I'),
455 518
       _ENDSTOP_HIT_TEST(J,'J'),
456
-      _ENDSTOP_HIT_TEST(K,'K')
519
+      _ENDSTOP_HIT_TEST(K,'K'),
520
+      _ENDSTOP_HIT_TEST(U,'U'),
521
+      _ENDSTOP_HIT_TEST(V,'V'),
522
+      _ENDSTOP_HIT_TEST(W,'W')
457 523
     );
458 524
 
459 525
     #if USES_Z_MIN_PROBE_PIN
@@ -464,9 +530,9 @@ void Endstops::event_handler() {
464 530
 
465 531
     TERN_(HAS_STATUS_MESSAGE,
466 532
       ui.status_printf(0,
467
-        F(S_FMT GANG_N_1(LINEAR_AXES, " %c") " %c"),
533
+        F(S_FMT GANG_N_1(NUM_AXES, " %c") " %c"),
468 534
         GET_TEXT(MSG_LCD_ENDSTOPS),
469
-        LINEAR_AXIS_LIST(chrX, chrY, chrZ, chrI, chrJ, chrK), chrP
535
+        NUM_AXIS_LIST(chrX, chrY, chrZ, chrI, chrJ, chrK, chrU, chrV, chrW), chrP
470 536
       )
471 537
     );
472 538
 
@@ -564,6 +630,24 @@ void _O2 Endstops::report_states() {
564 630
   #if HAS_K_MAX
565 631
     ES_REPORT(K_MAX);
566 632
   #endif
633
+  #if HAS_U_MIN
634
+    ES_REPORT(U_MIN);
635
+  #endif
636
+  #if HAS_U_MAX
637
+    ES_REPORT(U_MAX);
638
+  #endif
639
+  #if HAS_V_MIN
640
+    ES_REPORT(V_MIN);
641
+  #endif
642
+  #if HAS_V_MAX
643
+    ES_REPORT(V_MAX);
644
+  #endif
645
+  #if HAS_W_MIN
646
+    ES_REPORT(W_MIN);
647
+  #endif
648
+  #if HAS_W_MAX
649
+    ES_REPORT(W_MAX);
650
+  #endif
567 651
   #if ENABLED(PROBE_ACTIVATION_SWITCH)
568 652
     print_es_state(probe_switch_activated(), F(STR_PROBE_EN));
569 653
   #endif
@@ -649,6 +733,9 @@ void Endstops::update() {
649 733
   #define I_AXIS_HEAD I_AXIS
650 734
   #define J_AXIS_HEAD J_AXIS
651 735
   #define K_AXIS_HEAD K_AXIS
736
+  #define U_AXIS_HEAD U_AXIS
737
+  #define V_AXIS_HEAD V_AXIS
738
+  #define W_AXIS_HEAD W_AXIS
652 739
 
653 740
   /**
654 741
    * Check and update endstops
@@ -835,6 +922,82 @@ void Endstops::update() {
835 922
     #endif
836 923
   #endif
837 924
 
925
+  #if HAS_U_MIN && !U_SPI_SENSORLESS
926
+    #if ENABLED(U_DUAL_ENDSTOPS)
927
+      UPDATE_ENDSTOP_BIT(U, MIN);
928
+      #if HAS_U2_MIN
929
+        UPDATE_ENDSTOP_BIT(U2, MIN);
930
+      #else
931
+        COPY_LIVE_STATE(U_MIN, U2_MIN);
932
+      #endif
933
+    #else
934
+      UPDATE_ENDSTOP_BIT(U, MIN);
935
+    #endif
936
+  #endif
937
+
938
+  #if HAS_U_MAX && !U_SPI_SENSORLESS
939
+    #if ENABLED(U_DUAL_ENDSTOPS)
940
+      UPDATE_ENDSTOP_BIT(U, MAX);
941
+      #if HAS_U2_MAX
942
+        UPDATE_ENDSTOP_BIT(U2, MAX);
943
+      #else
944
+        COPY_LIVE_STATE(U_MAX, U2_MAX);
945
+      #endif
946
+    #else
947
+      UPDATE_ENDSTOP_BIT(U, MAX);
948
+    #endif
949
+  #endif
950
+
951
+  #if HAS_V_MIN && !V_SPI_SENSORLESS
952
+    #if ENABLED(V_DUAL_ENDSTOPS)
953
+      UPDATE_ENDSTOP_BIT(V, MIN);
954
+      #if HAS_V2_MIN
955
+        UPDATE_ENDSTOP_BIT(V2, MIN);
956
+      #else
957
+        COPY_LIVE_STATE(V_MIN, V2_MIN);
958
+      #endif
959
+    #else
960
+      UPDATE_ENDSTOP_BIT(V, MIN);
961
+    #endif
962
+  #endif
963
+  #if HAS_V_MAX && !V_SPI_SENSORLESS
964
+    #if ENABLED(O_DUAL_ENDSTOPS)
965
+      UPDATE_ENDSTOP_BIT(V, MAX);
966
+      #if HAS_V2_MAX
967
+        UPDATE_ENDSTOP_BIT(V2, MAX);
968
+      #else
969
+        COPY_LIVE_STATE(V_MAX, V2_MAX);
970
+      #endif
971
+    #else
972
+      UPDATE_ENDSTOP_BIT(V, MAX);
973
+    #endif
974
+  #endif
975
+
976
+  #if HAS_W_MIN && !W_SPI_SENSORLESS
977
+    #if ENABLED(W_DUAL_ENDSTOPS)
978
+      UPDATE_ENDSTOP_BIT(W, MIN);
979
+      #if HAS_W2_MIN
980
+        UPDATE_ENDSTOP_BIT(W2, MIN);
981
+      #else
982
+        COPY_LIVE_STATE(W_MIN, W2_MIN);
983
+      #endif
984
+    #else
985
+      UPDATE_ENDSTOP_BIT(W, MIN);
986
+    #endif
987
+  #endif
988
+  #if HAS_W_MAX && !W_SPI_SENSORLESS
989
+    #if ENABLED(W_DUAL_ENDSTOPS)
990
+      UPDATE_ENDSTOP_BIT(W, MAX);
991
+      #if HAS_W2_MAX
992
+        UPDATE_ENDSTOP_BIT(W2, MAX);
993
+      #else
994
+        COPY_LIVE_STATE(W_MAX, W2_MAX);
995
+      #endif
996
+    #else
997
+      UPDATE_ENDSTOP_BIT(W, MAX);
998
+    #endif
999
+  #endif
1000
+
838 1001
   #if ENDSTOP_NOISE_THRESHOLD
839 1002
 
840 1003
     /**
@@ -935,7 +1098,7 @@ void Endstops::update() {
935 1098
     #define PROCESS_ENDSTOP_Z(MINMAX) PROCESS_DUAL_ENDSTOP(Z, MINMAX)
936 1099
   #endif
937 1100
 
938
-  #if HAS_G38_PROBE
1101
+  #if HAS_G38_PROBE // TODO (DerAndere): Add support for HAS_I_AXIS
939 1102
     #define _G38_OPEN_STATE TERN(G38_PROBE_AWAY, (G38_move >= 4), LOW)
940 1103
     // For G38 moves check the probe's pin for ALL movement
941 1104
     if (G38_move && TEST_ENDSTOP(_ENDSTOP(Z, TERN(USES_Z_MIN_PROBE_PIN, MIN_PROBE, MIN))) != _G38_OPEN_STATE) {
@@ -1105,6 +1268,51 @@ void Endstops::update() {
1105 1268
       }
1106 1269
     }
1107 1270
   #endif
1271
+
1272
+  #if HAS_U_AXIS
1273
+    if (stepper.axis_is_moving(U_AXIS)) {
1274
+      if (stepper.motor_direction(U_AXIS_HEAD)) { // -direction
1275
+        #if HAS_U_MIN || (U_SPI_SENSORLESS && U_HOME_TO_MIN)
1276
+          PROCESS_ENDSTOP(U, MIN);
1277
+        #endif
1278
+      }
1279
+      else { // +direction
1280
+        #if HAS_U_MAX || (U_SPI_SENSORLESS && U_HOME_TO_MAX)
1281
+          PROCESS_ENDSTOP(U, MAX);
1282
+        #endif
1283
+      }
1284
+    }
1285
+  #endif
1286
+
1287
+  #if HAS_V_AXIS
1288
+    if (stepper.axis_is_moving(V_AXIS)) {
1289
+      if (stepper.motor_direction(V_AXIS_HEAD)) { // -direction
1290
+        #if HAS_V_MIN || (V_SPI_SENSORLESS && V_HOME_TO_MIN)
1291
+          PROCESS_ENDSTOP(V, MIN);
1292
+        #endif
1293
+      }
1294
+      else { // +direction
1295
+        #if HAS_V_MAX || (V_SPI_SENSORLESS && V_HOME_TO_MAX)
1296
+          PROCESS_ENDSTOP(V, MAX);
1297
+        #endif
1298
+      }
1299
+    }
1300
+  #endif
1301
+
1302
+  #if HAS_W_AXIS
1303
+    if (stepper.axis_is_moving(W_AXIS)) {
1304
+      if (stepper.motor_direction(W_AXIS_HEAD)) { // -direction
1305
+        #if HAS_W_MIN || (W_SPI_SENSORLESS && W_HOME_TO_MIN)
1306
+          PROCESS_ENDSTOP(W, MIN);
1307
+        #endif
1308
+      }
1309
+      else { // +direction
1310
+        #if HAS_W_MAX || (W_SPI_SENSORLESS && W_HOME_TO_MAX)
1311
+          PROCESS_ENDSTOP(W, MAX);
1312
+        #endif
1313
+      }
1314
+    }
1315
+  #endif
1108 1316
 } // Endstops::update()
1109 1317
 
1110 1318
 #if ENABLED(SPI_ENDSTOPS)
@@ -1166,6 +1374,24 @@ void Endstops::update() {
1166 1374
         hit = true;
1167 1375
       }
1168 1376
     #endif
1377
+    #if U_SPI_SENSORLESS
1378
+      if (tmc_spi_homing.u && stepperU.test_stall_status()) {
1379
+        SBI(live_state, U_ENDSTOP);
1380
+        hit = true;
1381
+      }
1382
+    #endif
1383
+    #if V_SPI_SENSORLESS
1384
+      if (tmc_spi_homing.v && stepperV.test_stall_status()) {
1385
+        SBI(live_state, V_ENDSTOP);
1386
+        hit = true;
1387
+      }
1388
+    #endif
1389
+    #if W_SPI_SENSORLESS
1390
+      if (tmc_spi_homing.w && stepperW.test_stall_status()) {
1391
+        SBI(live_state, W_ENDSTOP);
1392
+        hit = true;
1393
+      }
1394
+    #endif
1169 1395
 
1170 1396
     if (TERN0(ENDSTOP_INTERRUPTS_FEATURE, hit)) update();
1171 1397
 
@@ -1179,6 +1405,9 @@ void Endstops::update() {
1179 1405
     TERN_(I_SPI_SENSORLESS, CBI(live_state, I_ENDSTOP));
1180 1406
     TERN_(J_SPI_SENSORLESS, CBI(live_state, J_ENDSTOP));
1181 1407
     TERN_(K_SPI_SENSORLESS, CBI(live_state, K_ENDSTOP));
1408
+    TERN_(U_SPI_SENSORLESS, CBI(live_state, U_ENDSTOP));
1409
+    TERN_(V_SPI_SENSORLESS, CBI(live_state, V_ENDSTOP));
1410
+    TERN_(W_SPI_SENSORLESS, CBI(live_state, W_ENDSTOP));
1182 1411
   }
1183 1412
 
1184 1413
 #endif // SPI_ENDSTOPS
@@ -1273,6 +1502,24 @@ void Endstops::update() {
1273 1502
     #if HAS_K_MIN
1274 1503
       ES_GET_STATE(K_MIN);
1275 1504
     #endif
1505
+    #if HAS_U_MAX
1506
+      ES_GET_STATE(U_MAX);
1507
+    #endif
1508
+    #if HAS_U_MIN
1509
+      ES_GET_STATE(U_MIN);
1510
+    #endif
1511
+    #if HAS_V_MAX
1512
+      ES_GET_STATE(V_MAX);
1513
+    #endif
1514
+    #if HAS_V_MIN
1515
+      ES_GET_STATE(V_MIN);
1516
+    #endif
1517
+    #if HAS_W_MAX
1518
+      ES_GET_STATE(W_MAX);
1519
+    #endif
1520
+    #if HAS_W_MIN
1521
+      ES_GET_STATE(W_MIN);
1522
+    #endif
1276 1523
 
1277 1524
     uint16_t endstop_change = live_state_local ^ old_live_state_local;
1278 1525
     #define ES_REPORT_CHANGE(S) if (TEST(endstop_change, S)) SERIAL_ECHOPGM("  " STRINGIFY(S) ":", TEST(live_state_local, S))
@@ -1347,6 +1594,25 @@ void Endstops::update() {
1347 1594
       #if HAS_K_MAX
1348 1595
         ES_REPORT_CHANGE(K_MAX);
1349 1596
       #endif
1597
+      #if HAS_U_MIN
1598
+        ES_REPORT_CHANGE(U_MIN);
1599
+      #endif
1600
+      #if HAS_U_MAX
1601
+        ES_REPORT_CHANGE(U_MAX);
1602
+      #endif
1603
+      #if HAS_V_MIN
1604
+        ES_REPORT_CHANGE(V_MIN);
1605
+      #endif
1606
+      #if HAS_V_MAX
1607
+        ES_REPORT_CHANGE(V_MAX);
1608
+      #endif
1609
+      #if HAS_W_MIN
1610
+        ES_REPORT_CHANGE(W_MIN);
1611
+      #endif
1612
+      #if HAS_W_MAX
1613
+        ES_REPORT_CHANGE(W_MAX);
1614
+      #endif
1615
+
1350 1616
       SERIAL_ECHOLNPGM("\n");
1351 1617
       hal.set_pwm_duty(pin_t(LED_PIN), local_LED_status);
1352 1618
       local_LED_status ^= 255;

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

@@ -45,6 +45,12 @@ enum EndstopEnum : char {
45 45
   _ES_ITEM(HAS_J_MAX, J_MAX)
46 46
   _ES_ITEM(HAS_K_MIN, K_MIN)
47 47
   _ES_ITEM(HAS_K_MAX, K_MAX)
48
+  _ES_ITEM(HAS_U_MIN, U_MIN)
49
+  _ES_ITEM(HAS_U_MAX, U_MAX)
50
+  _ES_ITEM(HAS_V_MIN, V_MIN)
51
+  _ES_ITEM(HAS_V_MAX, V_MAX)
52
+  _ES_ITEM(HAS_W_MIN, W_MIN)
53
+  _ES_ITEM(HAS_W_MAX, W_MAX)
48 54
 
49 55
   // Extra Endstops for XYZ
50 56
   #if ENABLED(X_DUAL_ENDSTOPS)
@@ -234,7 +240,7 @@ class Endstops {
234 240
       typedef struct {
235 241
         union {
236 242
           bool any;
237
-          struct { bool LINEAR_AXIS_LIST(x:1, y:1, z:1, i:1, j:1, k:1); };
243
+          struct { bool NUM_AXIS_LIST(x:1, y:1, z:1, i:1, j:1, k:1); };
238 244
         };
239 245
       } tmc_spi_homing_t;
240 246
       static tmc_spi_homing_t tmc_spi_homing;

+ 208
- 41
Marlin/src/module/motion.cpp View File

@@ -84,7 +84,7 @@ bool relative_mode; // = false;
84 84
   #define Z_INIT_POS Z_HOME_POS
85 85
 #endif
86 86
 
87
-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);
87
+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, U_HOME_POS, V_HOME_POS, W_HOME_POS);
88 88
 
89 89
 /**
90 90
  * Cartesian Destination
@@ -189,13 +189,16 @@ inline void report_more_positions() {
189 189
 inline void report_logical_position(const xyze_pos_t &rpos) {
190 190
   const xyze_pos_t lpos = rpos.asLogical();
191 191
   SERIAL_ECHOPGM_P(
192
-    LIST_N(DOUBLE(LINEAR_AXES),
192
+    LIST_N(DOUBLE(NUM_AXES),
193 193
          X_LBL, lpos.x,
194 194
       SP_Y_LBL, lpos.y,
195 195
       SP_Z_LBL, lpos.z,
196 196
       SP_I_LBL, lpos.i,
197 197
       SP_J_LBL, lpos.j,
198
-      SP_K_LBL, lpos.k
198
+      SP_K_LBL, lpos.k,
199
+      SP_U_LBL, lpos.u,
200
+      SP_V_LBL, lpos.v,
201
+      SP_W_LBL, lpos.w
199 202
     )
200 203
     #if HAS_EXTRUDERS
201 204
       , SP_E_LBL, lpos.e
@@ -210,7 +213,8 @@ void report_real_position() {
210 213
   xyze_pos_t npos = LOGICAL_AXIS_ARRAY(
211 214
     planner.get_axis_position_mm(E_AXIS),
212 215
     cartes.x, cartes.y, cartes.z,
213
-    cartes.i, cartes.j, cartes.k
216
+    cartes.i, cartes.j, cartes.k,
217
+    cartes.u, cartes.v, cartes.w
214 218
   );
215 219
 
216 220
   TERN_(HAS_POSITION_MODIFIERS, planner.unapply_modifiers(npos, true));
@@ -258,13 +262,16 @@ void report_current_position_projected() {
258 262
     const xyz_pos_t lpos = cartes.asLogical();
259 263
 
260 264
     SERIAL_ECHOPGM_P(
261
-      LIST_N(DOUBLE(LINEAR_AXES),
265
+      LIST_N(DOUBLE(NUM_AXES),
262 266
            X_LBL, lpos.x,
263 267
         SP_Y_LBL, lpos.y,
264 268
         SP_Z_LBL, lpos.z,
265 269
         SP_I_LBL, lpos.i,
266 270
         SP_J_LBL, lpos.j,
267
-        SP_K_LBL, lpos.k
271
+        SP_K_LBL, lpos.k,
272
+        SP_U_LBL, lpos.u,
273
+        SP_V_LBL, lpos.v,
274
+        SP_W_LBL, lpos.w
268 275
       )
269 276
       #if HAS_EXTRUDERS
270 277
         , SP_E_LBL, current_position.e
@@ -355,13 +362,16 @@ void get_cartesian_from_steppers() {
355 362
     );
356 363
     cartes.z = planner.get_axis_position_mm(Z_AXIS);
357 364
   #else
358
-    LINEAR_AXIS_CODE(
365
+    NUM_AXIS_CODE(
359 366
       cartes.x = planner.get_axis_position_mm(X_AXIS),
360 367
       cartes.y = planner.get_axis_position_mm(Y_AXIS),
361 368
       cartes.z = planner.get_axis_position_mm(Z_AXIS),
362 369
       cartes.i = planner.get_axis_position_mm(I_AXIS),
363 370
       cartes.j = planner.get_axis_position_mm(J_AXIS),
364
-      cartes.k = planner.get_axis_position_mm(K_AXIS)
371
+      cartes.k = planner.get_axis_position_mm(K_AXIS),
372
+      cartes.u = planner.get_axis_position_mm(U_AXIS),
373
+      cartes.v = planner.get_axis_position_mm(V_AXIS),
374
+      cartes.w = planner.get_axis_position_mm(W_AXIS)
365 375
     );
366 376
   #endif
367 377
 }
@@ -468,24 +478,23 @@ void _internal_move_to_destination(const_feedRate_t fr_mm_s/*=0.0f*/
468 478
  * - Delta may lower Z first to get into the free motion zone.
469 479
  * - Before returning, wait for the planner buffer to empty.
470 480
  */
471
-void do_blocking_move_to(LINEAR_AXIS_ARGS(const float), const_feedRate_t fr_mm_s/*=0.0f*/) {
481
+void do_blocking_move_to(NUM_AXIS_ARGS(const float), const_feedRate_t fr_mm_s/*=0.0f*/) {
472 482
   DEBUG_SECTION(log_move, "do_blocking_move_to", DEBUGGING(LEVELING));
473
-  if (DEBUGGING(LEVELING)) DEBUG_XYZ("> ", LINEAR_AXIS_ARGS());
483
+  if (DEBUGGING(LEVELING)) DEBUG_XYZ("> ", NUM_AXIS_ARGS());
474 484
 
475 485
   const feedRate_t xy_feedrate = fr_mm_s ?: feedRate_t(XY_PROBE_FEEDRATE_MM_S);
476 486
 
477 487
   #if HAS_Z_AXIS
478 488
     const feedRate_t z_feedrate = fr_mm_s ?: homing_feedrate(Z_AXIS);
479 489
   #endif
480
-  #if HAS_I_AXIS
481
-    const feedRate_t i_feedrate = fr_mm_s ?: homing_feedrate(I_AXIS);
482
-  #endif
483
-  #if HAS_J_AXIS
484
-    const feedRate_t j_feedrate = fr_mm_s ?: homing_feedrate(J_AXIS);
485
-  #endif
486
-  #if HAS_K_AXIS
487
-    const feedRate_t k_feedrate = fr_mm_s ?: homing_feedrate(K_AXIS);
488
-  #endif
490
+  SECONDARY_AXIS_CODE(
491
+    const feedRate_t i_feedrate = fr_mm_s ?: homing_feedrate(I_AXIS),
492
+    const feedRate_t j_feedrate = fr_mm_s ?: homing_feedrate(J_AXIS),
493
+    const feedRate_t k_feedrate = fr_mm_s ?: homing_feedrate(K_AXIS),
494
+    const feedRate_t u_feedrate = fr_mm_s ?: homing_feedrate(U_AXIS),
495
+    const feedRate_t v_feedrate = fr_mm_s ?: homing_feedrate(V_AXIS),
496
+    const feedRate_t w_feedrate = fr_mm_s ?: homing_feedrate(W_AXIS)
497
+  );
489 498
 
490 499
   #if IS_KINEMATIC
491 500
     if (!position_is_reachable(x, y)) return;
@@ -554,7 +563,18 @@ void do_blocking_move_to(LINEAR_AXIS_ARGS(const float), const_feedRate_t fr_mm_s
554 563
     #if HAS_K_AXIS
555 564
       current_position.k = k; line_to_current_position(k_feedrate);
556 565
     #endif
557
-    #if HAS_Z_AXIS  // If Z needs to lower, do it after moving XY...
566
+    #if HAS_U_AXIS
567
+      current_position.u = u; line_to_current_position(u_feedrate);
568
+    #endif
569
+    #if HAS_V_AXIS
570
+      current_position.v = v; line_to_current_position(v_feedrate);
571
+    #endif
572
+    #if HAS_W_AXIS
573
+      current_position.w = w; line_to_current_position(w_feedrate);
574
+    #endif
575
+
576
+    #if HAS_Z_AXIS
577
+      // If Z needs to lower, do it after moving XY
558 578
       if (current_position.z > z) { current_position.z = z; line_to_current_position(z_feedrate); }
559 579
     #endif
560 580
 
@@ -564,17 +584,19 @@ void do_blocking_move_to(LINEAR_AXIS_ARGS(const float), const_feedRate_t fr_mm_s
564 584
 }
565 585
 
566 586
 void do_blocking_move_to(const xy_pos_t &raw, const_feedRate_t fr_mm_s/*=0.0f*/) {
567
-  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);
587
+  do_blocking_move_to(NUM_AXIS_LIST(raw.x, raw.y, current_position.z, current_position.i, current_position.j, current_position.k,
588
+                                    current_position.u, current_position.v, current_position.w), fr_mm_s);
568 589
 }
569 590
 void do_blocking_move_to(const xyz_pos_t &raw, const_feedRate_t fr_mm_s/*=0.0f*/) {
570
-  do_blocking_move_to(LINEAR_AXIS_ELEM(raw), fr_mm_s);
591
+  do_blocking_move_to(NUM_AXIS_ELEM(raw), fr_mm_s);
571 592
 }
572 593
 void do_blocking_move_to(const xyze_pos_t &raw, const_feedRate_t fr_mm_s/*=0.0f*/) {
573
-  do_blocking_move_to(LINEAR_AXIS_ELEM(raw), fr_mm_s);
594
+  do_blocking_move_to(NUM_AXIS_ELEM(raw), fr_mm_s);
574 595
 }
575 596
 void do_blocking_move_to_x(const_float_t rx, const_feedRate_t fr_mm_s/*=0.0*/) {
576 597
   do_blocking_move_to(
577
-    LINEAR_AXIS_LIST(rx, current_position.y, current_position.z, current_position.i, current_position.j, current_position.k),
598
+    NUM_AXIS_LIST(rx, current_position.y, current_position.z, current_position.i, current_position.j, current_position.k,
599
+                  current_position.u, current_position.v, current_position.w),
578 600
     fr_mm_s
579 601
   );
580 602
 }
@@ -582,7 +604,8 @@ void do_blocking_move_to_x(const_float_t rx, const_feedRate_t fr_mm_s/*=0.0*/) {
582 604
 #if HAS_Y_AXIS
583 605
   void do_blocking_move_to_y(const_float_t ry, const_feedRate_t fr_mm_s/*=0.0*/) {
584 606
     do_blocking_move_to(
585
-      LINEAR_AXIS_LIST(current_position.x, ry, current_position.z, current_position.i, current_position.j, current_position.k),
607
+      NUM_AXIS_LIST(current_position.x, ry, current_position.z, current_position.i, current_position.j, current_position.k,
608
+                    current_position.u, current_position.v, current_position.w),
586 609
       fr_mm_s
587 610
     );
588 611
   }
@@ -600,7 +623,7 @@ void do_blocking_move_to_x(const_float_t rx, const_feedRate_t fr_mm_s/*=0.0*/) {
600 623
   }
601 624
   void do_blocking_move_to_xyz_i(const xyze_pos_t &raw, const_float_t i, const_feedRate_t fr_mm_s/*=0.0f*/) {
602 625
     do_blocking_move_to(
603
-      LINEAR_AXIS_LIST(raw.x, raw.y, raw.z, i, raw.j, raw.k),
626
+      NUM_AXIS_LIST(raw.x, raw.y, raw.z, i, raw.j, raw.k, raw.u, raw.v, raw.w),
604 627
       fr_mm_s
605 628
     );
606 629
   }
@@ -612,7 +635,7 @@ void do_blocking_move_to_x(const_float_t rx, const_feedRate_t fr_mm_s/*=0.0*/) {
612 635
   }
613 636
   void do_blocking_move_to_xyzi_j(const xyze_pos_t &raw, const_float_t j, const_feedRate_t fr_mm_s/*=0.0f*/) {
614 637
     do_blocking_move_to(
615
-      LINEAR_AXIS_LIST(raw.x, raw.y, raw.z, raw.i, j, raw.k),
638
+      NUM_AXIS_LIST(raw.x, raw.y, raw.z, raw.i, j, raw.k, raw.u, raw.v, raw.w),
616 639
       fr_mm_s
617 640
     );
618 641
   }
@@ -624,7 +647,43 @@ void do_blocking_move_to_x(const_float_t rx, const_feedRate_t fr_mm_s/*=0.0*/) {
624 647
   }
625 648
   void do_blocking_move_to_xyzij_k(const xyze_pos_t &raw, const_float_t k, const_feedRate_t fr_mm_s/*=0.0f*/) {
626 649
     do_blocking_move_to(
627
-      LINEAR_AXIS_LIST(raw.x, raw.y, raw.z, raw.i, raw.j, k),
650
+      NUM_AXIS_LIST(raw.x, raw.y, raw.z, raw.i, raw.j, k, raw.u, raw.v, raw.w),
651
+      fr_mm_s
652
+    );
653
+  }
654
+#endif
655
+
656
+#if HAS_U_AXIS
657
+  void do_blocking_move_to_u(const_float_t ru, const_feedRate_t fr_mm_s/*=0.0*/) {
658
+    do_blocking_move_to_xyzijk_u(current_position, ru, fr_mm_s);
659
+  }
660
+  void do_blocking_move_to_xyzijk_u(const xyze_pos_t &raw, const_float_t u, const_feedRate_t fr_mm_s/*=0.0f*/) {
661
+    do_blocking_move_to(
662
+      NUM_AXIS_LIST(raw.x, raw.y, raw.z, raw.i, raw.j, raw.k, u, raw.v, raw.w),
663
+      fr_mm_s
664
+    );
665
+  }
666
+#endif
667
+
668
+#if HAS_V_AXIS
669
+  void do_blocking_move_to_v(const_float_t rv, const_feedRate_t fr_mm_s/*=0.0*/) {
670
+    do_blocking_move_to_xyzijku_v(current_position, rv, fr_mm_s);
671
+  }
672
+  void do_blocking_move_to_xyzijku_v(const xyze_pos_t &raw, const_float_t v, const_feedRate_t fr_mm_s/*=0.0f*/) {
673
+    do_blocking_move_to(
674
+      NUM_AXIS_LIST(raw.x, raw.y, raw.z, raw.i, raw.j, raw.k, raw.u, v, raw.w),
675
+      fr_mm_s
676
+    );
677
+  }
678
+#endif
679
+
680
+#if HAS_W_AXIS
681
+  void do_blocking_move_to_w(const_float_t rw, const_feedRate_t fr_mm_s/*=0.0*/) {
682
+    do_blocking_move_to_xyzijkuv_w(current_position, rw, fr_mm_s);
683
+  }
684
+  void do_blocking_move_to_xyzijkuv_w(const xyze_pos_t &raw, const_float_t w, const_feedRate_t fr_mm_s/*=0.0f*/) {
685
+    do_blocking_move_to(
686
+      NUM_AXIS_LIST(raw.x, raw.y, raw.z, raw.i, raw.j, raw.k, raw.u, raw.v, w),
628 687
       fr_mm_s
629 688
     );
630 689
   }
@@ -633,7 +692,8 @@ void do_blocking_move_to_x(const_float_t rx, const_feedRate_t fr_mm_s/*=0.0*/) {
633 692
 #if HAS_Y_AXIS
634 693
   void do_blocking_move_to_xy(const_float_t rx, const_float_t ry, const_feedRate_t fr_mm_s/*=0.0*/) {
635 694
     do_blocking_move_to(
636
-      LINEAR_AXIS_LIST(rx, ry, current_position.z, current_position.i, current_position.j, current_position.k),
695
+      NUM_AXIS_LIST(rx, ry, current_position.z, current_position.i, current_position.j, current_position.k,
696
+                    current_position.u, current_position.v, current_position.w),
637 697
       fr_mm_s
638 698
     );
639 699
   }
@@ -645,7 +705,8 @@ void do_blocking_move_to_x(const_float_t rx, const_feedRate_t fr_mm_s/*=0.0*/) {
645 705
 #if HAS_Z_AXIS
646 706
   void do_blocking_move_to_xy_z(const xy_pos_t &raw, const_float_t z, const_feedRate_t fr_mm_s/*=0.0f*/) {
647 707
     do_blocking_move_to(
648
-      LINEAR_AXIS_LIST(raw.x, raw.y, z, current_position.i, current_position.j, current_position.k),
708
+      NUM_AXIS_LIST(raw.x, raw.y, z, current_position.i, current_position.j, current_position.k,
709
+                    current_position.u, current_position.v, current_position.w),
649 710
       fr_mm_s
650 711
     );
651 712
   }
@@ -680,8 +741,8 @@ void restore_feedrate_and_scaling() {
680 741
   // Software Endstops are based on the configured limits.
681 742
   soft_endstops_t soft_endstop = {
682 743
     true, false,
683
-    LINEAR_AXIS_ARRAY(X_MIN_POS, Y_MIN_POS, Z_MIN_POS, I_MIN_POS, J_MIN_POS, K_MIN_POS),
684
-    LINEAR_AXIS_ARRAY(X_MAX_BED, Y_MAX_BED, Z_MAX_POS, I_MAX_POS, J_MAX_POS, K_MAX_POS)
744
+    NUM_AXIS_ARRAY(X_MIN_POS, Y_MIN_POS, Z_MIN_POS, I_MIN_POS, J_MIN_POS, K_MIN_POS, U_MIN_POS, V_MIN_POS, W_MIN_POS),
745
+    NUM_AXIS_ARRAY(X_MAX_BED, Y_MAX_BED, Z_MAX_POS, I_MAX_POS, J_MAX_POS, K_MAX_POS, U_MAX_POS, V_MAX_POS, W_MAX_POS)
685 746
   };
686 747
 
687 748
   /**
@@ -860,6 +921,36 @@ void restore_feedrate_and_scaling() {
860 921
         #endif
861 922
       }
862 923
     #endif
924
+    #if HAS_U_AXIS
925
+      if (axis_was_homed(U_AXIS)) {
926
+        #if !HAS_SOFTWARE_ENDSTOPS || ENABLED(MIN_SOFTWARE_ENDSTOP_U)
927
+          NOLESS(target.u, soft_endstop.min.u);
928
+        #endif
929
+        #if !HAS_SOFTWARE_ENDSTOPS || ENABLED(MAX_SOFTWARE_ENDSTOP_U)
930
+          NOMORE(target.u, soft_endstop.max.u);
931
+        #endif
932
+      }
933
+    #endif
934
+    #if HAS_V_AXIS
935
+      if (axis_was_homed(V_AXIS)) {
936
+        #if !HAS_SOFTWARE_ENDSTOPS || ENABLED(MIN_SOFTWARE_ENDSTOP_V)
937
+          NOLESS(target.v, soft_endstop.min.v);
938
+        #endif
939
+        #if !HAS_SOFTWARE_ENDSTOPS || ENABLED(MAX_SOFTWARE_ENDSTOP_V)
940
+          NOMORE(target.v, soft_endstop.max.v);
941
+        #endif
942
+      }
943
+    #endif
944
+    #if HAS_W_AXIS
945
+      if (axis_was_homed(W_AXIS)) {
946
+        #if !HAS_SOFTWARE_ENDSTOPS || ENABLED(MIN_SOFTWARE_ENDSTOP_W)
947
+          NOLESS(target.w, soft_endstop.min.w);
948
+        #endif
949
+        #if !HAS_SOFTWARE_ENDSTOPS || ENABLED(MAX_SOFTWARE_ENDSTOP_W)
950
+          NOMORE(target.w, soft_endstop.max.w);
951
+        #endif
952
+      }
953
+    #endif
863 954
   }
864 955
 
865 956
 #else // !HAS_SOFTWARE_ENDSTOPS
@@ -1297,9 +1388,10 @@ void prepare_line_to_destination() {
1297 1388
         CBI(b, a);
1298 1389
     };
1299 1390
     // Clear test bits that are trusted
1300
-    LINEAR_AXIS_CODE(
1391
+    NUM_AXIS_CODE(
1301 1392
       set_should(axis_bits, X_AXIS), set_should(axis_bits, Y_AXIS), set_should(axis_bits, Z_AXIS),
1302
-      set_should(axis_bits, I_AXIS), set_should(axis_bits, J_AXIS), set_should(axis_bits, K_AXIS)
1393
+      set_should(axis_bits, I_AXIS), set_should(axis_bits, J_AXIS), set_should(axis_bits, K_AXIS),
1394
+      set_should(axis_bits, U_AXIS), set_should(axis_bits, V_AXIS), set_should(axis_bits, W_AXIS)
1303 1395
     );
1304 1396
     return axis_bits;
1305 1397
   }
@@ -1309,13 +1401,16 @@ void prepare_line_to_destination() {
1309 1401
       PGM_P home_first = GET_TEXT(MSG_HOME_FIRST);
1310 1402
       char msg[strlen_P(home_first)+1];
1311 1403
       sprintf_P(msg, home_first,
1312
-        LINEAR_AXIS_LIST(
1313
-          TEST(axis_bits, X_AXIS) ? "X" : "",
1314
-          TEST(axis_bits, Y_AXIS) ? "Y" : "",
1315
-          TEST(axis_bits, Z_AXIS) ? "Z" : "",
1404
+        NUM_AXIS_LIST(
1405
+          TEST(axis_bits, X_AXIS) ? STR_A : "",
1406
+          TEST(axis_bits, Y_AXIS) ? STR_B : "",
1407
+          TEST(axis_bits, Z_AXIS) ? STR_C : "",
1316 1408
           TEST(axis_bits, I_AXIS) ? STR_I : "",
1317 1409
           TEST(axis_bits, J_AXIS) ? STR_J : "",
1318
-          TEST(axis_bits, K_AXIS) ? STR_K : ""
1410
+          TEST(axis_bits, K_AXIS) ? STR_K : "",
1411
+          TEST(axis_bits, U_AXIS) ? STR_U : "",
1412
+          TEST(axis_bits, V_AXIS) ? STR_V : "",
1413
+          TEST(axis_bits, W_AXIS) ? STR_W : ""
1319 1414
         )
1320 1415
       );
1321 1416
       SERIAL_ECHO_START();
@@ -1395,6 +1490,15 @@ void prepare_line_to_destination() {
1395 1490
         #if K_SENSORLESS
1396 1491
           case K_AXIS: stealth_states.k = tmc_enable_stallguard(stepperK); break;
1397 1492
         #endif
1493
+        #if U_SENSORLESS
1494
+          case U_AXIS: stealth_states.u = tmc_enable_stallguard(stepperU); break;
1495
+        #endif
1496
+        #if V_SENSORLESS
1497
+          case V_AXIS: stealth_states.v = tmc_enable_stallguard(stepperV); break;
1498
+        #endif
1499
+        #if W_SENSORLESS
1500
+          case W_AXIS: stealth_states.w = tmc_enable_stallguard(stepperW); break;
1501
+        #endif
1398 1502
       }
1399 1503
 
1400 1504
       #if ENABLED(SPI_ENDSTOPS)
@@ -1415,6 +1519,15 @@ void prepare_line_to_destination() {
1415 1519
           #if HAS_K_AXIS
1416 1520
             case K_AXIS: if (ENABLED(K_SPI_SENSORLESS)) endstops.tmc_spi_homing.k = true; break;
1417 1521
           #endif
1522
+          #if HAS_U_AXIS
1523
+            case U_AXIS: if (ENABLED(U_SPI_SENSORLESS)) endstops.tmc_spi_homing.u = true; break;
1524
+          #endif
1525
+          #if HAS_V_AXIS
1526
+            case V_AXIS: if (ENABLED(V_SPI_SENSORLESS)) endstops.tmc_spi_homing.v = true; break;
1527
+          #endif
1528
+          #if HAS_W_AXIS
1529
+            case W_AXIS: if (ENABLED(W_SPI_SENSORLESS)) endstops.tmc_spi_homing.w = true; break;
1530
+          #endif
1418 1531
           default: break;
1419 1532
         }
1420 1533
       #endif
@@ -1471,6 +1584,15 @@ void prepare_line_to_destination() {
1471 1584
         #if K_SENSORLESS
1472 1585
           case K_AXIS: tmc_disable_stallguard(stepperK, enable_stealth.k); break;
1473 1586
         #endif
1587
+        #if U_SENSORLESS
1588
+          case U_AXIS: tmc_disable_stallguard(stepperU, enable_stealth.u); break;
1589
+        #endif
1590
+        #if V_SENSORLESS
1591
+          case V_AXIS: tmc_disable_stallguard(stepperV, enable_stealth.v); break;
1592
+        #endif
1593
+        #if W_SENSORLESS
1594
+          case W_AXIS: tmc_disable_stallguard(stepperW, enable_stealth.w); break;
1595
+        #endif
1474 1596
       }
1475 1597
 
1476 1598
       #if ENABLED(SPI_ENDSTOPS)
@@ -1491,6 +1613,15 @@ void prepare_line_to_destination() {
1491 1613
           #if HAS_K_AXIS
1492 1614
             case K_AXIS: if (ENABLED(K_SPI_SENSORLESS)) endstops.tmc_spi_homing.k = false; break;
1493 1615
           #endif
1616
+          #if HAS_U_AXIS
1617
+            case U_AXIS: if (ENABLED(U_SPI_SENSORLESS)) endstops.tmc_spi_homing.u = false; break;
1618
+          #endif
1619
+          #if HAS_V_AXIS
1620
+            case V_AXIS: if (ENABLED(V_SPI_SENSORLESS)) endstops.tmc_spi_homing.v = false; break;
1621
+          #endif
1622
+          #if HAS_W_AXIS
1623
+            case W_AXIS: if (ENABLED(W_SPI_SENSORLESS)) endstops.tmc_spi_homing.w = false; break;
1624
+          #endif
1494 1625
           default: break;
1495 1626
         }
1496 1627
       #endif
@@ -1667,6 +1798,30 @@ void prepare_line_to_destination() {
1667 1798
             stepperBackoutDir = INVERT_K_DIR ? effectorBackoutDir : -effectorBackoutDir;
1668 1799
             break;
1669 1800
         #endif
1801
+        #ifdef U_MICROSTEPS
1802
+          case U_AXIS:
1803
+            phasePerUStep = PHASE_PER_MICROSTEP(U);
1804
+            phaseCurrent = stepperU.get_microstep_counter();
1805
+            effectorBackoutDir = -U_HOME_DIR;
1806
+            stepperBackoutDir = INVERT_U_DIR ? effectorBackoutDir : -effectorBackoutDir;
1807
+            break;
1808
+        #endif
1809
+        #ifdef V_MICROSTEPS
1810
+          case V_AXIS:
1811
+            phasePerUStep = PHASE_PER_MICROSTEP(V);
1812
+            phaseCurrent = stepperV.get_microstep_counter();
1813
+            effectorBackoutDir = -V_HOME_DIR;
1814
+            stepperBackoutDir = INVERT_V_DIR ? effectorBackoutDir : -effectorBackoutDir;
1815
+            break;
1816
+        #endif
1817
+        #ifdef W_MICROSTEPS
1818
+          case W_AXIS:
1819
+            phasePerUStep = PHASE_PER_MICROSTEP(W);
1820
+            phaseCurrent = stepperW.get_microstep_counter();
1821
+            effectorBackoutDir = -W_HOME_DIR;
1822
+            stepperBackoutDir = INVERT_W_DIR ? effectorBackoutDir : -effectorBackoutDir;
1823
+            break;
1824
+        #endif
1670 1825
         default: return;
1671 1826
       }
1672 1827
 
@@ -1723,13 +1878,16 @@ void prepare_line_to_destination() {
1723 1878
         || TERN0(A##_HOME_TO_MIN, A##_MIN_PIN > -1) \
1724 1879
         || TERN0(A##_HOME_TO_MAX, A##_MAX_PIN > -1) \
1725 1880
       ))
1726
-      if (LINEAR_AXIS_GANG(
1881
+      if (NUM_AXIS_GANG(
1727 1882
            !_CAN_HOME(X),
1728 1883
         && !_CAN_HOME(Y),
1729 1884
         && !_CAN_HOME(Z),
1730 1885
         && !_CAN_HOME(I),
1731 1886
         && !_CAN_HOME(J),
1732
-        && !_CAN_HOME(K))
1887
+        && !_CAN_HOME(K),
1888
+        && !_CAN_HOME(U),
1889
+        && !_CAN_HOME(V),
1890
+        && !_CAN_HOME(W))
1733 1891
       ) return;
1734 1892
     #endif
1735 1893
 
@@ -1822,6 +1980,15 @@ void prepare_line_to_destination() {
1822 1980
           #if HAS_K_AXIS
1823 1981
             case K_AXIS: es = K_ENDSTOP; break;
1824 1982
           #endif
1983
+          #if HAS_U_AXIS
1984
+            case U_AXIS: es = U_ENDSTOP; break;
1985
+          #endif
1986
+          #if HAS_V_AXIS
1987
+            case V_AXIS: es = V_ENDSTOP; break;
1988
+          #endif
1989
+          #if HAS_W_AXIS
1990
+            case W_AXIS: es = W_ENDSTOP; break;
1991
+          #endif
1825 1992
         }
1826 1993
         if (TEST(endstops.state(), es)) {
1827 1994
           SERIAL_ECHO_MSG("Bad ", AS_CHAR(AXIS_CHAR(axis)), " Endstop?");

+ 52
- 7
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]; // TODO: Add support for LINEAR_AXES >= 4
47
+  extern uint8_t saved_slots[(SAVED_POSITIONS + 7) >> 3]; // TODO: Add support for HAS_I_AXIS
48 48
   extern xyze_pos_t stored_position[SAVED_POSITIONS];
49 49
 #endif
50 50
 
@@ -77,13 +77,16 @@ constexpr xyz_feedrate_t homing_feedrate_mm_m = HOMING_FEEDRATE_MM_M;
77 77
 FORCE_INLINE feedRate_t homing_feedrate(const AxisEnum a) {
78 78
   float v = TERN0(HAS_Z_AXIS, homing_feedrate_mm_m.z);
79 79
   #if DISABLED(DELTA)
80
-    LINEAR_AXIS_CODE(
80
+    NUM_AXIS_CODE(
81 81
            if (a == X_AXIS) v = homing_feedrate_mm_m.x,
82 82
       else if (a == Y_AXIS) v = homing_feedrate_mm_m.y,
83 83
       else if (a == Z_AXIS) v = homing_feedrate_mm_m.z,
84 84
       else if (a == I_AXIS) v = homing_feedrate_mm_m.i,
85 85
       else if (a == J_AXIS) v = homing_feedrate_mm_m.j,
86
-      else if (a == K_AXIS) v = homing_feedrate_mm_m.k
86
+      else if (a == K_AXIS) v = homing_feedrate_mm_m.k,
87
+      else if (a == U_AXIS) v = homing_feedrate_mm_m.u,
88
+      else if (a == V_AXIS) v = homing_feedrate_mm_m.v,
89
+      else if (a == W_AXIS) v = homing_feedrate_mm_m.w
87 90
     );
88 91
   #endif
89 92
   return MMM_TO_MMS(v);
@@ -124,7 +127,7 @@ inline int8_t pgm_read_any(const int8_t *p) { return TERN(__IMXRT1062__, *p, pgm
124 127
 
125 128
 #define XYZ_DEFS(T, NAME, OPT) \
126 129
   inline T NAME(const AxisEnum axis) { \
127
-    static const XYZval<T> NAME##_P DEFS_PROGMEM = LINEAR_AXIS_ARRAY(X_##OPT, Y_##OPT, Z_##OPT, I_##OPT, J_##OPT, K_##OPT); \
130
+    static const XYZval<T> NAME##_P DEFS_PROGMEM = NUM_AXIS_ARRAY(X_##OPT, Y_##OPT, Z_##OPT, I_##OPT, J_##OPT, K_##OPT, U_##OPT, V_##OPT, W_##OPT); \
128 131
     return pgm_read_any(&NAME##_P[axis]); \
129 132
   }
130 133
 XYZ_DEFS(float, base_min_pos,   MIN_POS);
@@ -198,6 +201,24 @@ inline float home_bump_mm(const AxisEnum axis) {
198 201
               TERN_(MIN_SOFTWARE_ENDSTOP_K, amax = max.k);
199 202
               break;
200 203
           #endif
204
+          #if HAS_U_AXIS
205
+            case U_AXIS:
206
+              TERN_(MIN_SOFTWARE_ENDSTOP_U, amin = min.u);
207
+              TERN_(MIN_SOFTWARE_ENDSTOP_U, amax = max.u);
208
+              break;
209
+          #endif
210
+          #if HAS_V_AXIS
211
+            case V_AXIS:
212
+              TERN_(MIN_SOFTWARE_ENDSTOP_V, amin = min.v);
213
+              TERN_(MIN_SOFTWARE_ENDSTOP_V, amax = max.v);
214
+              break;
215
+          #endif
216
+          #if HAS_W_AXIS
217
+            case W_AXIS:
218
+              TERN_(MIN_SOFTWARE_ENDSTOP_W, amin = min.w);
219
+              TERN_(MIN_SOFTWARE_ENDSTOP_W, amax = max.w);
220
+              break;
221
+          #endif
201 222
           default: break;
202 223
         }
203 224
       #endif
@@ -323,7 +344,7 @@ inline void prepare_internal_move_to_destination(const_feedRate_t fr_mm_s=0.0f)
323 344
 /**
324 345
  * Blocking movement and shorthand functions
325 346
  */
326
-void do_blocking_move_to(LINEAR_AXIS_ARGS(const float), const_feedRate_t fr_mm_s=0.0f);
347
+void do_blocking_move_to(NUM_AXIS_ARGS(const float), const_feedRate_t fr_mm_s=0.0f);
327 348
 void do_blocking_move_to(const xy_pos_t &raw, const_feedRate_t fr_mm_s=0.0f);
328 349
 void do_blocking_move_to(const xyz_pos_t &raw, const_feedRate_t fr_mm_s=0.0f);
329 350
 void do_blocking_move_to(const xyze_pos_t &raw, const_feedRate_t fr_mm_s=0.0f);
@@ -347,6 +368,18 @@ void do_blocking_move_to_x(const_float_t rx, const_feedRate_t fr_mm_s=0.0f);
347 368
   void do_blocking_move_to_k(const_float_t rk, const_feedRate_t fr_mm_s=0.0f);
348 369
   void do_blocking_move_to_xyzij_k(const xyze_pos_t &raw, const_float_t k, const_feedRate_t fr_mm_s=0.0f);
349 370
 #endif
371
+#if HAS_U_AXIS
372
+  void do_blocking_move_to_u(const_float_t ru, const_feedRate_t fr_mm_s=0.0f);
373
+  void do_blocking_move_to_xyzijk_u(const xyze_pos_t &raw, const_float_t u, const_feedRate_t fr_mm_s=0.0f);
374
+#endif
375
+#if HAS_V_AXIS
376
+  void do_blocking_move_to_v(const_float_t rv, const_feedRate_t fr_mm_s=0.0f);
377
+  void do_blocking_move_to_xyzijku_v(const xyze_pos_t &raw, const_float_t v, const_feedRate_t fr_mm_s=0.0f);
378
+#endif
379
+#if HAS_W_AXIS
380
+  void do_blocking_move_to_w(const float rw, const feedRate_t &fr_mm_s=0.0f);
381
+  void do_blocking_move_to_xyzijkuv_w(const xyze_pos_t &raw, const float w, const feedRate_t &fr_mm_s=0.0f);
382
+#endif
350 383
 
351 384
 #if HAS_Y_AXIS
352 385
   void do_blocking_move_to_xy(const_float_t rx, const_float_t ry, const_feedRate_t fr_mm_s=0.0f);
@@ -374,8 +407,8 @@ void restore_feedrate_and_scaling();
374 407
 /**
375 408
  * Homing and Trusted Axes
376 409
  */
377
-typedef IF<(LINEAR_AXES > 8), uint16_t, uint8_t>::type linear_axis_bits_t;
378
-constexpr linear_axis_bits_t linear_bits = _BV(LINEAR_AXES) - 1;
410
+typedef IF<(NUM_AXES > 8), uint16_t, uint8_t>::type linear_axis_bits_t;
411
+constexpr linear_axis_bits_t linear_bits = _BV(NUM_AXES) - 1;
379 412
 
380 413
 void set_axis_is_at_home(const AxisEnum axis);
381 414
 
@@ -490,6 +523,18 @@ void home_if_needed(const bool keeplev=false);
490 523
   #define LOGICAL_K_POSITION(POS) NATIVE_TO_LOGICAL(POS, K_AXIS)
491 524
   #define RAW_K_POSITION(POS)     LOGICAL_TO_NATIVE(POS, K_AXIS)
492 525
 #endif
526
+#if HAS_U_AXIS
527
+  #define LOGICAL_U_POSITION(POS) NATIVE_TO_LOGICAL(POS, U_AXIS)
528
+  #define RAW_U_POSITION(POS)     LOGICAL_TO_NATIVE(POS, U_AXIS)
529
+#endif
530
+#if HAS_V_AXIS
531
+  #define LOGICAL_V_POSITION(POS) NATIVE_TO_LOGICAL(POS, V_AXIS)
532
+  #define RAW_V_POSITION(POS)     LOGICAL_TO_NATIVE(POS, V_AXIS)
533
+#endif
534
+#if HAS_W_AXIS
535
+  #define LOGICAL_W_POSITION(POS) NATIVE_TO_LOGICAL(POS, W_AXIS)
536
+  #define RAW_W_POSITION(POS)     LOGICAL_TO_NATIVE(POS, W_AXIS)
537
+#endif
493 538
 
494 539
 /**
495 540
  * position_is_reachable family of functions

+ 205
- 90
Marlin/src/module/planner.cpp View File

@@ -1300,7 +1300,7 @@ void Planner::recalculate() {
1300 1300
  */
1301 1301
 void Planner::check_axes_activity() {
1302 1302
 
1303
-  #if ANY(DISABLE_X, DISABLE_Y, DISABLE_Z, DISABLE_I, DISABLE_J, DISABLE_K, DISABLE_E)
1303
+  #if ANY(DISABLE_X, DISABLE_Y, DISABLE_Z, DISABLE_I, DISABLE_J, DISABLE_K, DISABLE_U, DISABLE_V, DISABLE_W, DISABLE_E)
1304 1304
     xyze_bool_t axis_active = { false };
1305 1305
   #endif
1306 1306
 
@@ -1350,7 +1350,10 @@ void Planner::check_axes_activity() {
1350 1350
           if (TERN0(DISABLE_Z, block->steps.z)) axis_active.z = true,
1351 1351
           if (TERN0(DISABLE_I, block->steps.i)) axis_active.i = true,
1352 1352
           if (TERN0(DISABLE_J, block->steps.j)) axis_active.j = true,
1353
-          if (TERN0(DISABLE_K, block->steps.k)) axis_active.k = true
1353
+          if (TERN0(DISABLE_K, block->steps.k)) axis_active.k = true,
1354
+          if (TERN0(DISABLE_U, block->steps.u)) axis_active.u = true,
1355
+          if (TERN0(DISABLE_V, block->steps.v)) axis_active.v = true,
1356
+          if (TERN0(DISABLE_W, block->steps.w)) axis_active.w = true
1354 1357
         );
1355 1358
       }
1356 1359
     #endif
@@ -1385,7 +1388,10 @@ void Planner::check_axes_activity() {
1385 1388
     if (TERN0(DISABLE_Z, !axis_active.z)) stepper.disable_axis(Z_AXIS),
1386 1389
     if (TERN0(DISABLE_I, !axis_active.i)) stepper.disable_axis(I_AXIS),
1387 1390
     if (TERN0(DISABLE_J, !axis_active.j)) stepper.disable_axis(J_AXIS),
1388
-    if (TERN0(DISABLE_K, !axis_active.k)) stepper.disable_axis(K_AXIS)
1391
+    if (TERN0(DISABLE_K, !axis_active.k)) stepper.disable_axis(K_AXIS),
1392
+    if (TERN0(DISABLE_U, !axis_active.u)) stepper.disable_axis(U_AXIS),
1393
+    if (TERN0(DISABLE_V, !axis_active.v)) stepper.disable_axis(V_AXIS),
1394
+    if (TERN0(DISABLE_W, !axis_active.w)) stepper.disable_axis(W_AXIS)
1389 1395
   );
1390 1396
 
1391 1397
   //
@@ -1453,7 +1459,7 @@ void Planner::check_axes_activity() {
1453 1459
     float high = 0.0;
1454 1460
     for (uint8_t b = block_buffer_tail; b != block_buffer_head; b = next_block_index(b)) {
1455 1461
       block_t *block = &block_buffer[b];
1456
-      if (LINEAR_AXIS_GANG(block->steps.x, || block->steps.y, || block->steps.z, || block->steps.i, || block->steps.j, || block->steps.k)) {
1462
+      if (NUM_AXIS_GANG(block->steps.x, || block->steps.y, || block->steps.z, || block->steps.i, || block->steps.j, || block->steps.k, || block->steps.u, || block->steps.v, || block->steps.w)) {
1457 1463
         const float se = (float)block->steps.e / block->step_event_count * SQRT(block->nominal_speed_sqr); // mm/sec;
1458 1464
         NOLESS(high, se);
1459 1465
       }
@@ -1856,15 +1862,22 @@ bool Planner::_populate_block(block_t * const block, bool split_move,
1856 1862
     dc = target.c - position.c,
1857 1863
     di = target.i - position.i,
1858 1864
     dj = target.j - position.j,
1859
-    dk = target.k - position.k
1865
+    dk = target.k - position.k,
1866
+    du = target.u - position.u,
1867
+    dv = target.v - position.v,
1868
+    dw = target.w - position.w
1860 1869
   );
1861 1870
 
1862 1871
   /* <-- add a slash to enable
1863 1872
     SERIAL_ECHOLNPGM(
1864 1873
       "  _populate_block FR:", fr_mm_s,
1865 1874
       " A:", target.a, " (", da, " steps)"
1866
-      " B:", target.b, " (", db, " steps)"
1867
-      " C:", target.c, " (", dc, " steps)"
1875
+      #if HAS_Y_AXIS
1876
+        " B:", target.b, " (", db, " steps)"
1877
+      #endif
1878
+      #if HAS_Z_AXIS
1879
+        " C:", target.c, " (", dc, " steps)"
1880
+      #endif
1868 1881
       #if HAS_I_AXIS
1869 1882
         " " STR_I ":", target.i, " (", di, " steps)"
1870 1883
       #endif
@@ -1874,6 +1887,14 @@ bool Planner::_populate_block(block_t * const block, bool split_move,
1874 1887
       #if HAS_K_AXIS
1875 1888
         " " STR_K ":", target.k, " (", dk, " steps)"
1876 1889
       #endif
1890
+      #if HAS_U_AXIS
1891
+        " " STR_U ":", target.u, " (", du, " steps)"
1892
+      #endif
1893
+      #if HAS_V_AXIS
1894
+        " " STR_V ":", target.v, " (", dv, " steps)"
1895
+      #endif
1896
+      #if HAS_W_AXIS
1897
+        " " STR_W ":", target.w, " (", dw, " steps)"
1877 1898
       #if HAS_EXTRUDERS
1878 1899
         " E:", target.e, " (", de, " steps)"
1879 1900
       #endif
@@ -1938,15 +1959,6 @@ bool Planner::_populate_block(block_t * const block, bool split_move,
1938 1959
       if (db + dc < 0) SBI(dm, B_AXIS);           // Motor B direction
1939 1960
       if (CORESIGN(db - dc) < 0) SBI(dm, C_AXIS); // Motor C direction
1940 1961
     #endif
1941
-    #if HAS_I_AXIS
1942
-      if (di < 0) SBI(dm, I_AXIS);
1943
-    #endif
1944
-    #if HAS_J_AXIS
1945
-      if (dj < 0) SBI(dm, J_AXIS);
1946
-    #endif
1947
-    #if HAS_K_AXIS
1948
-      if (dk < 0) SBI(dm, K_AXIS);
1949
-    #endif
1950 1962
   #elif ENABLED(MARKFORGED_XY)
1951 1963
     if (da + db < 0) SBI(dm, A_AXIS);              // Motor A direction
1952 1964
     if (db < 0) SBI(dm, B_AXIS);                   // Motor B direction
@@ -1954,16 +1966,22 @@ bool Planner::_populate_block(block_t * const block, bool split_move,
1954 1966
     if (da < 0) SBI(dm, A_AXIS);                   // Motor A direction
1955 1967
     if (db + da < 0) SBI(dm, B_AXIS);              // Motor B direction
1956 1968
   #else
1957
-    LINEAR_AXIS_CODE(
1969
+    XYZ_CODE(
1958 1970
       if (da < 0) SBI(dm, X_AXIS),
1959 1971
       if (db < 0) SBI(dm, Y_AXIS),
1960
-      if (dc < 0) SBI(dm, Z_AXIS),
1961
-      if (di < 0) SBI(dm, I_AXIS),
1962
-      if (dj < 0) SBI(dm, J_AXIS),
1963
-      if (dk < 0) SBI(dm, K_AXIS)
1972
+      if (dc < 0) SBI(dm, Z_AXIS)
1964 1973
     );
1965 1974
   #endif
1966 1975
 
1976
+  SECONDARY_AXIS_CODE(
1977
+    if (di < 0) SBI(dm, I_AXIS),
1978
+    if (dj < 0) SBI(dm, J_AXIS),
1979
+    if (dk < 0) SBI(dm, K_AXIS),
1980
+    if (du < 0) SBI(dm, U_AXIS),
1981
+    if (dv < 0) SBI(dm, V_AXIS),
1982
+    if (dw < 0) SBI(dm, W_AXIS)
1983
+  );
1984
+
1967 1985
   #if HAS_EXTRUDERS
1968 1986
     if (de < 0) SBI(dm, E_AXIS);
1969 1987
     const float esteps_float = de * e_factor[extruder];
@@ -1988,20 +2006,20 @@ bool Planner::_populate_block(block_t * const block, bool split_move,
1988 2006
   // Number of steps for each axis
1989 2007
   // See https://www.corexy.com/theory.html
1990 2008
   #if CORE_IS_XY
1991
-    block->steps.set(LINEAR_AXIS_LIST(ABS(da + db), ABS(da - db), ABS(dc), ABS(di), ABS(dj), ABS(dk)));
2009
+    block->steps.set(NUM_AXIS_LIST(ABS(da + db), ABS(da - db), ABS(dc), ABS(di), ABS(dj), ABS(dk), ABS(du), ABS(dv), ABS(dw)));
1992 2010
   #elif CORE_IS_XZ
1993
-    block->steps.set(LINEAR_AXIS_LIST(ABS(da + dc), ABS(db), ABS(da - dc), ABS(di), ABS(dj), ABS(dk)));
2011
+    block->steps.set(NUM_AXIS_LIST(ABS(da + dc), ABS(db), ABS(da - dc), ABS(di), ABS(dj), ABS(dk), ABS(du), ABS(dv), ABS(dw)));
1994 2012
   #elif CORE_IS_YZ
1995
-    block->steps.set(LINEAR_AXIS_LIST(ABS(da), ABS(db + dc), ABS(db - dc), ABS(di), ABS(dj), ABS(dk)));
2013
+    block->steps.set(NUM_AXIS_LIST(ABS(da), ABS(db + dc), ABS(db - dc), ABS(di), ABS(dj), ABS(dk), ABS(du), ABS(dv), ABS(dw)));
1996 2014
   #elif ENABLED(MARKFORGED_XY)
1997
-    block->steps.set(LINEAR_AXIS_LIST(ABS(da + db), ABS(db), ABS(dc), ABS(di), ABS(dj), ABS(dk)));
2015
+    block->steps.set(NUM_AXIS_LIST(ABS(da + db), ABS(db), ABS(dc), ABS(di), ABS(dj), ABS(dk), ABS(du), ABS(dv), ABS(dw)));
1998 2016
   #elif ENABLED(MARKFORGED_YX)
1999
-    block->steps.set(LINEAR_AXIS_LIST(ABS(da), ABS(db + da), ABS(dc), ABS(di), ABS(dj), ABS(dk)));
2017
+    block->steps.set(NUM_AXIS_LIST(ABS(da), ABS(db + da), ABS(dc), ABS(di), ABS(dj), ABS(dk), ABS(du), ABS(dv), ABS(dw)));
2000 2018
   #elif IS_SCARA
2001
-    block->steps.set(LINEAR_AXIS_LIST(ABS(da), ABS(db), ABS(dc), ABS(di), ABS(dj), ABS(dk)));
2019
+    block->steps.set(NUM_AXIS_LIST(ABS(da), ABS(db), ABS(dc), ABS(di), ABS(dj), ABS(dk), ABS(du), ABS(dv), ABS(dw)));
2002 2020
   #else
2003 2021
     // default non-h-bot planning
2004
-    block->steps.set(LINEAR_AXIS_LIST(ABS(da), ABS(db), ABS(dc), ABS(di), ABS(dj), ABS(dk)));
2022
+    block->steps.set(NUM_AXIS_LIST(ABS(da), ABS(db), ABS(dc), ABS(di), ABS(dj), ABS(dk), ABS(du), ABS(dv), ABS(dw)));
2005 2023
   #endif
2006 2024
 
2007 2025
   /**
@@ -2040,9 +2058,6 @@ bool Planner::_populate_block(block_t * const block, bool split_move,
2040 2058
       steps_dist_mm.b      = (db + dc) * mm_per_step[B_AXIS];
2041 2059
       steps_dist_mm.c      = CORESIGN(db - dc) * mm_per_step[C_AXIS];
2042 2060
     #endif
2043
-    TERN_(HAS_I_AXIS, steps_dist_mm.i = di * mm_per_step[I_AXIS]);
2044
-    TERN_(HAS_J_AXIS, steps_dist_mm.j = dj * mm_per_step[J_AXIS]);
2045
-    TERN_(HAS_K_AXIS, steps_dist_mm.k = dk * mm_per_step[K_AXIS]);
2046 2061
   #elif ENABLED(MARKFORGED_XY)
2047 2062
     steps_dist_mm.a      = (da - db) * mm_per_step[A_AXIS];
2048 2063
     steps_dist_mm.b      = db * mm_per_step[B_AXIS];
@@ -2050,27 +2065,40 @@ bool Planner::_populate_block(block_t * const block, bool split_move,
2050 2065
     steps_dist_mm.a      = da * mm_per_step[A_AXIS];
2051 2066
     steps_dist_mm.b      = (db - da) * mm_per_step[B_AXIS];
2052 2067
   #else
2053
-    LINEAR_AXIS_CODE(
2068
+    XYZ_CODE(
2054 2069
       steps_dist_mm.a = da * mm_per_step[A_AXIS],
2055 2070
       steps_dist_mm.b = db * mm_per_step[B_AXIS],
2056
-      steps_dist_mm.c = dc * mm_per_step[C_AXIS],
2057
-      steps_dist_mm.i = di * mm_per_step[I_AXIS],
2058
-      steps_dist_mm.j = dj * mm_per_step[J_AXIS],
2059
-      steps_dist_mm.k = dk * mm_per_step[K_AXIS]
2071
+      steps_dist_mm.c = dc * mm_per_step[C_AXIS]
2060 2072
     );
2061 2073
   #endif
2062 2074
 
2075
+  SECONDARY_AXIS_CODE(
2076
+    steps_dist_mm.i = di * mm_per_step[I_AXIS],
2077
+    steps_dist_mm.j = dj * mm_per_step[J_AXIS],
2078
+    steps_dist_mm.k = dk * mm_per_step[K_AXIS],
2079
+    steps_dist_mm.u = du * mm_per_step[U_AXIS],
2080
+    steps_dist_mm.v = dv * mm_per_step[V_AXIS],
2081
+    steps_dist_mm.w = dw * mm_per_step[W_AXIS]
2082
+  );
2083
+
2063 2084
   TERN_(HAS_EXTRUDERS, steps_dist_mm.e = esteps_float * mm_per_step[E_AXIS_N(extruder)]);
2064 2085
 
2065 2086
   TERN_(LCD_SHOW_E_TOTAL, e_move_accumulator += steps_dist_mm.e);
2066 2087
 
2067
-  if (true LINEAR_AXIS_GANG(
2088
+  #if BOTH(HAS_ROTATIONAL_AXES, INCH_MODE_SUPPORT)
2089
+    bool cartesian_move = true;
2090
+  #endif
2091
+
2092
+  if (true NUM_AXIS_GANG(
2068 2093
       && block->steps.a < MIN_STEPS_PER_SEGMENT,
2069 2094
       && block->steps.b < MIN_STEPS_PER_SEGMENT,
2070 2095
       && block->steps.c < MIN_STEPS_PER_SEGMENT,
2071 2096
       && block->steps.i < MIN_STEPS_PER_SEGMENT,
2072 2097
       && block->steps.j < MIN_STEPS_PER_SEGMENT,
2073
-      && block->steps.k < MIN_STEPS_PER_SEGMENT
2098
+      && block->steps.k < MIN_STEPS_PER_SEGMENT,
2099
+      && block->steps.u < MIN_STEPS_PER_SEGMENT,
2100
+      && block->steps.v < MIN_STEPS_PER_SEGMENT,
2101
+      && block->steps.w < MIN_STEPS_PER_SEGMENT
2074 2102
     )
2075 2103
   ) {
2076 2104
     block->millimeters = TERN0(HAS_EXTRUDERS, ABS(steps_dist_mm.e));
@@ -2079,36 +2107,71 @@ bool Planner::_populate_block(block_t * const block, bool split_move,
2079 2107
     if (millimeters)
2080 2108
       block->millimeters = millimeters;
2081 2109
     else {
2082
-      block->millimeters = SQRT(
2083
-        #if ANY(CORE_IS_XY, MARKFORGED_XY, MARKFORGED_YX)
2084
-          LINEAR_AXIS_GANG(
2085
-              sq(steps_dist_mm.head.x), + sq(steps_dist_mm.head.y), + sq(steps_dist_mm.z),
2086
-            + sq(steps_dist_mm.i),      + sq(steps_dist_mm.j),      + sq(steps_dist_mm.k)
2087
-          )
2088
-        #elif CORE_IS_XZ
2089
-          LINEAR_AXIS_GANG(
2090
-              sq(steps_dist_mm.head.x), + sq(steps_dist_mm.y), + sq(steps_dist_mm.head.z),
2091
-            + sq(steps_dist_mm.i),      + sq(steps_dist_mm.j), + sq(steps_dist_mm.k)
2092
-          )
2093
-        #elif CORE_IS_YZ
2094
-          LINEAR_AXIS_GANG(
2095
-              sq(steps_dist_mm.x)  + sq(steps_dist_mm.head.y) + sq(steps_dist_mm.head.z)
2096
-            + sq(steps_dist_mm.i), + sq(steps_dist_mm.j),     + sq(steps_dist_mm.k)
2097
-          )
2098
-        #elif ENABLED(FOAMCUTTER_XYUV)
2099
-          // Return the largest distance move from either X/Y or I/J plane
2110
+      /**
2111
+       * Distance for interpretation of feedrate in accordance with LinuxCNC (the successor of NIST
2112
+       * RS274NGC interpreter - version 3) and its default CANON_XYZ feed reference mode.
2113
+       * Assume that X, Y, Z are the primary linear axes and U, V, W are secondary linear axes and A, B, C are
2114
+       * rotational axes. Then dX, dY, dZ are the displacements of the primary linear axes and dU, dV, dW are the displacements of linear axes and
2115
+       * dA, dB, dC are the displacements of rotational axes.
2116
+       * The time it takes to execute move command with feedrate F is t = D/F, where D is the total distance, calculated as follows:
2117
+       *   D^2 = dX^2 + dY^2 + dZ^2
2118
+       *   if D^2 == 0 (none of XYZ move but any secondary linear axes move, whether other axes are moved or not):
2119
+       *     D^2 = dU^2 + dV^2 + dW^2
2120
+       *   if D^2 == 0 (only rotational axes are moved):
2121
+       *     D^2 = dA^2 + dB^2 + dC^2
2122
+       */
2123
+      float distance_sqr = (
2124
+        #if ENABLED(ARTICULATED_ROBOT_ARM)
2125
+          // For articulated robots, interpreting feedrate like LinuxCNC would require inverse kinematics. As a workaround, pretend that motors sit on n mutually orthogonal
2126
+          // axes and assume that we could think of distance as magnitude of an n-vector in an n-dimensional Euclidian space.
2127
+          NUM_AXIS_GANG(
2128
+              sq(steps_dist_mm.x), + sq(steps_dist_mm.y), + sq(steps_dist_mm.z),
2129
+            + sq(steps_dist_mm.i), + sq(steps_dist_mm.j), + sq(steps_dist_mm.k),
2130
+            + sq(steps_dist_mm.u), + sq(steps_dist_mm.v), + sq(steps_dist_mm.w)
2131
+          );
2132
+        #elif ENABLED(FOAMCUTTER_XYUV) 
2100 2133
           #if HAS_J_AXIS
2101
-            _MAX(sq(steps_dist_mm.x) + sq(steps_dist_mm.y), sq(steps_dist_mm.i) + sq(steps_dist_mm.j))
2102
-          #else
2134
+          // Special 5 axis kinematics. Return the largest distance move from either X/Y or I/J plane
2135
+          _MAX(sq(steps_dist_mm.x) + sq(steps_dist_mm.y), sq(steps_dist_mm.i) + sq(steps_dist_mm.j))
2136
+          #else // Foamcutter with only two axes (XY)
2103 2137
             sq(steps_dist_mm.x) + sq(steps_dist_mm.y)
2104 2138
           #endif
2139
+        #elif ANY(CORE_IS_XY, MARKFORGED_XY, MARKFORGED_YX)
2140
+          XYZ_GANG(sq(steps_dist_mm.head.x), + sq(steps_dist_mm.head.y), + sq(steps_dist_mm.z))
2141
+        #elif CORE_IS_XZ
2142
+          XYZ_GANG(sq(steps_dist_mm.head.x), + sq(steps_dist_mm.y),      + sq(steps_dist_mm.head.z))
2143
+        #elif CORE_IS_YZ
2144
+          XYZ_GANG(sq(steps_dist_mm.x),      + sq(steps_dist_mm.head.y), + sq(steps_dist_mm.head.z))
2105 2145
         #else
2106
-          LINEAR_AXIS_GANG(
2107
-              sq(steps_dist_mm.x), + sq(steps_dist_mm.y), + sq(steps_dist_mm.z),
2108
-            + sq(steps_dist_mm.i), + sq(steps_dist_mm.j), + sq(steps_dist_mm.k)
2109
-          )
2146
+          XYZ_GANG(sq(steps_dist_mm.x),       + sq(steps_dist_mm.y),      + sq(steps_dist_mm.z))
2110 2147
         #endif
2111 2148
       );
2149
+
2150
+      #if SECONDARY_LINEAR_AXES >= 1 && NONE(FOAMCUTTER_XYUV, ARTICULATED_ROBOT_ARM)
2151
+        if (NEAR_ZERO(distance_sqr)) {
2152
+          // Move does not involve any primary linear axes (xyz) but might involve secondary linear axes
2153
+          distance_sqr = (0.0
2154
+            SECONDARY_AXIS_GANG(
2155
+              IF_DISABLED(AXIS4_ROTATES, + sq(steps_dist_mm.i)),
2156
+              IF_DISABLED(AXIS5_ROTATES, + sq(steps_dist_mm.j)),
2157
+              IF_DISABLED(AXIS6_ROTATES, + sq(steps_dist_mm.k)),
2158
+              IF_DISABLED(AXIS7_ROTATES, + sq(steps_dist_mm.u)),
2159
+              IF_DISABLED(AXIS8_ROTATES, + sq(steps_dist_mm.v)),
2160
+              IF_DISABLED(AXIS9_ROTATES, + sq(steps_dist_mm.w))
2161
+            )
2162
+          );
2163
+        }
2164
+      #endif
2165
+
2166
+      #if HAS_ROTATIONAL_AXES && NONE(FOAMCUTTER_XYUV, ARTICULATED_ROBOT_ARM)
2167
+        if (NEAR_ZERO(distance_sqr)) {
2168
+          // Move involves only rotational axes. Calculate angular distance in accordance with LinuxCNC
2169
+          TERN_(INCH_MODE_SUPPORT, cartesian_move = false);
2170
+          distance_sqr = ROTATIONAL_AXIS_GANG(sq(steps_dist_mm.i), + sq(steps_dist_mm.j), + sq(steps_dist_mm.k), + sq(steps_dist_mm.u), + sq(steps_dist_mm.v), + sq(steps_dist_mm.w));
2171
+        }
2172
+      #endif
2173
+
2174
+      block->millimeters = SQRT(distance_sqr);
2112 2175
     }
2113 2176
 
2114 2177
     /**
@@ -2125,8 +2188,10 @@ bool Planner::_populate_block(block_t * const block, bool split_move,
2125 2188
 
2126 2189
   TERN_(HAS_EXTRUDERS, block->steps.e = esteps);
2127 2190
 
2128
-  block->step_event_count = _MAX(LOGICAL_AXIS_LIST(
2129
-    esteps, block->steps.a, block->steps.b, block->steps.c, block->steps.i, block->steps.j, block->steps.k
2191
+  block->step_event_count = _MAX(LOGICAL_AXIS_LIST(esteps,
2192
+    block->steps.a, block->steps.b, block->steps.c,
2193
+    block->steps.i, block->steps.j, block->steps.k,
2194
+    block->steps.u, block->steps.v, block->steps.w
2130 2195
   ));
2131 2196
 
2132 2197
   // Bail if this is a zero-length block
@@ -2148,13 +2213,16 @@ bool Planner::_populate_block(block_t * const block, bool split_move,
2148 2213
   E_TERN_(block->extruder = extruder);
2149 2214
 
2150 2215
   #if ENABLED(AUTO_POWER_CONTROL)
2151
-    if (LINEAR_AXIS_GANG(
2216
+    if (NUM_AXIS_GANG(
2152 2217
          block->steps.x,
2153 2218
       || block->steps.y,
2154 2219
       || block->steps.z,
2155 2220
       || block->steps.i,
2156 2221
       || block->steps.j,
2157
-      || block->steps.k
2222
+      || block->steps.k,
2223
+      || block->steps.u,
2224
+      || block->steps.v,
2225
+      || block->steps.w
2158 2226
     )) powerManager.power_on();
2159 2227
   #endif
2160 2228
 
@@ -2180,19 +2248,27 @@ bool Planner::_populate_block(block_t * const block, bool split_move,
2180 2248
     }
2181 2249
     if (block->steps.x) stepper.enable_axis(X_AXIS);
2182 2250
   #else
2183
-    LINEAR_AXIS_CODE(
2251
+    NUM_AXIS_CODE(
2184 2252
       if (block->steps.x) stepper.enable_axis(X_AXIS),
2185 2253
       if (block->steps.y) stepper.enable_axis(Y_AXIS),
2186 2254
       if (TERN(Z_LATE_ENABLE, 0, block->steps.z)) stepper.enable_axis(Z_AXIS),
2187 2255
       if (block->steps.i) stepper.enable_axis(I_AXIS),
2188 2256
       if (block->steps.j) stepper.enable_axis(J_AXIS),
2189
-      if (block->steps.k) stepper.enable_axis(K_AXIS)
2257
+      if (block->steps.k) stepper.enable_axis(K_AXIS),
2258
+      if (block->steps.u) stepper.enable_axis(U_AXIS),
2259
+      if (block->steps.v) stepper.enable_axis(V_AXIS),
2260
+      if (block->steps.w) stepper.enable_axis(W_AXIS)
2190 2261
     );
2191 2262
   #endif
2192 2263
   #if ANY(CORE_IS_XY, MARKFORGED_XY, MARKFORGED_YX)
2193
-    TERN_(HAS_I_AXIS, if (block->steps.i) stepper.enable_axis(I_AXIS));
2194
-    TERN_(HAS_J_AXIS, if (block->steps.j) stepper.enable_axis(J_AXIS));
2195
-    TERN_(HAS_K_AXIS, if (block->steps.k) stepper.enable_axis(K_AXIS));
2264
+    SECONDARY_AXIS_CODE(
2265
+      if (block->steps.i) stepper.enable_axis(I_AXIS),
2266
+      if (block->steps.j) stepper.enable_axis(J_AXIS),
2267
+      if (block->steps.k) stepper.enable_axis(K_AXIS),
2268
+      if (block->steps.u) stepper.enable_axis(U_AXIS),
2269
+      if (block->steps.v) stepper.enable_axis(V_AXIS),
2270
+      if (block->steps.w) stepper.enable_axis(W_AXIS)
2271
+    );
2196 2272
   #endif
2197 2273
 
2198 2274
   // Enable extruder(s)
@@ -2239,8 +2315,14 @@ bool Planner::_populate_block(block_t * const block, bool split_move,
2239 2315
   const float inverse_millimeters = 1.0f / block->millimeters;  // Inverse millimeters to remove multiple divides
2240 2316
 
2241 2317
   // Calculate inverse time for this move. No divide by zero due to previous checks.
2242
-  // Example: At 120mm/s a 60mm move takes 0.5s. So this will give 2.0.
2243
-  float inverse_secs = fr_mm_s * inverse_millimeters;
2318
+  // Example: At 120mm/s a 60mm move involving XYZ axes takes 0.5s. So this will give 2.0.
2319
+  // Example 2: At 120°/s a 60° move involving only rotational axes takes 0.5s. So this will give 2.0.
2320
+  float inverse_secs;
2321
+  #if BOTH(HAS_ROTATIONAL_AXES, INCH_MODE_SUPPORT)
2322
+    inverse_secs = inverse_millimeters * (cartesian_move ? fr_mm_s : LINEAR_UNIT(fr_mm_s));
2323
+  #else
2324
+    inverse_secs = fr_mm_s * inverse_millimeters;
2325
+  #endif
2244 2326
 
2245 2327
   // Get the number of non busy movements in queue (non busy means that they can be altered)
2246 2328
   const uint8_t moves_queued = nonbusy_movesplanned();
@@ -2286,13 +2368,13 @@ bool Planner::_populate_block(block_t * const block, bool split_move,
2286 2368
       filwidth.advance_e(steps_dist_mm.e);
2287 2369
   #endif
2288 2370
 
2289
-  // Calculate and limit speed in mm/sec
2371
+  // Calculate and limit speed in mm/sec (linear) or degrees/sec (rotational)
2290 2372
 
2291 2373
   xyze_float_t current_speed;
2292 2374
   float speed_factor = 1.0f; // factor <1 decreases speed
2293 2375
 
2294 2376
   // Linear axes first with less logic
2295
-  LOOP_LINEAR_AXES(i) {
2377
+  LOOP_NUM_AXES(i) {
2296 2378
     current_speed[i] = steps_dist_mm[i] * inverse_secs;
2297 2379
     const feedRate_t cs = ABS(current_speed[i]),
2298 2380
                  max_fr = settings.max_feedrate_mm_s[i];
@@ -2380,9 +2462,10 @@ bool Planner::_populate_block(block_t * const block, bool split_move,
2380 2462
   // Compute and limit the acceleration rate for the trapezoid generator.
2381 2463
   const float steps_per_mm = block->step_event_count * inverse_millimeters;
2382 2464
   uint32_t accel;
2383
-  if (LINEAR_AXIS_GANG(
2465
+  if (NUM_AXIS_GANG(
2384 2466
          !block->steps.a, && !block->steps.b, && !block->steps.c,
2385
-      && !block->steps.i, && !block->steps.j, && !block->steps.k)
2467
+      && !block->steps.i, && !block->steps.j, && !block->steps.k,
2468
+      && !block->steps.u, && !block->steps.v, && !block->steps.w)
2386 2469
   ) {                                                             // Is this a retract / recover move?
2387 2470
     accel = CEIL(settings.retract_acceleration * steps_per_mm);   // Convert to: acceleration steps/sec^2
2388 2471
     TERN_(LIN_ADVANCE, block->use_advance_lead = false);          // No linear advance for simple retract/recover
@@ -2455,7 +2538,10 @@ bool Planner::_populate_block(block_t * const block, bool split_move,
2455 2538
         LIMIT_ACCEL_LONG(C_AXIS, 0),
2456 2539
         LIMIT_ACCEL_LONG(I_AXIS, 0),
2457 2540
         LIMIT_ACCEL_LONG(J_AXIS, 0),
2458
-        LIMIT_ACCEL_LONG(K_AXIS, 0)
2541
+        LIMIT_ACCEL_LONG(K_AXIS, 0),
2542
+        LIMIT_ACCEL_LONG(U_AXIS, 0),
2543
+        LIMIT_ACCEL_LONG(V_AXIS, 0),
2544
+        LIMIT_ACCEL_LONG(W_AXIS, 0)
2459 2545
       );
2460 2546
     }
2461 2547
     else {
@@ -2466,7 +2552,10 @@ bool Planner::_populate_block(block_t * const block, bool split_move,
2466 2552
         LIMIT_ACCEL_FLOAT(C_AXIS, 0),
2467 2553
         LIMIT_ACCEL_FLOAT(I_AXIS, 0),
2468 2554
         LIMIT_ACCEL_FLOAT(J_AXIS, 0),
2469
-        LIMIT_ACCEL_FLOAT(K_AXIS, 0)
2555
+        LIMIT_ACCEL_FLOAT(K_AXIS, 0),
2556
+        LIMIT_ACCEL_FLOAT(U_AXIS, 0),
2557
+        LIMIT_ACCEL_FLOAT(V_AXIS, 0),
2558
+        LIMIT_ACCEL_FLOAT(W_AXIS, 0)
2470 2559
       );
2471 2560
     }
2472 2561
   }
@@ -2531,7 +2620,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move,
2531 2620
       #if HAS_DIST_MM_ARG
2532 2621
         cart_dist_mm
2533 2622
       #else
2534
-        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)
2623
+        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, steps_dist_mm.u, steps_dist_mm.v, steps_dist_mm.w)
2535 2624
       #endif
2536 2625
     ;
2537 2626
 
@@ -2557,7 +2646,10 @@ bool Planner::_populate_block(block_t * const block, bool split_move,
2557 2646
                                  + (-prev_unit_vec.z * unit_vec.z),
2558 2647
                                  + (-prev_unit_vec.i * unit_vec.i),
2559 2648
                                  + (-prev_unit_vec.j * unit_vec.j),
2560
-                                 + (-prev_unit_vec.k * unit_vec.k)
2649
+                                 + (-prev_unit_vec.k * unit_vec.k),
2650
+                                 + (-prev_unit_vec.u * unit_vec.u),
2651
+                                 + (-prev_unit_vec.v * unit_vec.v),
2652
+                                 + (-prev_unit_vec.w * unit_vec.w)
2561 2653
                                );
2562 2654
 
2563 2655
       // NOTE: Computed without any expensive trig, sin() or acos(), by trig half angle identity of cos(theta).
@@ -2704,7 +2796,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move,
2704 2796
     const float extra_xyjerk = TERN0(HAS_EXTRUDERS, de <= 0) ? TRAVEL_EXTRA_XYJERK : 0;
2705 2797
 
2706 2798
     uint8_t limited = 0;
2707
-    TERN(HAS_LINEAR_E_JERK, LOOP_LINEAR_AXES, LOOP_LOGICAL_AXES)(i) {
2799
+    TERN(HAS_LINEAR_E_JERK, LOOP_NUM_AXES, LOOP_LOGICAL_AXES)(i) {
2708 2800
       const float jerk = ABS(current_speed[i]),   // cs : Starting from zero, change in speed for this axis
2709 2801
                   maxj = (max_jerk[i] + (i == X_AXIS || i == Y_AXIS ? extra_xyjerk : 0.0f)); // mj : The max jerk setting for this axis
2710 2802
       if (jerk > maxj) {                          // cs > mj : New current speed too fast?
@@ -2742,7 +2834,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move,
2742 2834
         vmax_junction = previous_nominal_speed;
2743 2835
 
2744 2836
       // Now limit the jerk in all axes.
2745
-      TERN(HAS_LINEAR_E_JERK, LOOP_LINEAR_AXES, LOOP_LOGICAL_AXES)(axis) {
2837
+      TERN(HAS_LINEAR_E_JERK, LOOP_NUM_AXES, LOOP_LOGICAL_AXES)(axis) {
2746 2838
         // Limit an axis. We have to differentiate: coasting, reversal of an axis, full stop.
2747 2839
         float v_exit = previous_speed[axis] * smaller_speed_factor,
2748 2840
               v_entry = current_speed[axis];
@@ -2844,7 +2936,7 @@ void Planner::buffer_sync_block(TERN_(LASER_SYNCHRONOUS_M106_M107, uint8_t sync_
2844 2936
 
2845 2937
   block->position = position;
2846 2938
   #if ENABLED(BACKLASH_COMPENSATION)
2847
-    LOOP_LINEAR_AXES(axis) block->position[axis] += backlash.get_applied_steps((AxisEnum)axis);
2939
+    LOOP_NUM_AXES(axis) block->position[axis] += backlash.get_applied_steps((AxisEnum)axis);
2848 2940
   #endif
2849 2941
 
2850 2942
   #if BOTH(HAS_FAN, LASER_SYNCHRONOUS_M106_M107)
@@ -2906,7 +2998,10 @@ bool Planner::buffer_segment(const abce_pos_t &abce
2906 2998
       int32_t(LROUND(abce.c * settings.axis_steps_per_mm[C_AXIS])),
2907 2999
       int32_t(LROUND(abce.i * settings.axis_steps_per_mm[I_AXIS])),
2908 3000
       int32_t(LROUND(abce.j * settings.axis_steps_per_mm[J_AXIS])),
2909
-      int32_t(LROUND(abce.k * settings.axis_steps_per_mm[K_AXIS]))
3001
+      int32_t(LROUND(abce.k * settings.axis_steps_per_mm[K_AXIS])),
3002
+      int32_t(LROUND(abce.u * settings.axis_steps_per_mm[U_AXIS])),
3003
+      int32_t(LROUND(abce.v * settings.axis_steps_per_mm[V_AXIS])),
3004
+      int32_t(LROUND(abce.w * settings.axis_steps_per_mm[W_AXIS]))
2910 3005
     )
2911 3006
   };
2912 3007
 
@@ -2958,6 +3053,21 @@ bool Planner::buffer_segment(const abce_pos_t &abce
2958 3053
       SERIAL_ECHOPGM(" (", position.k, "->", target.k);
2959 3054
       SERIAL_CHAR(')');
2960 3055
     #endif
3056
+    #if HAS_U_AXIS
3057
+      SERIAL_ECHOPGM_P(SP_U_LBL, abce.u);
3058
+      SERIAL_ECHOPGM(" (", position.u, "->", target.u);
3059
+      SERIAL_CHAR(')');
3060
+    #endif
3061
+    #if HAS_V_AXIS
3062
+      SERIAL_ECHOPGM_P(SP_V_LBL, abce.v);
3063
+      SERIAL_ECHOPGM(" (", position.v, "->", target.v);
3064
+      SERIAL_CHAR(')');
3065
+    #endif
3066
+    #if HAS_W_AXIS
3067
+      SERIAL_ECHOPGM_P(SP_W_LBL, abce.w);
3068
+      SERIAL_ECHOPGM(" (", position.w, "->", target.w);
3069
+      SERIAL_CHAR(')');
3070
+    #endif
2961 3071
     #if HAS_EXTRUDERS
2962 3072
       SERIAL_ECHOPGM_P(SP_E_LBL, abce.e);
2963 3073
       SERIAL_ECHOLNPGM(" (", position.e, "->", target.e, ")");
@@ -3000,12 +3110,14 @@ bool Planner::buffer_line(const xyze_pos_t &cart, const_feedRate_t fr_mm_s, cons
3000 3110
       const xyze_pos_t cart_dist_mm = LOGICAL_AXIS_ARRAY(
3001 3111
         cart.e - position_cart.e,
3002 3112
         cart.x - position_cart.x, cart.y - position_cart.y, cart.z - position_cart.z,
3003
-        cart.i - position_cart.i, cart.j - position_cart.j, cart.j - position_cart.k
3113
+        cart.i - position_cart.i, cart.j - position_cart.j, cart.k - position_cart.k,
3114
+        cart.u - position_cart.u, cart.v - position_cart.v, cart.w - position_cart.w
3004 3115
       );
3005 3116
     #else
3006
-      const xyz_pos_t cart_dist_mm = LINEAR_AXIS_ARRAY(
3117
+      const xyz_pos_t cart_dist_mm = NUM_AXIS_ARRAY(
3007 3118
         cart.x - position_cart.x, cart.y - position_cart.y, cart.z - position_cart.z,
3008
-        cart.i - position_cart.i, cart.j - position_cart.j, cart.j - position_cart.k
3119
+        cart.i - position_cart.i, cart.j - position_cart.j, cart.k - position_cart.k,
3120
+        cart.u - position_cart.u, cart.v - position_cart.v, cart.w - position_cart.w
3009 3121
       );
3010 3122
     #endif
3011 3123
 
@@ -3110,7 +3222,10 @@ void Planner::set_machine_position_mm(const abce_pos_t &abce) {
3110 3222
       LROUND(abce.c * settings.axis_steps_per_mm[C_AXIS]),
3111 3223
       LROUND(abce.i * settings.axis_steps_per_mm[I_AXIS]),
3112 3224
       LROUND(abce.j * settings.axis_steps_per_mm[J_AXIS]),
3113
-      LROUND(abce.k * settings.axis_steps_per_mm[K_AXIS])
3225
+      LROUND(abce.k * settings.axis_steps_per_mm[K_AXIS]),
3226
+      LROUND(abce.u * settings.axis_steps_per_mm[U_AXIS]),
3227
+      LROUND(abce.v * settings.axis_steps_per_mm[V_AXIS]),
3228
+      LROUND(abce.w * settings.axis_steps_per_mm[W_AXIS])
3114 3229
     )
3115 3230
   );
3116 3231
 
@@ -3122,7 +3237,7 @@ void Planner::set_machine_position_mm(const abce_pos_t &abce) {
3122 3237
   else {
3123 3238
     #if ENABLED(BACKLASH_COMPENSATION)
3124 3239
       abce_long_t stepper_pos = position;
3125
-      LOOP_LINEAR_AXES(axis) stepper_pos[axis] += backlash.get_applied_steps((AxisEnum)axis);
3240
+      LOOP_NUM_AXES(axis) stepper_pos[axis] += backlash.get_applied_steps((AxisEnum)axis);
3126 3241
       stepper.set_position(stepper_pos);
3127 3242
     #else
3128 3243
       stepper.set_position(position);

+ 4
- 2
Marlin/src/module/planner.h View File

@@ -84,7 +84,8 @@
84 84
   constexpr xyze_feedrate_t _mf = MANUAL_FEEDRATE,
85 85
            manual_feedrate_mm_s = LOGICAL_AXIS_ARRAY(_mf.e / 60.0f,
86 86
                                                      _mf.x / 60.0f, _mf.y / 60.0f, _mf.z / 60.0f,
87
-                                                     _mf.i / 60.0f, _mf.j / 60.0f, _mf.k / 60.0f);
87
+                                                     _mf.i / 60.0f, _mf.j / 60.0f, _mf.k / 60.0f,
88
+                                                     _mf.u / 60.0f, _mf.v / 60.0f, _mf.w / 60.0f);
88 89
 #endif
89 90
 
90 91
 #if IS_KINEMATIC && HAS_JUNCTION_DEVIATION
@@ -843,7 +844,8 @@ class Planner {
843 844
       const abce_pos_t out = LOGICAL_AXIS_ARRAY(
844 845
         get_axis_position_mm(E_AXIS),
845 846
         get_axis_position_mm(A_AXIS), get_axis_position_mm(B_AXIS), get_axis_position_mm(C_AXIS),
846
-        get_axis_position_mm(I_AXIS), get_axis_position_mm(J_AXIS), get_axis_position_mm(K_AXIS)
847
+        get_axis_position_mm(I_AXIS), get_axis_position_mm(J_AXIS), get_axis_position_mm(K_AXIS),
848
+        get_axis_position_mm(U_AXIS), get_axis_position_mm(V_AXIS), get_axis_position_mm(W_AXIS)
847 849
       );
848 850
       return out;
849 851
     }

+ 4
- 1
Marlin/src/module/planner_bezier.cpp View File

@@ -188,7 +188,10 @@ void cubic_b_spline(
188 188
       interp(position.z, target.z, t),  // FIXME. Wrong, since t is not linear in the distance.
189 189
       interp(position.i, target.i, t),  // FIXME. Wrong, since t is not linear in the distance.
190 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.
191
+      interp(position.k, target.k, t),  // FIXME. Wrong, since t is not linear in the distance.
192
+      interp(position.u, target.u, t),  // FIXME. Wrong, since t is not linear in the distance.
193
+      interp(position.v, target.v, t),  // FIXME. Wrong, since t is not linear in the distance.
194
+      interp(position.w, target.w, t)   // FIXME. Wrong, since t is not linear in the distance.
192 195
     );
193 196
     apply_motion_limits(new_bez);
194 197
     bez_target = new_bez;

+ 4
- 3
Marlin/src/module/probe.cpp View File

@@ -794,9 +794,10 @@ float Probe::probe_at_point(const_float_t rx, const_float_t ry, const ProbePtRai
794 794
   #endif
795 795
 
796 796
   // On delta keep Z below clip height or do_blocking_move_to will abort
797
-  xyz_pos_t npos = LINEAR_AXIS_ARRAY(
797
+  xyz_pos_t npos = NUM_AXIS_ARRAY(
798 798
     rx, ry, TERN(DELTA, _MIN(delta_clip_start_height, current_position.z), current_position.z),
799
-    current_position.i, current_position.j, current_position.k
799
+    current_position.i, current_position.j, current_position.k,
800
+    current_position.u, current_position.v, current_position.w
800 801
   );
801 802
   if (!can_reach(npos, probe_relative)) {
802 803
     if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("Position Not Reachable");
@@ -888,7 +889,7 @@ float Probe::probe_at_point(const_float_t rx, const_float_t ry, const ProbePtRai
888 889
    */
889 890
   void Probe::set_homing_current(const bool onoff) {
890 891
     #define HAS_CURRENT_HOME(N) (defined(N##_CURRENT_HOME) && N##_CURRENT_HOME != N##_CURRENT)
891
-    #if HAS_CURRENT_HOME(X) || HAS_CURRENT_HOME(Y) || HAS_CURRENT_HOME(Z)
892
+    #if HAS_CURRENT_HOME(X) || HAS_CURRENT_HOME(Y) || HAS_CURRENT_HOME(Z) || HAS_CURRENT_HOME(I) || HAS_CURRENT_HOME(J) || HAS_CURRENT_HOME(K) || HAS_CURRENT_HOME(U) || HAS_CURRENT_HOME(V) || HAS_CURRENT_HOME(W)
892 893
       #if ENABLED(DELTA)
893 894
         static int16_t saved_current_X, saved_current_Y;
894 895
       #endif

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

@@ -138,7 +138,7 @@ public:
138 138
 
139 139
   #else
140 140
 
141
-    static constexpr xyz_pos_t offset = xyz_pos_t(LINEAR_AXIS_ARRAY(0, 0, 0, 0, 0, 0)); // See #16767
141
+    static constexpr xyz_pos_t offset = xyz_pos_t(NUM_AXIS_ARRAY(0, 0, 0, 0, 0, 0)); // See #16767
142 142
 
143 143
     static bool set_deployed(const bool) { return false; }
144 144
 

+ 1
- 1
Marlin/src/module/scara.cpp View File

@@ -254,7 +254,7 @@ float segments_per_second = TERN(AXEL_TPARA, TPARA_SEGMENTS_PER_SECOND, SCARA_SE
254 254
     // Do this here all at once for Delta, because
255 255
     // XYZ isn't ABC. Applying this per-tower would
256 256
     // give the impression that they are the same.
257
-    LOOP_LINEAR_AXES(i) set_axis_is_at_home((AxisEnum)i);
257
+    LOOP_NUM_AXES(i) set_axis_is_at_home((AxisEnum)i);
258 258
 
259 259
     sync_plan_position();
260 260
   }

+ 70
- 25
Marlin/src/module/settings.cpp View File

@@ -179,10 +179,10 @@
179 179
 
180 180
 #define _EN_ITEM(N) , E##N
181 181
 
182
-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;
183
-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;
184
-typedef struct {  int16_t LINEAR_AXIS_LIST(X, Y, Z, I, J, K), X2, Y2, Z2, Z3, Z4;                              } tmc_sgt_t;
185
-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;
182
+typedef struct { uint16_t NUM_AXIS_LIST(X, Y, Z, I, J, K, U, V, W), X2, Y2, Z2, Z3, Z4 REPEAT(E_STEPPERS, _EN_ITEM); } tmc_stepper_current_t;
183
+typedef struct { uint32_t NUM_AXIS_LIST(X, Y, Z, I, J, K, U, V, W), X2, Y2, Z2, Z3, Z4 REPEAT(E_STEPPERS, _EN_ITEM); } tmc_hybrid_threshold_t;
184
+typedef struct {  int16_t NUM_AXIS_LIST(X, Y, Z, I, J, K, U, V, W), X2, Y2, Z2, Z3, Z4;                              } tmc_sgt_t;
185
+typedef struct {     bool NUM_AXIS_LIST(X, Y, Z, I, J, K, U, V, W), X2, Y2, Z2, Z3, Z4 REPEAT(E_STEPPERS, _EN_ITEM); } tmc_stealth_enabled_t;
186 186
 
187 187
 #undef _EN_ITEM
188 188
 
@@ -210,7 +210,7 @@ typedef struct SettingsDataStruct {
210 210
   //
211 211
   // DISTINCT_E_FACTORS
212 212
   //
213
-  uint8_t e_factors;                                    // DISTINCT_AXES - LINEAR_AXES
213
+  uint8_t e_factors;                                    // DISTINCT_AXES - NUM_AXES
214 214
 
215 215
   //
216 216
   // Planner settings
@@ -444,7 +444,7 @@ typedef struct SettingsDataStruct {
444 444
   // HAS_MOTOR_CURRENT_PWM
445 445
   //
446 446
   #ifndef MOTOR_CURRENT_COUNT
447
-    #define MOTOR_CURRENT_COUNT LINEAR_AXES
447
+    #define MOTOR_CURRENT_COUNT NUM_AXES
448 448
   #endif
449 449
   uint32_t motor_current_setting[MOTOR_CURRENT_COUNT];  // M907 X Z E ...
450 450
 
@@ -590,7 +590,7 @@ void MarlinSettings::postprocess() {
590 590
   #endif
591 591
 
592 592
   // Software endstops depend on home_offset
593
-  LOOP_LINEAR_AXES(i) {
593
+  LOOP_NUM_AXES(i) {
594 594
     update_workspace_offset((AxisEnum)i);
595 595
     update_software_endstops((AxisEnum)i);
596 596
   }
@@ -738,7 +738,7 @@ void MarlinSettings::postprocess() {
738 738
 
739 739
     working_crc = 0; // clear before first "real data"
740 740
 
741
-    const uint8_t e_factors = DISTINCT_AXES - (LINEAR_AXES);
741
+    const uint8_t e_factors = DISTINCT_AXES - (NUM_AXES);
742 742
     _FIELD_TEST(e_factors);
743 743
     EEPROM_WRITE(e_factors);
744 744
 
@@ -755,7 +755,7 @@ void MarlinSettings::postprocess() {
755 755
           EEPROM_WRITE(dummyf);
756 756
         #endif
757 757
       #else
758
-        const xyze_pos_t planner_max_jerk = LOGICAL_AXIS_ARRAY(float(DEFAULT_EJERK), 10, 10, 0.4, 0.4, 0.4, 0.4);
758
+        const xyze_pos_t planner_max_jerk = LOGICAL_AXIS_ARRAY(float(DEFAULT_EJERK), 10, 10, 0.4, 0.4, 0.4, 0.4, 0.4, 0.4, 0.4);
759 759
         EEPROM_WRITE(planner_max_jerk);
760 760
       #endif
761 761
 
@@ -1234,6 +1234,15 @@ void MarlinSettings::postprocess() {
1234 1234
         #if AXIS_IS_TMC(K)
1235 1235
           tmc_stepper_current.K = stepperK.getMilliamps();
1236 1236
         #endif
1237
+        #if AXIS_IS_TMC(U)
1238
+          tmc_stepper_current.U = stepperU.getMilliamps();
1239
+        #endif
1240
+        #if AXIS_IS_TMC(V)
1241
+          tmc_stepper_current.V = stepperV.getMilliamps();
1242
+        #endif
1243
+        #if AXIS_IS_TMC(W)
1244
+          tmc_stepper_current.W = stepperW.getMilliamps();
1245
+        #endif
1237 1246
         #if AXIS_IS_TMC(X2)
1238 1247
           tmc_stepper_current.X2 = stepperX2.getMilliamps();
1239 1248
         #endif
@@ -1291,6 +1300,9 @@ void MarlinSettings::postprocess() {
1291 1300
         TERN_(I_HAS_STEALTHCHOP,  tmc_hybrid_threshold.I =  stepperI.get_pwm_thrs());
1292 1301
         TERN_(J_HAS_STEALTHCHOP,  tmc_hybrid_threshold.J =  stepperJ.get_pwm_thrs());
1293 1302
         TERN_(K_HAS_STEALTHCHOP,  tmc_hybrid_threshold.K =  stepperK.get_pwm_thrs());
1303
+        TERN_(U_HAS_STEALTHCHOP,  tmc_hybrid_threshold.U =  stepperU.get_pwm_thrs());
1304
+        TERN_(V_HAS_STEALTHCHOP,  tmc_hybrid_threshold.V =  stepperV.get_pwm_thrs());
1305
+        TERN_(W_HAS_STEALTHCHOP,  tmc_hybrid_threshold.W =  stepperW.get_pwm_thrs());
1294 1306
         TERN_(X2_HAS_STEALTHCHOP, tmc_hybrid_threshold.X2 = stepperX2.get_pwm_thrs());
1295 1307
         TERN_(Y2_HAS_STEALTHCHOP, tmc_hybrid_threshold.Y2 = stepperY2.get_pwm_thrs());
1296 1308
         TERN_(Z2_HAS_STEALTHCHOP, tmc_hybrid_threshold.Z2 = stepperZ2.get_pwm_thrs());
@@ -1307,7 +1319,7 @@ void MarlinSettings::postprocess() {
1307 1319
       #else
1308 1320
         #define _EN_ITEM(N) , .E##N =  30
1309 1321
         const tmc_hybrid_threshold_t tmc_hybrid_threshold = {
1310
-          LINEAR_AXIS_LIST(.X = 100, .Y = 100, .Z = 3, .I = 3, .J = 3, .K = 3),
1322
+          NUM_AXIS_LIST(.X = 100, .Y = 100, .Z = 3, .I = 3, .J = 3, .K = 3, .U = 3, .V = 3, .W = 3),
1311 1323
           .X2 = 100, .Y2 = 100, .Z2 = 3, .Z3 = 3, .Z4 = 3
1312 1324
           REPEAT(E_STEPPERS, _EN_ITEM)
1313 1325
         };
@@ -1322,13 +1334,16 @@ void MarlinSettings::postprocess() {
1322 1334
     {
1323 1335
       tmc_sgt_t tmc_sgt{0};
1324 1336
       #if USE_SENSORLESS
1325
-        LINEAR_AXIS_CODE(
1337
+        NUM_AXIS_CODE(
1326 1338
           TERN_(X_SENSORLESS, tmc_sgt.X = stepperX.homing_threshold()),
1327 1339
           TERN_(Y_SENSORLESS, tmc_sgt.Y = stepperY.homing_threshold()),
1328 1340
           TERN_(Z_SENSORLESS, tmc_sgt.Z = stepperZ.homing_threshold()),
1329 1341
           TERN_(I_SENSORLESS, tmc_sgt.I = stepperI.homing_threshold()),
1330 1342
           TERN_(J_SENSORLESS, tmc_sgt.J = stepperJ.homing_threshold()),
1331
-          TERN_(K_SENSORLESS, tmc_sgt.K = stepperK.homing_threshold())
1343
+          TERN_(K_SENSORLESS, tmc_sgt.K = stepperK.homing_threshold()),
1344
+          TERN_(U_SENSORLESS, tmc_sgt.U = stepperU.homing_threshold()),
1345
+          TERN_(V_SENSORLESS, tmc_sgt.V = stepperV.homing_threshold()),
1346
+          TERN_(W_SENSORLESS, tmc_sgt.W = stepperW.homing_threshold())
1332 1347
         );
1333 1348
         TERN_(X2_SENSORLESS, tmc_sgt.X2 = stepperX2.homing_threshold());
1334 1349
         TERN_(Y2_SENSORLESS, tmc_sgt.Y2 = stepperY2.homing_threshold());
@@ -1352,6 +1367,9 @@ void MarlinSettings::postprocess() {
1352 1367
       TERN_(I_HAS_STEALTHCHOP,  tmc_stealth_enabled.I  = stepperI.get_stored_stealthChop());
1353 1368
       TERN_(J_HAS_STEALTHCHOP,  tmc_stealth_enabled.J  = stepperJ.get_stored_stealthChop());
1354 1369
       TERN_(K_HAS_STEALTHCHOP,  tmc_stealth_enabled.K  = stepperK.get_stored_stealthChop());
1370
+      TERN_(U_HAS_STEALTHCHOP,  tmc_stealth_enabled.U  = stepperU.get_stored_stealthChop());
1371
+      TERN_(V_HAS_STEALTHCHOP,  tmc_stealth_enabled.V  = stepperV.get_stored_stealthChop());
1372
+      TERN_(W_HAS_STEALTHCHOP,  tmc_stealth_enabled.W  = stepperW.get_stored_stealthChop());
1355 1373
       TERN_(X2_HAS_STEALTHCHOP, tmc_stealth_enabled.X2 = stepperX2.get_stored_stealthChop());
1356 1374
       TERN_(Y2_HAS_STEALTHCHOP, tmc_stealth_enabled.Y2 = stepperY2.get_stored_stealthChop());
1357 1375
       TERN_(Z2_HAS_STEALTHCHOP, tmc_stealth_enabled.Z2 = stepperZ2.get_stored_stealthChop());
@@ -1441,7 +1459,7 @@ void MarlinSettings::postprocess() {
1441 1459
     {
1442 1460
       #if ENABLED(BACKLASH_GCODE)
1443 1461
         xyz_float_t backlash_distance_mm;
1444
-        LOOP_LINEAR_AXES(axis) backlash_distance_mm[axis] = backlash.get_distance_mm((AxisEnum)axis);
1462
+        LOOP_NUM_AXES(axis) backlash_distance_mm[axis] = backlash.get_distance_mm((AxisEnum)axis);
1445 1463
         const uint8_t backlash_correction = backlash.get_correction_uint8();
1446 1464
       #else
1447 1465
         const xyz_float_t backlash_distance_mm{0};
@@ -1653,16 +1671,16 @@ void MarlinSettings::postprocess() {
1653 1671
       {
1654 1672
         // Get only the number of E stepper parameters previously stored
1655 1673
         // Any steppers added later are set to their defaults
1656
-        uint32_t tmp1[LINEAR_AXES + e_factors];
1657
-        float tmp2[LINEAR_AXES + e_factors];
1658
-        feedRate_t tmp3[LINEAR_AXES + e_factors];
1674
+        uint32_t tmp1[NUM_AXES + e_factors];
1675
+        float tmp2[NUM_AXES + e_factors];
1676
+        feedRate_t tmp3[NUM_AXES + e_factors];
1659 1677
         EEPROM_READ((uint8_t *)tmp1, sizeof(tmp1)); // max_acceleration_mm_per_s2
1660 1678
         EEPROM_READ(planner.settings.min_segment_time_us);
1661 1679
         EEPROM_READ((uint8_t *)tmp2, sizeof(tmp2)); // axis_steps_per_mm
1662 1680
         EEPROM_READ((uint8_t *)tmp3, sizeof(tmp3)); // max_feedrate_mm_s
1663 1681
 
1664 1682
         if (!validating) LOOP_DISTINCT_AXES(i) {
1665
-          const bool in = (i < e_factors + LINEAR_AXES);
1683
+          const bool in = (i < e_factors + NUM_AXES);
1666 1684
           planner.settings.max_acceleration_mm_per_s2[i] = in ? tmp1[i] : pgm_read_dword(&_DMA[ALIM(i, _DMA)]);
1667 1685
           planner.settings.axis_steps_per_mm[i]          = in ? tmp2[i] : pgm_read_float(&_DASU[ALIM(i, _DASU)]);
1668 1686
           planner.settings.max_feedrate_mm_s[i]          = in ? tmp3[i] : pgm_read_float(&_DMF[ALIM(i, _DMF)]);
@@ -2175,6 +2193,15 @@ void MarlinSettings::postprocess() {
2175 2193
             #if AXIS_IS_TMC(K)
2176 2194
               SET_CURR(K);
2177 2195
             #endif
2196
+            #if AXIS_IS_TMC(U)
2197
+              SET_CURR(U);
2198
+            #endif
2199
+            #if AXIS_IS_TMC(V)
2200
+              SET_CURR(V);
2201
+            #endif
2202
+            #if AXIS_IS_TMC(W)
2203
+              SET_CURR(W);
2204
+            #endif
2178 2205
             #if AXIS_IS_TMC(E0)
2179 2206
               SET_CURR(E0);
2180 2207
             #endif
@@ -2222,6 +2249,9 @@ void MarlinSettings::postprocess() {
2222 2249
             TERN_(I_HAS_STEALTHCHOP,  stepperI.set_pwm_thrs(tmc_hybrid_threshold.I));
2223 2250
             TERN_(J_HAS_STEALTHCHOP,  stepperJ.set_pwm_thrs(tmc_hybrid_threshold.J));
2224 2251
             TERN_(K_HAS_STEALTHCHOP,  stepperK.set_pwm_thrs(tmc_hybrid_threshold.K));
2252
+            TERN_(U_HAS_STEALTHCHOP,  stepperU.set_pwm_thrs(tmc_hybrid_threshold.U));
2253
+            TERN_(V_HAS_STEALTHCHOP,  stepperV.set_pwm_thrs(tmc_hybrid_threshold.V));
2254
+            TERN_(W_HAS_STEALTHCHOP,  stepperW.set_pwm_thrs(tmc_hybrid_threshold.W));
2225 2255
             TERN_(E0_HAS_STEALTHCHOP, stepperE0.set_pwm_thrs(tmc_hybrid_threshold.E0));
2226 2256
             TERN_(E1_HAS_STEALTHCHOP, stepperE1.set_pwm_thrs(tmc_hybrid_threshold.E1));
2227 2257
             TERN_(E2_HAS_STEALTHCHOP, stepperE2.set_pwm_thrs(tmc_hybrid_threshold.E2));
@@ -2243,13 +2273,16 @@ void MarlinSettings::postprocess() {
2243 2273
         EEPROM_READ(tmc_sgt);
2244 2274
         #if USE_SENSORLESS
2245 2275
           if (!validating) {
2246
-            LINEAR_AXIS_CODE(
2276
+            NUM_AXIS_CODE(
2247 2277
               TERN_(X_SENSORLESS, stepperX.homing_threshold(tmc_sgt.X)),
2248 2278
               TERN_(Y_SENSORLESS, stepperY.homing_threshold(tmc_sgt.Y)),
2249 2279
               TERN_(Z_SENSORLESS, stepperZ.homing_threshold(tmc_sgt.Z)),
2250 2280
               TERN_(I_SENSORLESS, stepperI.homing_threshold(tmc_sgt.I)),
2251 2281
               TERN_(J_SENSORLESS, stepperJ.homing_threshold(tmc_sgt.J)),
2252
-              TERN_(K_SENSORLESS, stepperK.homing_threshold(tmc_sgt.K))
2282
+              TERN_(K_SENSORLESS, stepperK.homing_threshold(tmc_sgt.K)),
2283
+              TERN_(U_SENSORLESS, stepperU.homing_threshold(tmc_sgt.U)),
2284
+              TERN_(V_SENSORLESS, stepperV.homing_threshold(tmc_sgt.V)),
2285
+              TERN_(W_SENSORLESS, stepperW.homing_threshold(tmc_sgt.W))
2253 2286
             );
2254 2287
             TERN_(X2_SENSORLESS, stepperX2.homing_threshold(tmc_sgt.X2));
2255 2288
             TERN_(Y2_SENSORLESS, stepperY2.homing_threshold(tmc_sgt.Y2));
@@ -2277,6 +2310,9 @@ void MarlinSettings::postprocess() {
2277 2310
             TERN_(I_HAS_STEALTHCHOP,  SET_STEPPING_MODE(I));
2278 2311
             TERN_(J_HAS_STEALTHCHOP,  SET_STEPPING_MODE(J));
2279 2312
             TERN_(K_HAS_STEALTHCHOP,  SET_STEPPING_MODE(K));
2313
+            TERN_(U_HAS_STEALTHCHOP,  SET_STEPPING_MODE(U));
2314
+            TERN_(V_HAS_STEALTHCHOP,  SET_STEPPING_MODE(V));
2315
+            TERN_(W_HAS_STEALTHCHOP,  SET_STEPPING_MODE(W));
2280 2316
             TERN_(X2_HAS_STEALTHCHOP, SET_STEPPING_MODE(X2));
2281 2317
             TERN_(Y2_HAS_STEALTHCHOP, SET_STEPPING_MODE(Y2));
2282 2318
             TERN_(Z2_HAS_STEALTHCHOP, SET_STEPPING_MODE(Z2));
@@ -2397,7 +2433,7 @@ void MarlinSettings::postprocess() {
2397 2433
         EEPROM_READ(backlash_smoothing_mm);
2398 2434
 
2399 2435
         #if ENABLED(BACKLASH_GCODE)
2400
-          LOOP_LINEAR_AXES(axis) backlash.set_distance_mm((AxisEnum)axis, backlash_distance_mm[axis]);
2436
+          LOOP_NUM_AXES(axis) backlash.set_distance_mm((AxisEnum)axis, backlash_distance_mm[axis]);
2401 2437
           backlash.set_correction_uint8(backlash_correction);
2402 2438
           #ifdef BACKLASH_SMOOTHING_MM
2403 2439
             backlash.set_smoothing_mm(backlash_smoothing_mm);
@@ -2773,8 +2809,17 @@ void MarlinSettings::reset() {
2773 2809
     #if HAS_K_AXIS && !defined(DEFAULT_KJERK)
2774 2810
       #define DEFAULT_KJERK 0
2775 2811
     #endif
2812
+    #if HAS_U_AXIS && !defined(DEFAULT_UJERK)
2813
+      #define DEFAULT_UJERK 0
2814
+    #endif
2815
+    #if HAS_V_AXIS && !defined(DEFAULT_VJERK)
2816
+      #define DEFAULT_VJERK 0
2817
+    #endif
2818
+    #if HAS_W_AXIS && !defined(DEFAULT_WJERK)
2819
+      #define DEFAULT_WJERK 0
2820
+    #endif
2776 2821
     planner.max_jerk.set(
2777
-      LINEAR_AXIS_LIST(DEFAULT_XJERK, DEFAULT_YJERK, DEFAULT_ZJERK, DEFAULT_IJERK, DEFAULT_JJERK, DEFAULT_KJERK)
2822
+      NUM_AXIS_LIST(DEFAULT_XJERK, DEFAULT_YJERK, DEFAULT_ZJERK, DEFAULT_IJERK, DEFAULT_JJERK, DEFAULT_KJERK, DEFAULT_UJERK, DEFAULT_VJERK, DEFAULT_WJERK)
2778 2823
     );
2779 2824
     TERN_(HAS_CLASSIC_E_JERK, planner.max_jerk.e = DEFAULT_EJERK);
2780 2825
   #endif
@@ -2836,7 +2881,7 @@ void MarlinSettings::reset() {
2836 2881
   #if ENABLED(BACKLASH_GCODE)
2837 2882
     backlash.set_correction(BACKLASH_CORRECTION);
2838 2883
     constexpr xyz_float_t tmp = BACKLASH_DISTANCE_MM;
2839
-    LOOP_LINEAR_AXES(axis) backlash.set_distance_mm((AxisEnum)axis, tmp[axis]);
2884
+    LOOP_NUM_AXES(axis) backlash.set_distance_mm((AxisEnum)axis, tmp[axis]);
2840 2885
     #ifdef BACKLASH_SMOOTHING_MM
2841 2886
       backlash.set_smoothing_mm(BACKLASH_SMOOTHING_MM);
2842 2887
     #endif
@@ -2881,11 +2926,11 @@ void MarlinSettings::reset() {
2881 2926
   //
2882 2927
   #if HAS_BED_PROBE
2883 2928
     constexpr float dpo[] = NOZZLE_TO_PROBE_OFFSET;
2884
-    static_assert(COUNT(dpo) == LINEAR_AXES, "NOZZLE_TO_PROBE_OFFSET must contain offsets for each linear axis X, Y, Z....");
2929
+    static_assert(COUNT(dpo) == NUM_AXES, "NOZZLE_TO_PROBE_OFFSET must contain offsets for each linear axis X, Y, Z....");
2885 2930
     #if HAS_PROBE_XY_OFFSET
2886
-      LOOP_LINEAR_AXES(a) probe.offset[a] = dpo[a];
2931
+      LOOP_NUM_AXES(a) probe.offset[a] = dpo[a];
2887 2932
     #else
2888
-      probe.offset.set(LINEAR_AXIS_LIST(0, 0, dpo[Z_AXIS], 0, 0, 0));
2933
+      probe.offset.set(NUM_AXIS_LIST(0, 0, dpo[Z_AXIS], 0, 0, 0, 0, 0, 0));
2889 2934
     #endif
2890 2935
   #endif
2891 2936
 

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

@@ -447,6 +447,18 @@ xyze_int8_t Stepper::count_direction{0};
447 447
   #define K_APPLY_DIR(v,Q) K_DIR_WRITE(v)
448 448
   #define K_APPLY_STEP(v,Q) K_STEP_WRITE(v)
449 449
 #endif
450
+#if HAS_U_AXIS
451
+  #define U_APPLY_DIR(v,Q) U_DIR_WRITE(v)
452
+  #define U_APPLY_STEP(v,Q) U_STEP_WRITE(v)
453
+#endif
454
+#if HAS_V_AXIS
455
+  #define V_APPLY_DIR(v,Q) V_DIR_WRITE(v)
456
+  #define V_APPLY_STEP(v,Q) V_STEP_WRITE(v)
457
+#endif
458
+#if HAS_W_AXIS
459
+  #define W_APPLY_DIR(v,Q) W_DIR_WRITE(v)
460
+  #define W_APPLY_STEP(v,Q) W_STEP_WRITE(v)
461
+#endif
450 462
 
451 463
 #if DISABLED(MIXING_EXTRUDER)
452 464
   #define E_APPLY_STEP(v,Q) E_STEP_WRITE(stepper_extruder, v)
@@ -486,9 +498,10 @@ xyze_int8_t Stepper::count_direction{0};
486 498
 void Stepper::enable_axis(const AxisEnum axis) {
487 499
   #define _CASE_ENABLE(N) case N##_AXIS: ENABLE_AXIS_##N(); break;
488 500
   switch (axis) {
489
-    LINEAR_AXIS_CODE(
501
+    NUM_AXIS_CODE(
490 502
       _CASE_ENABLE(X), _CASE_ENABLE(Y), _CASE_ENABLE(Z),
491
-      _CASE_ENABLE(I), _CASE_ENABLE(J), _CASE_ENABLE(K)
503
+      _CASE_ENABLE(I), _CASE_ENABLE(J), _CASE_ENABLE(K),
504
+      _CASE_ENABLE(U), _CASE_ENABLE(V), _CASE_ENABLE(W)
492 505
     );
493 506
     default: break;
494 507
   }
@@ -505,9 +518,10 @@ bool Stepper::disable_axis(const AxisEnum axis) {
505 518
   if (can_disable) {
506 519
     #define _CASE_DISABLE(N) case N##_AXIS: DISABLE_AXIS_##N(); break;
507 520
     switch (axis) {
508
-      LINEAR_AXIS_CODE(
521
+      NUM_AXIS_CODE(
509 522
         _CASE_DISABLE(X), _CASE_DISABLE(Y), _CASE_DISABLE(Z),
510
-        _CASE_DISABLE(I), _CASE_DISABLE(J), _CASE_DISABLE(K)
523
+        _CASE_DISABLE(I), _CASE_DISABLE(J), _CASE_DISABLE(K),
524
+        _CASE_DISABLE(U), _CASE_DISABLE(V), _CASE_DISABLE(W)
511 525
       );
512 526
       default: break;
513 527
     }
@@ -550,9 +564,10 @@ bool Stepper::disable_axis(const AxisEnum axis) {
550 564
 
551 565
 void Stepper::enable_all_steppers() {
552 566
   TERN_(AUTO_POWER_CONTROL, powerManager.power_on());
553
-  LINEAR_AXIS_CODE(
567
+  NUM_AXIS_CODE(
554 568
     enable_axis(X_AXIS), enable_axis(Y_AXIS), enable_axis(Z_AXIS),
555
-    enable_axis(I_AXIS), enable_axis(J_AXIS), enable_axis(K_AXIS)
569
+    enable_axis(I_AXIS), enable_axis(J_AXIS), enable_axis(K_AXIS),
570
+    enable_axis(U_AXIS), enable_axis(V_AXIS), enable_axis(W_AXIS)
556 571
   );
557 572
   enable_e_steppers();
558 573
 
@@ -560,9 +575,10 @@ void Stepper::enable_all_steppers() {
560 575
 }
561 576
 
562 577
 void Stepper::disable_all_steppers() {
563
-  LINEAR_AXIS_CODE(
578
+  NUM_AXIS_CODE(
564 579
     disable_axis(X_AXIS), disable_axis(Y_AXIS), disable_axis(Z_AXIS),
565
-    disable_axis(I_AXIS), disable_axis(J_AXIS), disable_axis(K_AXIS)
580
+    disable_axis(I_AXIS), disable_axis(J_AXIS), disable_axis(K_AXIS),
581
+    disable_axis(U_AXIS), disable_axis(V_AXIS), disable_axis(W_AXIS)
566 582
   );
567 583
   disable_e_steppers();
568 584
 
@@ -596,6 +612,9 @@ void Stepper::set_directions() {
596 612
   TERN_(HAS_I_DIR, SET_STEP_DIR(I));
597 613
   TERN_(HAS_J_DIR, SET_STEP_DIR(J));
598 614
   TERN_(HAS_K_DIR, SET_STEP_DIR(K));
615
+  TERN_(HAS_U_DIR, SET_STEP_DIR(U));
616
+  TERN_(HAS_V_DIR, SET_STEP_DIR(V));
617
+  TERN_(HAS_W_DIR, SET_STEP_DIR(W));
599 618
 
600 619
   #if DISABLED(LIN_ADVANCE)
601 620
     #if ENABLED(MIXING_EXTRUDER)
@@ -1816,6 +1835,15 @@ void Stepper::pulse_phase_isr() {
1816 1835
       #if HAS_K_STEP
1817 1836
         PULSE_PREP(K);
1818 1837
       #endif
1838
+      #if HAS_U_STEP
1839
+        PULSE_PREP(U);
1840
+      #endif
1841
+      #if HAS_V_STEP
1842
+        PULSE_PREP(V);
1843
+      #endif
1844
+      #if HAS_W_STEP
1845
+        PULSE_PREP(W);
1846
+      #endif
1819 1847
 
1820 1848
       #if EITHER(LIN_ADVANCE, MIXING_EXTRUDER)
1821 1849
         delta_error.e += advance_dividend.e;
@@ -1860,6 +1888,15 @@ void Stepper::pulse_phase_isr() {
1860 1888
     #if HAS_K_STEP
1861 1889
       PULSE_START(K);
1862 1890
     #endif
1891
+    #if HAS_U_STEP
1892
+      PULSE_START(U);
1893
+    #endif
1894
+    #if HAS_V_STEP
1895
+      PULSE_START(V);
1896
+    #endif
1897
+    #if HAS_W_STEP
1898
+      PULSE_START(W);
1899
+    #endif
1863 1900
 
1864 1901
     #if DISABLED(LIN_ADVANCE)
1865 1902
       #if ENABLED(MIXING_EXTRUDER)
@@ -1898,6 +1935,15 @@ void Stepper::pulse_phase_isr() {
1898 1935
     #if HAS_K_STEP
1899 1936
       PULSE_STOP(K);
1900 1937
     #endif
1938
+    #if HAS_U_STEP
1939
+      PULSE_STOP(U);
1940
+    #endif
1941
+    #if HAS_V_STEP
1942
+      PULSE_STOP(V);
1943
+    #endif
1944
+    #if HAS_W_STEP
1945
+      PULSE_STOP(W);
1946
+    #endif
1901 1947
 
1902 1948
     #if DISABLED(LIN_ADVANCE)
1903 1949
       #if ENABLED(MIXING_EXTRUDER)
@@ -2243,13 +2289,16 @@ uint32_t Stepper::block_phase_isr() {
2243 2289
       #endif
2244 2290
 
2245 2291
       axis_bits_t axis_bits = 0;
2246
-      LINEAR_AXIS_CODE(
2292
+      NUM_AXIS_CODE(
2247 2293
         if (X_MOVE_TEST)            SBI(axis_bits, A_AXIS),
2248 2294
         if (Y_MOVE_TEST)            SBI(axis_bits, B_AXIS),
2249 2295
         if (Z_MOVE_TEST)            SBI(axis_bits, C_AXIS),
2250 2296
         if (current_block->steps.i) SBI(axis_bits, I_AXIS),
2251 2297
         if (current_block->steps.j) SBI(axis_bits, J_AXIS),
2252
-        if (current_block->steps.k) SBI(axis_bits, K_AXIS)
2298
+        if (current_block->steps.k) SBI(axis_bits, K_AXIS),
2299
+        if (current_block->steps.u) SBI(axis_bits, U_AXIS),
2300
+        if (current_block->steps.v) SBI(axis_bits, V_AXIS),
2301
+        if (current_block->steps.w) SBI(axis_bits, W_AXIS)
2253 2302
       );
2254 2303
       //if (current_block->steps.e) SBI(axis_bits, E_AXIS);
2255 2304
       //if (current_block->steps.a) SBI(axis_bits, X_HEAD);
@@ -2589,6 +2638,15 @@ void Stepper::init() {
2589 2638
   #if HAS_K_DIR
2590 2639
     K_DIR_INIT();
2591 2640
   #endif
2641
+  #if HAS_U_DIR
2642
+    U_DIR_INIT();
2643
+  #endif
2644
+  #if HAS_V_DIR
2645
+    V_DIR_INIT();
2646
+  #endif
2647
+  #if HAS_W_DIR
2648
+    W_DIR_INIT();
2649
+  #endif
2592 2650
   #if HAS_E0_DIR
2593 2651
     E0_DIR_INIT();
2594 2652
   #endif
@@ -2659,6 +2717,18 @@ void Stepper::init() {
2659 2717
     K_ENABLE_INIT();
2660 2718
     if (!K_ENABLE_ON) K_ENABLE_WRITE(HIGH);
2661 2719
   #endif
2720
+  #if HAS_U_ENABLE
2721
+    U_ENABLE_INIT();
2722
+    if (!U_ENABLE_ON) U_ENABLE_WRITE(HIGH);
2723
+  #endif
2724
+  #if HAS_V_ENABLE
2725
+    V_ENABLE_INIT();
2726
+    if (!V_ENABLE_ON) V_ENABLE_WRITE(HIGH);
2727
+  #endif
2728
+  #if HAS_W_ENABLE
2729
+    W_ENABLE_INIT();
2730
+    if (!W_ENABLE_ON) W_ENABLE_WRITE(HIGH);
2731
+  #endif
2662 2732
   #if HAS_E0_ENABLE
2663 2733
     E0_ENABLE_INIT();
2664 2734
     if (!E_ENABLE_ON) E0_ENABLE_WRITE(HIGH);
@@ -2744,6 +2814,15 @@ void Stepper::init() {
2744 2814
   #if HAS_K_STEP
2745 2815
     AXIS_INIT(K, K);
2746 2816
   #endif
2817
+  #if HAS_U_STEP
2818
+    AXIS_INIT(U, U);
2819
+  #endif
2820
+  #if HAS_V_STEP
2821
+    AXIS_INIT(V, V);
2822
+  #endif
2823
+  #if HAS_W_STEP
2824
+    AXIS_INIT(W, W);
2825
+  #endif
2747 2826
 
2748 2827
   #if E_STEPPERS && HAS_E0_STEP
2749 2828
     E_AXIS_INIT(0);
@@ -2778,13 +2857,16 @@ void Stepper::init() {
2778 2857
 
2779 2858
   // Init direction bits for first moves
2780 2859
   set_directions(0
2781
-    LINEAR_AXIS_GANG(
2860
+    NUM_AXIS_GANG(
2782 2861
       | TERN0(INVERT_X_DIR, _BV(X_AXIS)),
2783 2862
       | TERN0(INVERT_Y_DIR, _BV(Y_AXIS)),
2784 2863
       | TERN0(INVERT_Z_DIR, _BV(Z_AXIS)),
2785 2864
       | TERN0(INVERT_I_DIR, _BV(I_AXIS)),
2786 2865
       | TERN0(INVERT_J_DIR, _BV(J_AXIS)),
2787
-      | TERN0(INVERT_K_DIR, _BV(K_AXIS))
2866
+      | TERN0(INVERT_K_DIR, _BV(K_AXIS)),
2867
+      | TERN0(INVERT_U_DIR, _BV(U_AXIS)),
2868
+      | TERN0(INVERT_V_DIR, _BV(V_AXIS)),
2869
+      | TERN0(INVERT_W_DIR, _BV(W_AXIS))
2788 2870
     )
2789 2871
   );
2790 2872
 
@@ -2820,6 +2902,14 @@ void Stepper::_set_position(const abce_long_t &spos) {
2820 2902
     #elif ENABLED(MARKFORGED_YX)
2821 2903
       count_position.set(spos.a, spos.b - spos.a, spos.c);
2822 2904
     #endif
2905
+    SECONDARY_AXIS_CODE(
2906
+      count_position.i = spos.i,
2907
+      count_position.j = spos.j,
2908
+      count_position.k = spos.k,
2909
+      count_position.u = spos.u,
2910
+      count_position.v = spos.v,
2911
+      count_position.w = spos.w
2912
+    );
2823 2913
     TERN_(HAS_EXTRUDERS, count_position.e = spos.e);
2824 2914
   #else
2825 2915
     // default non-h-bot planning
@@ -2934,13 +3024,16 @@ int32_t Stepper::triggered_position(const AxisEnum axis) {
2934 3024
 
2935 3025
 void Stepper::report_a_position(const xyz_long_t &pos) {
2936 3026
   SERIAL_ECHOLNPGM_P(
2937
-    LIST_N(DOUBLE(LINEAR_AXES),
3027
+    LIST_N(DOUBLE(NUM_AXES),
2938 3028
       TERN(SAYS_A, PSTR(STR_COUNT_A), PSTR(STR_COUNT_X)), pos.x,
2939 3029
       TERN(SAYS_B, PSTR("B:"), SP_Y_LBL), pos.y,
2940 3030
       TERN(SAYS_C, PSTR("C:"), SP_Z_LBL), pos.z,
2941 3031
       SP_I_LBL, pos.i,
2942 3032
       SP_J_LBL, pos.j,
2943
-      SP_K_LBL, pos.k
3033
+      SP_K_LBL, pos.k,
3034
+      SP_U_LBL, pos.u,
3035
+      SP_V_LBL, pos.v,
3036
+      SP_W_LBL, pos.w
2944 3037
     )
2945 3038
   );
2946 3039
 }
@@ -3091,16 +3184,18 @@ void Stepper::report_positions() {
3091 3184
 
3092 3185
           const bool z_direction = direction ^ BABYSTEP_INVERT_Z;
3093 3186
 
3094
-          LINEAR_AXIS_CODE(
3187
+          NUM_AXIS_CODE(
3095 3188
             enable_axis(X_AXIS), enable_axis(Y_AXIS), enable_axis(Z_AXIS),
3096
-            enable_axis(I_AXIS), enable_axis(J_AXIS), enable_axis(K_AXIS)
3189
+            enable_axis(I_AXIS), enable_axis(J_AXIS), enable_axis(K_AXIS),
3190
+            enable_axis(U_AXIS), enable_axis(V_AXIS), enable_axis(W_AXIS)
3097 3191
           );
3098 3192
 
3099 3193
           DIR_WAIT_BEFORE();
3100 3194
 
3101
-          const xyz_byte_t old_dir = LINEAR_AXIS_ARRAY(
3195
+          const xyz_byte_t old_dir = NUM_AXIS_ARRAY(
3102 3196
             X_DIR_READ(), Y_DIR_READ(), Z_DIR_READ(),
3103
-            I_DIR_READ(), J_DIR_READ(), K_DIR_READ()
3197
+            I_DIR_READ(), J_DIR_READ(), K_DIR_READ(),
3198
+            U_DIR_READ(), V_DIR_READ(), W_DIR_READ()
3104 3199
           );
3105 3200
 
3106 3201
           X_DIR_WRITE(INVERT_X_DIR ^ z_direction);
@@ -3119,6 +3214,15 @@ void Stepper::report_positions() {
3119 3214
           #ifdef K_DIR_WRITE
3120 3215
             K_DIR_WRITE(INVERT_K_DIR ^ z_direction);
3121 3216
           #endif
3217
+          #ifdef U_DIR_WRITE
3218
+            U_DIR_WRITE(INVERT_U_DIR ^ z_direction);
3219
+          #endif
3220
+          #ifdef V_DIR_WRITE
3221
+            V_DIR_WRITE(INVERT_V_DIR ^ z_direction);
3222
+          #endif
3223
+          #ifdef W_DIR_WRITE
3224
+            W_DIR_WRITE(INVERT_W_DIR ^ z_direction);
3225
+          #endif
3122 3226
 
3123 3227
           DIR_WAIT_AFTER();
3124 3228
 
@@ -3140,6 +3244,15 @@ void Stepper::report_positions() {
3140 3244
           #ifdef K_STEP_WRITE
3141 3245
             K_STEP_WRITE(!INVERT_K_STEP_PIN);
3142 3246
           #endif
3247
+          #ifdef U_STEP_WRITE
3248
+            U_STEP_WRITE(!INVERT_U_STEP_PIN);
3249
+          #endif
3250
+          #ifdef V_STEP_WRITE
3251
+            V_STEP_WRITE(!INVERT_V_STEP_PIN);
3252
+          #endif
3253
+          #ifdef W_STEP_WRITE
3254
+            W_STEP_WRITE(!INVERT_W_STEP_PIN);
3255
+          #endif
3143 3256
 
3144 3257
           _PULSE_WAIT();
3145 3258
 
@@ -3159,6 +3272,15 @@ void Stepper::report_positions() {
3159 3272
           #ifdef K_STEP_WRITE
3160 3273
             K_STEP_WRITE(INVERT_K_STEP_PIN);
3161 3274
           #endif
3275
+          #ifdef U_STEP_WRITE
3276
+            U_STEP_WRITE(INVERT_U_STEP_PIN);
3277
+          #endif
3278
+           #ifdef V_STEP_WRITE
3279
+            V_STEP_WRITE(INVERT_V_STEP_PIN);
3280
+          #endif
3281
+          #ifdef W_STEP_WRITE
3282
+            W_STEP_WRITE(INVERT_W_STEP_PIN);
3283
+          #endif
3162 3284
 
3163 3285
           // Restore direction bits
3164 3286
           EXTRA_DIR_WAIT_BEFORE();
@@ -3179,6 +3301,15 @@ void Stepper::report_positions() {
3179 3301
           #ifdef K_DIR_WRITE
3180 3302
             K_DIR_WRITE(old_dir.k);
3181 3303
           #endif
3304
+          #ifdef U_DIR_WRITE
3305
+            U_DIR_WRITE(old_dir.u);
3306
+          #endif
3307
+          #ifdef V_DIR_WRITE
3308
+            V_DIR_WRITE(old_dir.v);
3309
+          #endif
3310
+          #ifdef W_DIR_WRITE
3311
+            W_DIR_WRITE(old_dir.w);
3312
+          #endif
3182 3313
 
3183 3314
           EXTRA_DIR_WAIT_AFTER();
3184 3315
 
@@ -3195,6 +3326,15 @@ void Stepper::report_positions() {
3195 3326
       #if HAS_K_AXIS
3196 3327
         case K_AXIS: BABYSTEP_AXIS(K, 0, direction); break;
3197 3328
       #endif
3329
+      #if HAS_U_AXIS
3330
+        case U_AXIS: BABYSTEP_AXIS(U, 0, direction); break;
3331
+      #endif
3332
+      #if HAS_V_AXIS
3333
+        case V_AXIS: BABYSTEP_AXIS(V, 0, direction); break;
3334
+      #endif
3335
+      #if HAS_W_AXIS
3336
+        case W_AXIS: BABYSTEP_AXIS(W, 0, direction); break;
3337
+      #endif
3198 3338
 
3199 3339
       default: break;
3200 3340
     }
@@ -3423,6 +3563,24 @@ void Stepper::report_positions() {
3423 3563
         SET_OUTPUT(K_MS3_PIN);
3424 3564
       #endif
3425 3565
     #endif
3566
+    #if HAS_U_MS_PINS
3567
+      SET_OUTPUT(U_MS1_PIN); SET_OUTPUT(U_MS2_PIN);
3568
+      #if PIN_EXISTS(U_MS3)
3569
+        SET_OUTPUT(U_MS3_PIN);
3570
+      #endif
3571
+    #endif
3572
+    #if HAS_V_MS_PINS
3573
+      SET_OUTPUT(V_MS1_PIN); SET_OUTPUT(V_MS2_PIN);
3574
+      #if PIN_EXISTS(V_MS3)
3575
+        SET_OUTPUT(V_MS3_PIN);
3576
+      #endif
3577
+    #endif
3578
+    #if HAS_W_MS_PINS
3579
+      SET_OUTPUT(W_MS1_PIN); SET_OUTPUT(W_MS2_PIN);
3580
+      #if PIN_EXISTS(W_MS3)
3581
+        SET_OUTPUT(W_MS3_PIN);
3582
+      #endif
3583
+    #endif
3426 3584
     #if HAS_E0_MS_PINS
3427 3585
       SET_OUTPUT(E0_MS1_PIN); SET_OUTPUT(E0_MS2_PIN);
3428 3586
       #if PIN_EXISTS(E0_MS3)
@@ -3548,6 +3706,15 @@ void Stepper::report_positions() {
3548 3706
       #if HAS_K_MS_PINS
3549 3707
         case 13: WRITE(K_MS1_PIN, ms1); break
3550 3708
       #endif
3709
+      #if HAS_U_MS_PINS
3710
+        case 14: WRITE(U_MS1_PIN, ms1); break
3711
+      #endif
3712
+      #if HAS_V_MS_PINS
3713
+        case 15: WRITE(V_MS1_PIN, ms1); break
3714
+      #endif
3715
+      #if HAS_W_MS_PINS
3716
+        case 16: WRITE(W_MS1_PIN, ms1); break
3717
+      #endif
3551 3718
     }
3552 3719
     if (ms2 >= 0) switch (driver) {
3553 3720
       #if HAS_X_MS_PINS || HAS_X2_MS_PINS
@@ -3619,6 +3786,15 @@ void Stepper::report_positions() {
3619 3786
       #if HAS_K_MS_PINS
3620 3787
         case 13: WRITE(K_MS2_PIN, ms2); break
3621 3788
       #endif
3789
+      #if HAS_U_MS_PINS
3790
+        case 14: WRITE(U_MS2_PIN, ms2); break
3791
+      #endif
3792
+      #if HAS_V_MS_PINS
3793
+        case 15: WRITE(V_MS2_PIN, ms2); break
3794
+      #endif
3795
+      #if HAS_W_MS_PINS
3796
+        case 16: WRITE(W_MS2_PIN, ms2); break
3797
+      #endif
3622 3798
     }
3623 3799
     if (ms3 >= 0) switch (driver) {
3624 3800
       #if HAS_X_MS_PINS || HAS_X2_MS_PINS
@@ -3755,6 +3931,24 @@ void Stepper::report_positions() {
3755 3931
         PIN_CHAR(K_MS3);
3756 3932
       #endif
3757 3933
     #endif
3934
+    #if HAS_U_MS_PINS
3935
+      MS_LINE(U);
3936
+      #if PIN_EXISTS(U_MS3)
3937
+        PIN_CHAR(U_MS3);
3938
+      #endif
3939
+    #endif
3940
+    #if HAS_V_MS_PINS
3941
+      MS_LINE(V);
3942
+      #if PIN_EXISTS(V_MS3)
3943
+        PIN_CHAR(V_MS3);
3944
+      #endif
3945
+    #endif
3946
+    #if HAS_W_MS_PINS
3947
+      MS_LINE(W);
3948
+      #if PIN_EXISTS(W_MS3)
3949
+        PIN_CHAR(W_MS3);
3950
+      #endif
3951
+    #endif
3758 3952
     #if HAS_E0_MS_PINS
3759 3953
       MS_LINE(E0);
3760 3954
       #if PIN_EXISTS(E0_MS3)

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

@@ -159,12 +159,21 @@
159 159
 #if HAS_K_STEP
160 160
   #define ISR_K_STEPPER_CYCLES  ISR_STEPPER_CYCLES
161 161
 #endif
162
+#if HAS_U_STEP
163
+  #define ISR_U_STEPPER_CYCLES  ISR_STEPPER_CYCLES
164
+#endif
165
+#if HAS_V_STEP
166
+  #define ISR_V_STEPPER_CYCLES  ISR_STEPPER_CYCLES
167
+#endif
168
+#if HAS_W_STEP
169
+  #define ISR_W_STEPPER_CYCLES  ISR_STEPPER_CYCLES
170
+#endif
162 171
 #if HAS_EXTRUDERS
163 172
   #define ISR_E_STEPPER_CYCLES  ISR_STEPPER_CYCLES    // E is always interpolated, even for mixing extruders
164 173
 #endif
165 174
 
166 175
 // And the total minimum loop time, not including the base
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))
176
+#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, + ISR_U_STEPPER_CYCLES, + ISR_V_STEPPER_CYCLES, + ISR_W_STEPPER_CYCLES))
168 177
 
169 178
 // Calculate the minimum MPU cycles needed per pulse to enforce, limited to the max stepper rate
170 179
 #define _MIN_STEPPER_PULSE_CYCLES(N) _MAX(uint32_t((F_CPU) / (MAXIMUM_STEPPER_RATE)), ((F_CPU) / 500000UL) * (N))
@@ -236,7 +245,7 @@
236 245
 // Perhaps DISABLE_MULTI_STEPPING should be required with ADAPTIVE_STEP_SMOOTHING.
237 246
 #define MIN_STEP_ISR_FREQUENCY (MAX_STEP_ISR_FREQUENCY_1X / 2)
238 247
 
239
-#define ENABLE_COUNT (LINEAR_AXES + E_STEPPERS)
248
+#define ENABLE_COUNT (NUM_AXES + E_STEPPERS)
240 249
 typedef IF<(ENABLE_COUNT > 8), uint16_t, uint8_t>::type ena_mask_t;
241 250
 
242 251
 // Axis flags type, for enabled state or other simple state
@@ -244,25 +253,25 @@ typedef struct {
244 253
   union {
245 254
     ena_mask_t bits;
246 255
     struct {
247
-      bool LINEAR_AXIS_LIST(X:1, Y:1, Z:1, I:1, J:1, K:1);
256
+      bool NUM_AXIS_LIST(X:1, Y:1, Z:1, I:1, J:1, K:1, U:1, V:1, W:1);
248 257
       #if HAS_EXTRUDERS
249 258
         bool LIST_N(EXTRUDERS, E0:1, E1:1, E2:1, E3:1, E4:1, E5:1, E6:1, E7:1);
250 259
       #endif
251 260
     };
252 261
   };
253
-  constexpr ena_mask_t linear_bits() { return _BV(LINEAR_AXES) - 1; }
254
-  constexpr ena_mask_t e_bits() { return (_BV(EXTRUDERS) - 1) << LINEAR_AXES; }
262
+  constexpr ena_mask_t linear_bits() { return _BV(NUM_AXES) - 1; }
263
+  constexpr ena_mask_t e_bits() { return (_BV(EXTRUDERS) - 1) << NUM_AXES; }
255 264
 } axis_flags_t;
256 265
 
257 266
 // All the stepper enable pins
258 267
 constexpr pin_t ena_pins[] = {
259
-  LINEAR_AXIS_LIST(X_ENABLE_PIN, Y_ENABLE_PIN, Z_ENABLE_PIN, I_ENABLE_PIN, J_ENABLE_PIN, K_ENABLE_PIN),
268
+  NUM_AXIS_LIST(X_ENABLE_PIN, Y_ENABLE_PIN, Z_ENABLE_PIN, I_ENABLE_PIN, J_ENABLE_PIN, K_ENABLE_PIN, U_ENABLE_PIN, V_ENABLE_PIN, W_ENABLE_PIN),
260 269
   LIST_N(E_STEPPERS, E0_ENABLE_PIN, E1_ENABLE_PIN, E2_ENABLE_PIN, E3_ENABLE_PIN, E4_ENABLE_PIN, E5_ENABLE_PIN, E6_ENABLE_PIN, E7_ENABLE_PIN)
261 270
 };
262 271
 
263 272
 // Index of the axis or extruder element in a combined array
264 273
 constexpr uint8_t index_of_axis(const AxisEnum axis E_OPTARG(const uint8_t eindex=0)) {
265
-  return uint8_t(axis) + (E_TERN0(axis < LINEAR_AXES ? 0 : eindex));
274
+  return uint8_t(axis) + (E_TERN0(axis < NUM_AXES ? 0 : eindex));
266 275
 }
267 276
 //#define __IAX_N(N,V...)           _IAX_##N(V)
268 277
 //#define _IAX_N(N,V...)            __IAX_N(N,V)
@@ -292,7 +301,7 @@ constexpr bool any_enable_overlap(const uint8_t a=0) {
292 301
 //       (e.g., CoreXY, Dual XYZ, or E with multiple steppers, etc.).
293 302
 constexpr ena_mask_t enable_overlap[] = {
294 303
   #define _OVERLAP(N) ena_overlap(INDEX_OF_AXIS(AxisEnum(N))),
295
-  REPEAT(LINEAR_AXES, _OVERLAP)
304
+  REPEAT(NUM_AXES, _OVERLAP)
296 305
   #if HAS_EXTRUDERS
297 306
     #define _E_OVERLAP(N) ena_overlap(INDEX_OF_AXIS(E_AXIS, N)),
298 307
     REPEAT(E_STEPPERS, _E_OVERLAP)
@@ -320,7 +329,7 @@ class Stepper {
320 329
         #ifndef MOTOR_CURRENT_PWM_FREQUENCY
321 330
           #define MOTOR_CURRENT_PWM_FREQUENCY 31400
322 331
         #endif
323
-        #define MOTOR_CURRENT_COUNT LINEAR_AXES
332
+        #define MOTOR_CURRENT_COUNT NUM_AXES
324 333
       #elif HAS_MOTOR_CURRENT_SPI
325 334
         static constexpr uint32_t digipot_count[] = DIGIPOT_MOTOR_CURRENT;
326 335
         #define MOTOR_CURRENT_COUNT COUNT(Stepper::digipot_count)

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

@@ -64,6 +64,15 @@
64 64
 #if AXIS_IS_L64XX(K)
65 65
   L64XX_CLASS(K) stepperK(L6470_CHAIN_SS_PIN);
66 66
 #endif
67
+#if AXIS_IS_L64XX(U)
68
+  L64XX_CLASS(u) stepperU(L6470_CHAIN_SS_PIN);
69
+#endif
70
+#if AXIS_IS_L64XX(V)
71
+  L64XX_CLASS(v) stepperV(L6470_CHAIN_SS_PIN);
72
+#endif
73
+#if AXIS_IS_L64XX(W)
74
+  L64XX_CLASS(w) stepperW(L6470_CHAIN_SS_PIN);
75
+#endif
67 76
 #if AXIS_IS_L64XX(E0)
68 77
   L64XX_CLASS(E0) stepperE0(L6470_CHAIN_SS_PIN);
69 78
 #endif
@@ -217,6 +226,15 @@ void L64XX_Marlin::init_to_defaults() {
217 226
   #if AXIS_IS_L64XX(K)
218 227
     L6470_INIT_CHIP(K);
219 228
   #endif
229
+  #if AXIS_IS_L64XX(U)
230
+    L6470_INIT_CHIP(U);
231
+  #endif
232
+  #if AXIS_IS_L64XX(V)
233
+    L6470_INIT_CHIP(V);
234
+  #endif
235
+  #if AXIS_IS_L64XX(W)
236
+    L6470_INIT_CHIP(W);
237
+  #endif
220 238
   #if AXIS_IS_L64XX(E0)
221 239
     L6470_INIT_CHIP(E0);
222 240
   #endif

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

@@ -266,6 +266,72 @@
266 266
   #endif
267 267
 #endif
268 268
 
269
+// U Stepper
270
+#if HAS_U_AXIS
271
+  #if AXIS_IS_L64XX(U)
272
+    extern L64XX_CLASS(U)         stepperU;
273
+    #define U_ENABLE_INIT()       NOOP
274
+    #define U_ENABLE_WRITE(STATE) (STATE ? stepperU.hardStop() : stepperU.free())
275
+    #define U_ENABLE_READ()       (stepperU.getStatus() & STATUS_HIZ)
276
+    #if AXIS_DRIVER_TYPE_U(L6474)
277
+      #define U_DIR_INIT()        SET_OUTPUT(U_DIR_PIN)
278
+      #define U_DIR_WRITE(STATE)  L6474_DIR_WRITE(U, STATE)
279
+      #define U_DIR_READ()        READ(U_DIR_PIN)
280
+    #else
281
+      #define U_DIR_INIT()        NOOP
282
+      #define U_DIR_WRITE(STATE)  L64XX_DIR_WRITE(U, STATE)
283
+      #define U_DIR_READ()        (stepper##U.getStatus() & STATUS_DIR);
284
+      #if AXIS_DRIVER_TYPE_U(L6470)
285
+        #define DISABLE_STEPPER_U() stepperU.free()
286
+      #endif
287
+    #endif
288
+  #endif
289
+#endif
290
+
291
+// V Stepper
292
+#if HAS_V_AXIS
293
+  #if AXIS_IS_L64XX(V)
294
+    extern L64XX_CLASS(V)         stepperV;
295
+    #define V_ENABLE_INIT()       NOOP
296
+    #define V_ENABLE_WRITE(STATE) (STATE ? stepperV.hardStop() : stepperV.free())
297
+    #define V_ENABLE_READ()       (stepperV.getStatus() & STATUS_HIZ)
298
+    #if AXIS_DRIVER_TYPE_V(L6474)
299
+      #define V_DIR_INIT()        SET_OUTPUT(V_DIR_PIN)
300
+      #define V_DIR_WRITE(STATE)  L6474_DIR_WRITE(V, STATE)
301
+      #define V_DIR_READ()        READ(V_DIR_PIN)
302
+    #else
303
+      #define V_DIR_INIT()        NOOP
304
+      #define V_DIR_WRITE(STATE)  L64XX_DIR_WRITE(V, STATE)
305
+      #define V_DIR_READ()        (stepper##V.getStatus() & STATUS_DIR);
306
+      #if AXIS_DRIVER_TYPE_V(L6470)
307
+        #define DISABLE_STEPPER_V() stepperV.free()
308
+      #endif
309
+    #endif
310
+  #endif
311
+#endif
312
+
313
+// W Stepper
314
+#if HAS_W_AXIS
315
+  #if AXIS_IS_L64XX(W)
316
+    extern L64XX_CLASS(w)         stepperW;
317
+    #define W_ENABLE_INIT()       NOOP
318
+    #define W_ENABLE_WRITE(STATE) (STATE ? stepperW.hardStop() : stepperW.free())
319
+    #define W_ENABLE_READ()       (stepperW.getStatus() & STATUS_HIZ)
320
+    #if AXIS_DRIVER_TYPE_W(L6474)
321
+      #define W_DIR_INIT()        SET_OUTPUT(W_DIR_PIN)
322
+      #define W_DIR_WRITE(STATE)  L6474_DIR_WRITE(W, STATE)
323
+      #define W_DIR_READ()        READ(W_DIR_PIN)
324
+    #else
325
+      #define W_DIR_INIT()        NOOP
326
+      #define W_DIR_WRITE(STATE)  L64XX_DIR_WRITE(W, STATE)
327
+      #define W_DIR_READ()        (stepper##W.getStatus() & STATUS_DIR);
328
+      #if AXIS_DRIVER_TYPE_W(L6470)
329
+        #define DISABLE_STEPPER_W() stepperW.free()
330
+      #endif
331
+    #endif
332
+  #endif
333
+#endif
334
+
269 335
 // E0 Stepper
270 336
 #if AXIS_IS_L64XX(E0)
271 337
   extern L64XX_CLASS(E0)         stepperE0;

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

@@ -69,6 +69,15 @@
69 69
 #if AXIS_DRIVER_TYPE_K(TMC26X)
70 70
   _TMC26X_DEFINE(K);
71 71
 #endif
72
+#if AXIS_DRIVER_TYPE_U(TMC26X)
73
+  _TMC26X_DEFINE(U);
74
+#endif
75
+#if AXIS_DRIVER_TYPE_V(TMC26X)
76
+  _TMC26X_DEFINE(V);
77
+#endif
78
+#if AXIS_DRIVER_TYPE_W(TMC26X)
79
+  _TMC26X_DEFINE(W);
80
+#endif
72 81
 #if AXIS_DRIVER_TYPE_E0(TMC26X)
73 82
   _TMC26X_DEFINE(E0);
74 83
 #endif
@@ -133,6 +142,15 @@ void tmc26x_init_to_defaults() {
133 142
   #if AXIS_DRIVER_TYPE_K(TMC26X)
134 143
     _TMC26X_INIT(K);
135 144
   #endif
145
+  #if AXIS_DRIVER_TYPE_U(TMC26X)
146
+    _TMC26X_INIT(U);
147
+  #endif
148
+  #if AXIS_DRIVER_TYPE_V(TMC26X)
149
+    _TMC26X_INIT(V);
150
+  #endif
151
+  #if AXIS_DRIVER_TYPE_W(TMC26X)
152
+    _TMC26X_INIT(W);
153
+  #endif
136 154
   #if AXIS_DRIVER_TYPE_E0(TMC26X)
137 155
     _TMC26X_INIT(E0);
138 156
   #endif

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

@@ -123,6 +123,30 @@ void tmc26x_init_to_defaults();
123 123
   #define K_ENABLE_READ() stepperK.isEnabled()
124 124
 #endif
125 125
 
126
+// U Stepper
127
+#if HAS_U_ENABLE && AXIS_DRIVER_TYPE_U(TMC26X)
128
+  extern TMC26XStepper stepperU;
129
+  #define U_ENABLE_INIT() NOOP
130
+  #define U_ENABLE_WRITE(STATE) stepperU.setEnabled(STATE)
131
+  #define U_ENABLE_READ() stepperU.isEnabled()
132
+#endif
133
+
134
+// V Stepper
135
+#if HAS_V_ENABLE && AXIS_DRIVER_TYPE_V(TMC26X)
136
+  extern TMC26XStepper stepperV;
137
+  #define V_ENABLE_INIT() NOOP
138
+  #define V_ENABLE_WRITE(STATE) stepperV.setEnabled(STATE)
139
+  #define V_ENABLE_READ() stepperV.isEnabled()
140
+#endif
141
+
142
+// W Stepper
143
+#if HAS_W_ENABLE && AXIS_DRIVER_TYPE_W(TMC26X)
144
+  extern TMC26XStepper stepperW;
145
+  #define W_ENABLE_INIT() NOOP
146
+  #define W_ENABLE_WRITE(STATE) stepperW.setEnabled(STATE)
147
+  #define W_ENABLE_READ() stepperW.isEnabled()
148
+#endif
149
+
126 150
 // E0 Stepper
127 151
 #if AXIS_DRIVER_TYPE_E0(TMC26X)
128 152
   extern TMC26XStepper stepperE0;

+ 124
- 0
Marlin/src/module/stepper/indirection.h View File

@@ -262,6 +262,63 @@ void reset_stepper_drivers();    // Called by settings.load / settings.reset
262 262
   #define K_STEP_READ() bool(READ(K_STEP_PIN))
263 263
 #endif
264 264
 
265
+// U Stepper
266
+#if HAS_U_AXIS
267
+  #ifndef U_ENABLE_INIT
268
+    #define U_ENABLE_INIT() SET_OUTPUT(U_ENABLE_PIN)
269
+    #define U_ENABLE_WRITE(STATE) WRITE(U_ENABLE_PIN,STATE)
270
+    #define U_ENABLE_READ() bool(READ(U_ENABLE_PIN))
271
+  #endif
272
+  #ifndef U_DIR_INIT
273
+    #define U_DIR_INIT() SET_OUTPUT(U_DIR_PIN)
274
+    #define U_DIR_WRITE(STATE) WRITE(U_DIR_PIN,STATE)
275
+    #define U_DIR_READ() bool(READ(U_DIR_PIN))
276
+  #endif
277
+  #define U_STEP_INIT() SET_OUTPUT(U_STEP_PIN)
278
+  #ifndef U_STEP_WRITE
279
+    #define U_STEP_WRITE(STATE) WRITE(U_STEP_PIN,STATE)
280
+  #endif
281
+  #define U_STEP_READ() bool(READ(U_STEP_PIN))
282
+#endif
283
+
284
+// V Stepper
285
+#if HAS_V_AXIS
286
+  #ifndef V_ENABLE_INIT
287
+    #define V_ENABLE_INIT() SET_OUTPUT(V_ENABLE_PIN)
288
+    #define V_ENABLE_WRITE(STATE) WRITE(V_ENABLE_PIN,STATE)
289
+    #define V_ENABLE_READ() bool(READ(V_ENABLE_PIN))
290
+  #endif
291
+  #ifndef V_DIR_INIT
292
+    #define V_DIR_INIT() SET_OUTPUT(V_DIR_PIN)
293
+    #define V_DIR_WRITE(STATE) WRITE(V_DIR_PIN,STATE)
294
+    #define V_DIR_READ() bool(READ(V_DIR_PIN))
295
+  #endif
296
+  #define V_STEP_INIT() SET_OUTPUT(V_STEP_PIN)
297
+  #ifndef V_STEP_WRITE
298
+    #define V_STEP_WRITE(STATE) WRITE(V_STEP_PIN,STATE)
299
+  #endif
300
+  #define V_STEP_READ() bool(READ(V_STEP_PIN))
301
+#endif
302
+
303
+// W Stepper
304
+#if HAS_W_AXIS
305
+  #ifndef W_ENABLE_INIT
306
+    #define W_ENABLE_INIT() SET_OUTPUT(W_ENABLE_PIN)
307
+    #define W_ENABLE_WRITE(STATE) WRITE(W_ENABLE_PIN,STATE)
308
+    #define W_ENABLE_READ() bool(READ(W_ENABLE_PIN))
309
+  #endif
310
+  #ifndef W_DIR_INIT
311
+    #define W_DIR_INIT() SET_OUTPUT(W_DIR_PIN)
312
+    #define W_DIR_WRITE(STATE) WRITE(W_DIR_PIN,STATE)
313
+    #define W_DIR_READ() bool(READ(W_DIR_PIN))
314
+  #endif
315
+  #define W_STEP_INIT() SET_OUTPUT(W_STEP_PIN)
316
+  #ifndef W_STEP_WRITE
317
+    #define W_STEP_WRITE(STATE) WRITE(W_STEP_PIN,STATE)
318
+  #endif
319
+  #define W_STEP_READ() bool(READ(W_STEP_PIN))
320
+#endif
321
+
265 322
 // E0 Stepper
266 323
 #ifndef E0_ENABLE_INIT
267 324
   #define E0_ENABLE_INIT() SET_OUTPUT(E0_ENABLE_PIN)
@@ -743,6 +800,51 @@ void reset_stepper_drivers();    // Called by settings.load / settings.reset
743 800
   #define DISABLE_STEPPER_K() TERN(HAS_K_ENABLE, K_ENABLE_WRITE(!K_ENABLE_ON), NOOP)
744 801
 #endif
745 802
 
803
+#ifndef ENABLE_STEPPER_U
804
+  #if HAS_U_ENABLE
805
+    #define  ENABLE_STEPPER_U() U_ENABLE_WRITE( U_ENABLE_ON)
806
+  #else
807
+    #define  ENABLE_STEPPER_U() NOOP
808
+  #endif
809
+#endif
810
+#ifndef DISABLE_STEPPER_U
811
+  #if HAS_U_ENABLE
812
+    #define DISABLE_STEPPER_U() U_ENABLE_WRITE(!U_ENABLE_ON)
813
+  #else
814
+    #define DISABLE_STEPPER_U() NOOP
815
+  #endif
816
+#endif
817
+
818
+#ifndef ENABLE_STEPPER_V
819
+  #if HAS_V_ENABLE
820
+    #define  ENABLE_STEPPER_V() V_ENABLE_WRITE( V_ENABLE_ON)
821
+  #else
822
+    #define  ENABLE_STEPPER_V() NOOP
823
+  #endif
824
+#endif
825
+#ifndef DISABLE_STEPPER_V
826
+  #if HAS_V_ENABLE
827
+    #define DISABLE_STEPPER_V() V_ENABLE_WRITE(!V_ENABLE_ON)
828
+  #else
829
+    #define DISABLE_STEPPER_V() NOOP
830
+  #endif
831
+#endif
832
+
833
+#ifndef ENABLE_STEPPER_W
834
+  #if HAS_W_ENABLE
835
+    #define  ENABLE_STEPPER_W() W_ENABLE_WRITE( W_ENABLE_ON)
836
+  #else
837
+    #define  ENABLE_STEPPER_W() NOOP
838
+  #endif
839
+#endif
840
+#ifndef DISABLE_STEPPER_W
841
+  #if HAS_W_ENABLE
842
+    #define DISABLE_STEPPER_W() W_ENABLE_WRITE(!W_ENABLE_ON)
843
+  #else
844
+    #define DISABLE_STEPPER_W() NOOP
845
+  #endif
846
+#endif
847
+
746 848
 #ifndef ENABLE_STEPPER_E0
747 849
   #define  ENABLE_STEPPER_E0() TERN(HAS_E0_ENABLE, E0_ENABLE_WRITE( E_ENABLE_ON), NOOP)
748 850
 #endif
@@ -917,6 +1019,28 @@ void reset_stepper_drivers();    // Called by settings.load / settings.reset
917 1019
   #define DISABLE_AXIS_K() NOOP
918 1020
 #endif
919 1021
 
1022
+#if HAS_U_AXIS
1023
+  #define  ENABLE_AXIS_U() if (SHOULD_ENABLE(u))  {  ENABLE_STEPPER_U(); AFTER_CHANGE(u, true); }
1024
+  #define DISABLE_AXIS_U() if (SHOULD_DISABLE(u)) { DISABLE_STEPPER_U(); AFTER_CHANGE(u, false); set_axis_untrusted(U_AXIS); }
1025
+#else
1026
+  #define  ENABLE_AXIS_U() NOOP
1027
+  #define DISABLE_AXIS_U() NOOP
1028
+#endif
1029
+#if HAS_V_AXIS
1030
+  #define  ENABLE_AXIS_V() if (SHOULD_ENABLE(v))  {  ENABLE_STEPPER_V(); AFTER_CHANGE(v, true); }
1031
+  #define DISABLE_AXIS_V() if (SHOULD_DISABLE(v)) { DISABLE_STEPPER_V(); AFTER_CHANGE(v, false); set_axis_untrusted(V_AXIS); }
1032
+#else
1033
+  #define  ENABLE_AXIS_V() NOOP
1034
+  #define DISABLE_AXIS_V() NOOP
1035
+#endif
1036
+#if HAS_W_AXIS
1037
+  #define  ENABLE_AXIS_W() if (SHOULD_ENABLE(w))  {  ENABLE_STEPPER_W(); AFTER_CHANGE(w, true); }
1038
+  #define DISABLE_AXIS_W() if (SHOULD_DISABLE(w)) { DISABLE_STEPPER_W(); AFTER_CHANGE(w, false); set_axis_untrusted(W_AXIS); }
1039
+#else
1040
+  #define  ENABLE_AXIS_W() NOOP
1041
+  #define DISABLE_AXIS_W() NOOP
1042
+#endif
1043
+
920 1044
 //
921 1045
 // Extruder steppers enable / disable macros
922 1046
 //

+ 94
- 7
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, STEALTH_AXIS_I, STEALTH_AXIS_J, STEALTH_AXIS_K)
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, STEALTH_AXIS_U, STEALTH_AXIS_V, STEALTH_AXIS_W)
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, ST##_HOLD_MULTIPLIER)
42 42
 
@@ -106,6 +106,15 @@ enum StealthIndex : uint8_t {
106 106
 #if AXIS_HAS_SPI(K)
107 107
   TMC_SPI_DEFINE(K, K);
108 108
 #endif
109
+#if AXIS_HAS_SPI(U)
110
+  TMC_SPI_DEFINE(U, U);
111
+#endif
112
+#if AXIS_HAS_SPI(V)
113
+  TMC_SPI_DEFINE(V, V);
114
+#endif
115
+#if AXIS_HAS_SPI(W)
116
+  TMC_SPI_DEFINE(W, W);
117
+#endif
109 118
 #if AXIS_HAS_SPI(E0)
110 119
   TMC_SPI_DEFINE_E(0);
111 120
 #endif
@@ -173,6 +182,15 @@ enum StealthIndex : uint8_t {
173 182
 #ifndef TMC_K_BAUD_RATE
174 183
   #define TMC_K_BAUD_RATE TMC_BAUD_RATE
175 184
 #endif
185
+#ifndef TMC_U_BAUD_RATE
186
+  #define TMC_U_BAUD_RATE TMC_BAUD_RATE
187
+#endif
188
+#ifndef TMC_V_BAUD_RATE
189
+  #define TMC_V_BAUD_RATE TMC_BAUD_RATE
190
+#endif
191
+#ifndef TMC_W_BAUD_RATE
192
+  #define TMC_W_BAUD_RATE TMC_BAUD_RATE
193
+#endif
176 194
 #ifndef TMC_E0_BAUD_RATE
177 195
   #define TMC_E0_BAUD_RATE TMC_BAUD_RATE
178 196
 #endif
@@ -374,6 +392,32 @@ enum StealthIndex : uint8_t {
374 392
       #define K_HAS_SW_SERIAL 1
375 393
     #endif
376 394
   #endif
395
+  #if AXIS_HAS_UART(U)
396
+    #ifdef U_HARDWARE_SERIAL
397
+      TMC_UART_DEFINE(HW, U, U);
398
+      #define U_HAS_HW_SERIAL 1
399
+    #else
400
+      TMC_UART_DEFINE(SW, U, U);
401
+      #define U_HAS_SW_SERIAL 1
402
+    #endif
403
+  #endif
404
+  #if AXIS_HAS_UART(V)
405
+    #ifdef V_HARDWARE_SERIAL
406
+      TMC_UART_DEFINE(HW, V, V);
407
+    #else
408
+      TMC_UART_DEFINE(SW, V, V);
409
+      #define V_HAS_SW_SERIAL 1
410
+    #endif
411
+  #endif
412
+  #if AXIS_HAS_UART(W)
413
+    #ifdef W_HARDWARE_SERIAL
414
+      TMC_UART_DEFINE(HW, W, W);
415
+      #define W_HAS_HW_SERIAL 1
416
+    #else
417
+      TMC_UART_DEFINE(SW, W, W);
418
+      #define W_HAS_SW_SERIAL 1
419
+    #endif
420
+  #endif
377 421
 
378 422
   #if AXIS_HAS_UART(E0)
379 423
     #ifdef E0_HARDWARE_SERIAL
@@ -449,7 +493,7 @@ enum StealthIndex : uint8_t {
449 493
   #endif
450 494
 
451 495
   #define _EN_ITEM(N) , E##N
452
-  enum TMCAxis : uint8_t { LINEAR_AXIS_LIST(X, Y, Z, I, J, K), X2, Y2, Z2, Z3, Z4 REPEAT(EXTRUDERS, _EN_ITEM), TOTAL };
496
+  enum TMCAxis : uint8_t { NUM_AXIS_LIST(X, Y, Z, I, J, K, U, V, W), X2, Y2, Z2, Z3, Z4 REPEAT(EXTRUDERS, _EN_ITEM), TOTAL };
453 497
   #undef _EN_ITEM
454 498
 
455 499
   void tmc_serial_begin() {
@@ -543,6 +587,27 @@ enum StealthIndex : uint8_t {
543 587
         stepperK.beginSerial(TMC_BAUD_RATE);
544 588
       #endif
545 589
     #endif
590
+    #if AXIS_HAS_UART(U)
591
+      #ifdef U_HARDWARE_SERIAL
592
+        HW_SERIAL_BEGIN(U);
593
+      #else
594
+        stepperU.beginSerial(TMC_BAUD_RATE);
595
+      #endif
596
+    #endif
597
+    #if AXIS_HAS_UART(V)
598
+      #ifdef V_HARDWARE_SERIAL
599
+        HW_SERIAL_BEGIN(V);
600
+      #else
601
+        stepperV.beginSerial(TMC_BAUD_RATE);
602
+      #endif
603
+    #endif
604
+    #if AXIS_HAS_UART(W)
605
+      #ifdef W_HARDWARE_SERIAL
606
+        HW_SERIAL_BEGIN(W);
607
+      #else
608
+        stepperW.beginSerial(TMC_BAUD_RATE);
609
+      #endif
610
+    #endif
546 611
     #if AXIS_HAS_UART(E0)
547 612
       #ifdef E0_HARDWARE_SERIAL
548 613
         HW_SERIAL_BEGIN(E0);
@@ -814,6 +879,15 @@ void restore_trinamic_drivers() {
814 879
   #if AXIS_IS_TMC(K)
815 880
     stepperK.push();
816 881
   #endif
882
+  #if AXIS_IS_TMC(U)
883
+    stepperU.push();
884
+  #endif
885
+  #if AXIS_IS_TMC(V)
886
+    stepperV.push();
887
+  #endif
888
+  #if AXIS_IS_TMC(W)
889
+    stepperW.push();
890
+  #endif
817 891
   #if AXIS_IS_TMC(E0)
818 892
     stepperE0.push();
819 893
   #endif
@@ -844,7 +918,8 @@ void reset_trinamic_drivers() {
844 918
   static constexpr bool stealthchop_by_axis[] = LOGICAL_AXIS_ARRAY(
845 919
     ENABLED(STEALTHCHOP_E),
846 920
     ENABLED(STEALTHCHOP_XY), ENABLED(STEALTHCHOP_XY), ENABLED(STEALTHCHOP_Z),
847
-    ENABLED(STEALTHCHOP_I), ENABLED(STEALTHCHOP_J), ENABLED(STEALTHCHOP_K)
921
+    ENABLED(STEALTHCHOP_I), ENABLED(STEALTHCHOP_J), ENABLED(STEALTHCHOP_K),
922
+    ENABLED(STEALTHCHOP_U), ENABLED(STEALTHCHOP_V), ENABLED(STEALTHCHOP_W)
848 923
   );
849 924
 
850 925
   #if AXIS_IS_TMC(X)
@@ -880,6 +955,15 @@ void reset_trinamic_drivers() {
880 955
   #if AXIS_IS_TMC(K)
881 956
     TMC_INIT(K, STEALTH_AXIS_K);
882 957
   #endif
958
+  #if AXIS_IS_TMC(U)
959
+    TMC_INIT(U, STEALTH_AXIS_U);
960
+  #endif
961
+  #if AXIS_IS_TMC(V)
962
+    TMC_INIT(V, STEALTH_AXIS_V);
963
+  #endif
964
+  #if AXIS_IS_TMC(W)
965
+    TMC_INIT(W, STEALTH_AXIS_W);
966
+  #endif
883 967
   #if AXIS_IS_TMC(E0)
884 968
     TMC_INIT(E0, STEALTH_AXIS_E);
885 969
   #endif
@@ -917,6 +1001,9 @@ void reset_trinamic_drivers() {
917 1001
     TERN_(I_SENSORLESS, stepperI.homing_threshold(I_STALL_SENSITIVITY));
918 1002
     TERN_(J_SENSORLESS, stepperJ.homing_threshold(J_STALL_SENSITIVITY));
919 1003
     TERN_(K_SENSORLESS, stepperK.homing_threshold(K_STALL_SENSITIVITY));
1004
+    TERN_(U_SENSORLESS, stepperU.homing_threshold(U_STALL_SENSITIVITY));
1005
+    TERN_(V_SENSORLESS, stepperV.homing_threshold(V_STALL_SENSITIVITY));
1006
+    TERN_(W_SENSORLESS, stepperW.homing_threshold(W_STALL_SENSITIVITY));
920 1007
   #endif
921 1008
 
922 1009
   #ifdef TMC_ADV
@@ -946,7 +1033,7 @@ void reset_trinamic_drivers() {
946 1033
     TMC_HW_DETAIL(X), TMC_HW_DETAIL(X2),
947 1034
     TMC_HW_DETAIL(Y), TMC_HW_DETAIL(Y2),
948 1035
     TMC_HW_DETAIL(Z), TMC_HW_DETAIL(Z2), TMC_HW_DETAIL(Z3), TMC_HW_DETAIL(Z4),
949
-    TMC_HW_DETAIL(I), TMC_HW_DETAIL(J), TMC_HW_DETAIL(K),
1036
+    TMC_HW_DETAIL(I), TMC_HW_DETAIL(J), TMC_HW_DETAIL(K), TMC_HW_DETAIL(U), TMC_HW_DETAIL(V), TMC_HW_DETAIL(W),
950 1037
     TMC_HW_DETAIL(E0), TMC_HW_DETAIL(E1), TMC_HW_DETAIL(E2), TMC_HW_DETAIL(E3), TMC_HW_DETAIL(E4), TMC_HW_DETAIL(E5), TMC_HW_DETAIL(E6), TMC_HW_DETAIL(E7)
951 1038
   };
952 1039
 
@@ -969,7 +1056,7 @@ void reset_trinamic_drivers() {
969 1056
   SA_NO_TMC_HW_C(X); SA_NO_TMC_HW_C(X2);
970 1057
   SA_NO_TMC_HW_C(Y); SA_NO_TMC_HW_C(Y2);
971 1058
   SA_NO_TMC_HW_C(Z); SA_NO_TMC_HW_C(Z2); SA_NO_TMC_HW_C(Z3); SA_NO_TMC_HW_C(Z4);
972
-  SA_NO_TMC_HW_C(I); SA_NO_TMC_HW_C(J); SA_NO_TMC_HW_C(K);
1059
+  SA_NO_TMC_HW_C(I); SA_NO_TMC_HW_C(J); SA_NO_TMC_HW_C(K); SA_NO_TMC_HW_C(U); SA_NO_TMC_HW_C(V); SA_NO_TMC_HW_C(W);
973 1060
   SA_NO_TMC_HW_C(E0); SA_NO_TMC_HW_C(E1); SA_NO_TMC_HW_C(E2); SA_NO_TMC_HW_C(E3); SA_NO_TMC_HW_C(E4); SA_NO_TMC_HW_C(E5); SA_NO_TMC_HW_C(E6); SA_NO_TMC_HW_C(E7);
974 1061
 #endif
975 1062
 
@@ -981,7 +1068,7 @@ void reset_trinamic_drivers() {
981 1068
     TMC_SW_DETAIL(X), TMC_SW_DETAIL(X2),
982 1069
     TMC_SW_DETAIL(Y), TMC_SW_DETAIL(Y2),
983 1070
     TMC_SW_DETAIL(Z), TMC_SW_DETAIL(Z2), TMC_SW_DETAIL(Z3), TMC_SW_DETAIL(Z4),
984
-    TMC_SW_DETAIL(I), TMC_SW_DETAIL(J), TMC_SW_DETAIL(K),
1071
+    TMC_SW_DETAIL(I), TMC_SW_DETAIL(J), TMC_SW_DETAIL(K), TMC_SW_DETAIL(U), TMC_SW_DETAIL(V), TMC_SW_DETAIL(W),
985 1072
     TMC_SW_DETAIL(E0), TMC_SW_DETAIL(E1), TMC_SW_DETAIL(E2), TMC_SW_DETAIL(E3), TMC_SW_DETAIL(E4), TMC_SW_DETAIL(E5), TMC_SW_DETAIL(E6), TMC_SW_DETAIL(E7)
986 1073
   };
987 1074
 
@@ -999,7 +1086,7 @@ void reset_trinamic_drivers() {
999 1086
   SA_NO_TMC_SW_C(X); SA_NO_TMC_SW_C(X2);
1000 1087
   SA_NO_TMC_SW_C(Y); SA_NO_TMC_SW_C(Y2);
1001 1088
   SA_NO_TMC_SW_C(Z); SA_NO_TMC_SW_C(Z2); SA_NO_TMC_SW_C(Z3); SA_NO_TMC_SW_C(Z4);
1002
-  SA_NO_TMC_SW_C(I); SA_NO_TMC_SW_C(J); SA_NO_TMC_SW_C(K);
1089
+  SA_NO_TMC_SW_C(I); SA_NO_TMC_SW_C(J); SA_NO_TMC_SW_C(K); SA_NO_TMC_SW_C(U); SA_NO_TMC_SW_C(V); SA_NO_TMC_SW_C(W);
1003 1090
   SA_NO_TMC_SW_C(E0); SA_NO_TMC_SW_C(E1); SA_NO_TMC_SW_C(E2); SA_NO_TMC_SW_C(E3); SA_NO_TMC_SW_C(E4); SA_NO_TMC_SW_C(E5); SA_NO_TMC_SW_C(E6); SA_NO_TMC_SW_C(E7);
1004 1091
 #endif
1005 1092
 

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

@@ -49,6 +49,9 @@
49 49
 #define TMC_I_LABEL 'I', '0'
50 50
 #define TMC_J_LABEL 'J', '0'
51 51
 #define TMC_K_LABEL 'K', '0'
52
+#define TMC_U_LABEL 'U', '0'
53
+#define TMC_V_LABEL 'V', '0'
54
+#define TMC_W_LABEL 'W', '0'
52 55
 
53 56
 #define TMC_X2_LABEL 'X', '2'
54 57
 #define TMC_Y2_LABEL 'Y', '2'
@@ -92,6 +95,15 @@
92 95
 #if HAS_K_AXIS && !defined(CHOPPER_TIMING_K)
93 96
   #define CHOPPER_TIMING_K CHOPPER_TIMING
94 97
 #endif
98
+#if HAS_U_AXIS && !defined(CHOPPER_TIMING_U)
99
+  #define CHOPPER_TIMING_U CHOPPER_TIMING
100
+#endif
101
+#if HAS_V_AXIS && !defined(CHOPPER_TIMING_V)
102
+  #define CHOPPER_TIMING_V CHOPPER_TIMING
103
+#endif
104
+#if HAS_W_AXIS && !defined(CHOPPER_TIMING_W)
105
+  #define CHOPPER_TIMING_W CHOPPER_TIMING
106
+#endif
95 107
 #if HAS_EXTRUDERS && !defined(CHOPPER_TIMING_E)
96 108
   #define CHOPPER_TIMING_E CHOPPER_TIMING
97 109
 #endif
@@ -274,6 +286,48 @@ void reset_trinamic_drivers();
274 286
   #endif
275 287
 #endif
276 288
 
289
+// U Stepper
290
+#if AXIS_IS_TMC(U)
291
+  extern TMC_CLASS(U, U) stepperU;
292
+  static constexpr chopper_timing_t chopper_timing_U = CHOPPER_TIMING_U;
293
+  #if ENABLED(SOFTWARE_DRIVER_ENABLE)
294
+    #define U_ENABLE_INIT() NOOP
295
+    #define U_ENABLE_WRITE(STATE) stepperU.toff((STATE)==U_ENABLE_ON ? chopper_timing_U.toff : 0)
296
+    #define U_ENABLE_READ() stepperU.isEnabled()
297
+  #endif
298
+  #if AXIS_HAS_SQUARE_WAVE(U)
299
+    #define U_STEP_WRITE(STATE) do{ if(STATE) TOGGLE(U_STEP_PIN); }while(0)
300
+  #endif
301
+#endif
302
+
303
+// V Stepper
304
+#if AXIS_IS_TMC(V)
305
+  extern TMC_CLASS(V, V) stepperV;
306
+  static constexpr chopper_timing_t chopper_timing_V = CHOPPER_TIMING_V;
307
+  #if ENABLED(SOFTWARE_DRIVER_ENABLE)
308
+    #define V_ENABLE_INIT() NOOP
309
+    #define V_ENABLE_WRITE(STATE) stepperV.toff((STATE)==V_ENABLE_ON ? chopper_timing_V.toff : 0)
310
+    #define V_ENABLE_READ() stepperV.isEnabled()
311
+  #endif
312
+  #if AXIS_HAS_SQUARE_WAVE(V)
313
+    #define V_STEP_WRITE(STATE) do{ if(STATE) TOGGLE(V_STEP_PIN); }while(0)
314
+  #endif
315
+#endif
316
+
317
+// W Stepper
318
+#if AXIS_IS_TMC(W)
319
+  extern TMC_CLASS(W, W) stepperW;
320
+  static constexpr chopper_timing_t chopper_timing_W = CHOPPER_TIMING_W;
321
+  #if ENABLED(SOFTWARE_DRIVER_ENABLE)
322
+    #define W_ENABLE_INIT() NOOP
323
+    #define W_ENABLE_WRITE(STATE) stepperW.toff((STATE)==W_ENABLE_ON ? chopper_timing_W.toff : 0)
324
+    #define W_ENABLE_READ() stepperW.isEnabled()
325
+  #endif
326
+  #if AXIS_HAS_SQUARE_WAVE(W)
327
+    #define W_STEP_WRITE(STATE) do{ if(STATE) TOGGLE(W_STEP_PIN); }while(0)
328
+  #endif
329
+#endif
330
+
277 331
 // E0 Stepper
278 332
 #if AXIS_IS_TMC(E0)
279 333
   extern TMC_CLASS_E(0) stepperE0;

+ 21
- 1
Marlin/src/module/tool_change.cpp View File

@@ -926,6 +926,16 @@ void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_axis, 0.
926 926
         if (ok) {
927 927
           IF_DISABLED(TOOLCHANGE_PARK_Y_ONLY, current_position.x = toolchange_settings.change_point.x);
928 928
           IF_DISABLED(TOOLCHANGE_PARK_X_ONLY, current_position.y = toolchange_settings.change_point.y);
929
+          #if NONE(TOOLCHANGE_PARK_X_ONLY, TOOLCHANGE_PARK_Y_ONLY)
930
+            SECONDARY_AXIS_CODE(
931
+              current_position.i = toolchange_settings.change_point.i,
932
+              current_position.j = toolchange_settings.change_point.j,
933
+              current_position.k = toolchange_settings.change_point.k,
934
+              current_position.u = toolchange_settings.change_point.u,
935
+              current_position.v = toolchange_settings.change_point.v,
936
+              current_position.w = toolchange_settings.change_point.w,
937
+            );
938
+          #endif
929 939
           planner.buffer_line(current_position, MMM_TO_MMS(TOOLCHANGE_PARK_XY_FEEDRATE), active_extruder);
930 940
           planner.synchronize();
931 941
         }
@@ -1121,6 +1131,16 @@ void tool_change(const uint8_t new_tool, bool no_move/*=false*/) {
1121 1131
         if (can_move_away && toolchange_settings.enable_park) {
1122 1132
           IF_DISABLED(TOOLCHANGE_PARK_Y_ONLY, current_position.x = toolchange_settings.change_point.x);
1123 1133
           IF_DISABLED(TOOLCHANGE_PARK_X_ONLY, current_position.y = toolchange_settings.change_point.y);
1134
+          #if NONE(TOOLCHANGE_PARK_X_ONLY, TOOLCHANGE_PARK_Y_ONLY)
1135
+            SECONDARY_AXIS_CODE(
1136
+              current_position.i = toolchange_settings.change_point.i,
1137
+              current_position.j = toolchange_settings.change_point.j,
1138
+              current_position.k = toolchange_settings.change_point.k,
1139
+              current_position.u = toolchange_settings.change_point.u,
1140
+              current_position.v = toolchange_settings.change_point.v,
1141
+              current_position.w = toolchange_settings.change_point.w,
1142
+            );
1143
+          #endif
1124 1144
           planner.buffer_line(current_position, MMM_TO_MMS(TOOLCHANGE_PARK_XY_FEEDRATE), old_tool);
1125 1145
           planner.synchronize();
1126 1146
         }
@@ -1175,7 +1195,7 @@ void tool_change(const uint8_t new_tool, bool no_move/*=false*/) {
1175 1195
       sync_plan_position();
1176 1196
 
1177 1197
       #if ENABLED(DELTA)
1178
-        //LOOP_LINEAR_AXES(i) update_software_endstops(i); // or modify the constrain function
1198
+        //LOOP_NUM_AXES(i) update_software_endstops(i); // or modify the constrain function
1179 1199
         const bool safe_to_move = current_position.z < delta_clip_start_height - 1;
1180 1200
       #else
1181 1201
         constexpr bool safe_to_move = true;

+ 0
- 0
Marlin/src/module/tool_change.h View File


Some files were not shown because too many files changed in this diff

Loading…
Cancel
Save