Browse Source

♻️ Refactor axis counts and loops

Scott Lahteine 3 years ago
parent
commit
a6e5492b08
45 changed files with 178 additions and 165 deletions
  1. 18
    20
      Marlin/src/core/types.h
  2. 2
    2
      Marlin/src/core/utility.cpp
  3. 1
    1
      Marlin/src/feature/backlash.cpp
  4. 2
    2
      Marlin/src/feature/dac/dac_mcp4728.cpp
  5. 1
    1
      Marlin/src/feature/dac/stepper_dac.cpp
  6. 11
    11
      Marlin/src/feature/encoder_i2c.cpp
  7. 1
    1
      Marlin/src/feature/joystick.cpp
  8. 4
    4
      Marlin/src/feature/powerloss.cpp
  9. 1
    1
      Marlin/src/gcode/calibrate/G28.cpp
  10. 5
    5
      Marlin/src/gcode/calibrate/G33.cpp
  11. 6
    6
      Marlin/src/gcode/calibrate/M425.cpp
  12. 3
    3
      Marlin/src/gcode/calibrate/M666.cpp
  13. 1
    1
      Marlin/src/gcode/calibrate/M852.cpp
  14. 2
    2
      Marlin/src/gcode/config/M200-M205.cpp
  15. 1
    1
      Marlin/src/gcode/config/M92.cpp
  16. 4
    4
      Marlin/src/gcode/control/M350_M351.cpp
  17. 1
    1
      Marlin/src/gcode/control/M605.cpp
  18. 1
    1
      Marlin/src/gcode/feature/L6470/M906.cpp
  19. 3
    3
      Marlin/src/gcode/feature/digipot/M907-M910.cpp
  20. 3
    3
      Marlin/src/gcode/feature/pause/G61.cpp
  21. 3
    3
      Marlin/src/gcode/feature/trinamic/M122.cpp
  22. 1
    1
      Marlin/src/gcode/feature/trinamic/M569.cpp
  23. 1
    1
      Marlin/src/gcode/feature/trinamic/M906.cpp
  24. 2
    2
      Marlin/src/gcode/feature/trinamic/M911-M914.cpp
  25. 2
    2
      Marlin/src/gcode/gcode.cpp
  26. 1
    1
      Marlin/src/gcode/geometry/G53-G59.cpp
  27. 3
    3
      Marlin/src/gcode/geometry/G92.cpp
  28. 4
    4
      Marlin/src/gcode/geometry/M206_M428.cpp
  29. 3
    3
      Marlin/src/gcode/host/M114.cpp
  30. 2
    2
      Marlin/src/gcode/motion/M290.cpp
  31. 3
    3
      Marlin/src/gcode/probe/G38.cpp
  32. 23
    7
      Marlin/src/inc/Conditionals_LCD.h
  33. 12
    12
      Marlin/src/inc/SanityCheck.h
  34. 6
    6
      Marlin/src/lcd/marlinui.cpp
  35. 1
    1
      Marlin/src/lcd/menu/menu_advanced.cpp
  36. 1
    1
      Marlin/src/lcd/menu/menu_bed_leveling.cpp
  37. 1
    1
      Marlin/src/lcd/menu/menu_ubl.cpp
  38. 1
    1
      Marlin/src/libs/L64XX/L64XX_Marlin.cpp
  39. 5
    5
      Marlin/src/module/motion.cpp
  40. 7
    7
      Marlin/src/module/planner.cpp
  41. 9
    9
      Marlin/src/module/planner.h
  42. 1
    1
      Marlin/src/module/scara.cpp
  43. 13
    14
      Marlin/src/module/settings.cpp
  44. 1
    1
      Marlin/src/module/stepper.h
  45. 1
    1
      Marlin/src/module/tool_change.cpp

+ 18
- 20
Marlin/src/core/types.h View File

@@ -47,25 +47,23 @@ struct IF<true, L, R> { typedef L type; };
47 47
 //  - X_HEAD, Y_HEAD, and Z_HEAD should be used for Steppers on Core kinematics
48 48
 //
49 49
 enum AxisEnum : uint8_t {
50
-  X_AXIS   = 0, A_AXIS = 0,
51
-  Y_AXIS   = 1, B_AXIS = 1,
52
-  Z_AXIS   = 2, C_AXIS = 2,
53
-  E_AXIS   = 3,
54
-  X_HEAD   = 4, Y_HEAD = 5, Z_HEAD = 6,
55
-  E0_AXIS  = 3,
50
+  X_AXIS = 0, A_AXIS = X_AXIS,
51
+  Y_AXIS = 1, B_AXIS = Y_AXIS,
52
+  Z_AXIS = 2, C_AXIS = Z_AXIS,
53
+  E_AXIS,
54
+  X_HEAD, Y_HEAD, Z_HEAD,
55
+  E0_AXIS = E_AXIS,
56 56
   E1_AXIS, E2_AXIS, E3_AXIS, E4_AXIS, E5_AXIS, E6_AXIS, E7_AXIS,
57
-  ALL_AXES = 0xFE, NO_AXIS = 0xFF
57
+  ALL_AXES_MASK = 0xFE, NO_AXIS_MASK = 0xFF
58 58
 };
59 59
 
60 60
 //
61
-// Loop over XYZE axes
61
+// Loop over axes
62 62
 //
63
-#define LOOP_XYZ(VAR) LOOP_S_LE_N(VAR, X_AXIS, Z_AXIS)
64
-#define LOOP_XYZE(VAR) LOOP_S_LE_N(VAR, X_AXIS, E_AXIS)
65
-#define LOOP_XYZE_N(VAR) LOOP_S_L_N(VAR, X_AXIS, XYZE_N)
66 63
 #define LOOP_ABC(VAR) LOOP_S_LE_N(VAR, A_AXIS, C_AXIS)
67
-#define LOOP_ABCE(VAR) LOOP_S_LE_N(VAR, A_AXIS, E_AXIS)
68
-#define LOOP_ABCE_N(VAR) LOOP_S_L_N(VAR, A_AXIS, XYZE_N)
64
+#define LOOP_LINEAR_AXES(VAR) LOOP_S_L_N(VAR, X_AXIS, LINEAR_AXES)
65
+#define LOOP_LOGICAL_AXES(VAR) LOOP_S_L_N(VAR, X_AXIS, LOGICAL_AXES)
66
+#define LOOP_DISTINCT_AXES(VAR) LOOP_S_L_N(VAR, X_AXIS, DISTINCT_AXES)
69 67
 
70 68
 //
71 69
 // feedRate_t is just a humble float
@@ -201,8 +199,8 @@ struct XYval {
201 199
   FI void set(const T (&arr)[XY])                       { x = arr[0]; y = arr[1]; }
202 200
   FI void set(const T (&arr)[XYZ])                      { x = arr[0]; y = arr[1]; }
203 201
   FI void set(const T (&arr)[XYZE])                     { x = arr[0]; y = arr[1]; }
204
-  #if XYZE_N > XYZE
205
-    FI void set(const T (&arr)[XYZE_N])                 { x = arr[0]; y = arr[1]; }
202
+  #if DISTINCT_AXES > LOGICAL_AXES
203
+    FI void set(const T (&arr)[DISTINCT_AXES])          { x = arr[0]; y = arr[1]; }
206 204
   #endif
207 205
   FI void reset()                                       { x = y = 0; }
208 206
   FI T magnitude()                                const { return (T)sqrtf(x*x + y*y); }
@@ -312,8 +310,8 @@ struct XYZval {
312 310
   FI void set(const T (&arr)[XY])                      { x = arr[0]; y = arr[1]; }
313 311
   FI void set(const T (&arr)[XYZ])                     { x = arr[0]; y = arr[1]; z = arr[2]; }
314 312
   FI void set(const T (&arr)[XYZE])                    { x = arr[0]; y = arr[1]; z = arr[2]; }
315
-  #if XYZE_N > XYZE
316
-    FI void set(const T (&arr)[XYZE_N])                { x = arr[0]; y = arr[1]; z = arr[2]; }
313
+  #if DISTINCT_AXES > XYZE
314
+    FI void set(const T (&arr)[DISTINCT_AXES])         { x = arr[0]; y = arr[1]; z = arr[2]; }
317 315
   #endif
318 316
   FI void reset()                                      { x = y = z = 0; }
319 317
   FI T magnitude()                               const { return (T)sqrtf(x*x + y*y + z*z); }
@@ -427,8 +425,8 @@ struct XYZEval {
427 425
   FI void set(const T (&arr)[XY])                             { x = arr[0]; y = arr[1]; }
428 426
   FI void set(const T (&arr)[XYZ])                            { x = arr[0]; y = arr[1]; z = arr[2]; }
429 427
   FI void set(const T (&arr)[XYZE])                           { x = arr[0]; y = arr[1]; z = arr[2]; e = arr[3]; }
430
-  #if XYZE_N > XYZE
431
-    FI void set(const T (&arr)[XYZE_N])                       { x = arr[0]; y = arr[1]; z = arr[2]; e = arr[3]; }
428
+  #if DISTINCT_AXES > XYZE
429
+    FI void set(const T (&arr)[DISTINCT_AXES])                { x = arr[0]; y = arr[1]; z = arr[2]; e = arr[3]; }
432 430
   #endif
433 431
   FI XYZEval<T>          copy()                         const { return *this; }
434 432
   FI XYZEval<T>           ABS()                         const { return { T(_ABS(x)), T(_ABS(y)), T(_ABS(z)), T(_ABS(e)) }; }
@@ -518,4 +516,4 @@ struct XYZEval {
518 516
 #undef FI
519 517
 
520 518
 const xyze_char_t axis_codes { 'X', 'Y', 'Z', 'E' };
521
-#define XYZ_CHAR(A) ((char)('X' + A))
519
+#define AXIS_CHAR(A) ((char)('X' + A))

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

@@ -123,9 +123,9 @@ void safe_delay(millis_t ms) {
123 123
         #endif
124 124
         #if ABL_PLANAR
125 125
           SERIAL_ECHOPGM("ABL Adjustment X");
126
-          LOOP_XYZ(a) {
126
+          LOOP_LINEAR_AXES(a) {
127 127
             const float v = planner.get_axis_position_mm(AxisEnum(a)) - current_position[a];
128
-            SERIAL_CHAR(' ', XYZ_CHAR(a));
128
+            SERIAL_CHAR(' ', AXIS_CHAR(a));
129 129
             if (v > 0) SERIAL_CHAR('+');
130 130
             SERIAL_DECIMAL(v);
131 131
           }

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

@@ -104,7 +104,7 @@ void Backlash::add_correction_steps(const int32_t &da, const int32_t &db, const
104 104
 
105 105
   const float f_corr = float(correction) / 255.0f;
106 106
 
107
-  LOOP_XYZ(axis) {
107
+  LOOP_LINEAR_AXES(axis) {
108 108
     if (distance_mm[axis]) {
109 109
       const bool reversing = TEST(dm,axis);
110 110
 

+ 2
- 2
Marlin/src/feature/dac/dac_mcp4728.cpp View File

@@ -73,7 +73,7 @@ uint8_t MCP4728::analogWrite(const uint8_t channel, const uint16_t value) {
73 73
 uint8_t MCP4728::eepromWrite() {
74 74
   Wire.beginTransmission(I2C_ADDRESS(DAC_DEV_ADDRESS));
75 75
   Wire.write(SEQWRITE);
76
-  LOOP_XYZE(i) {
76
+  LOOP_LOGICAL_AXES(i) {
77 77
     Wire.write(DAC_STEPPER_VREF << 7 | DAC_STEPPER_GAIN << 4 | highByte(dac_values[i]));
78 78
     Wire.write(lowByte(dac_values[i]));
79 79
   }
@@ -135,7 +135,7 @@ void MCP4728::setDrvPct(xyze_uint_t &pct) {
135 135
  */
136 136
 uint8_t MCP4728::fastWrite() {
137 137
   Wire.beginTransmission(I2C_ADDRESS(DAC_DEV_ADDRESS));
138
-  LOOP_XYZE(i) {
138
+  LOOP_LOGICAL_AXES(i) {
139 139
     Wire.write(highByte(dac_values[i]));
140 140
     Wire.write(lowByte(dac_values[i]));
141 141
   }

+ 1
- 1
Marlin/src/feature/dac/stepper_dac.cpp View File

@@ -77,7 +77,7 @@ static float dac_amps(int8_t n) { return mcp4728.getValue(dac_order[n]) * 0.125
77 77
 
78 78
 uint8_t StepperDAC::get_current_percent(const AxisEnum axis) { return mcp4728.getDrvPct(dac_order[axis]); }
79 79
 void StepperDAC::set_current_percents(xyze_uint8_t &pct) {
80
-  LOOP_XYZE(i) dac_channel_pct[i] = pct[dac_order[i]];
80
+  LOOP_LOGICAL_AXES(i) dac_channel_pct[i] = pct[dac_order[i]];
81 81
   mcp4728.setDrvPct(dac_channel_pct);
82 82
 }
83 83
 

+ 11
- 11
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_XYZ(a) {
340
+  LOOP_LINEAR_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
   }
@@ -392,7 +392,7 @@ void I2CPositionEncoder::calibrate_steps_mm(const uint8_t iter) {
392 392
   travelDistance = endDistance - startDistance;
393 393
 
394 394
   xyze_pos_t startCoord, endCoord;
395
-  LOOP_XYZ(a) {
395
+  LOOP_LINEAR_AXES(a) {
396 396
     startCoord[a] = planner.get_axis_position_mm((AxisEnum)a);
397 397
     endCoord[a] = planner.get_axis_position_mm((AxisEnum)a);
398 398
   }
@@ -822,7 +822,7 @@ void I2CPositionEncodersMgr::M860() {
822 822
   const bool hasU = parser.seen_test('U'), hasO = parser.seen_test('O');
823 823
 
824 824
   if (I2CPE_idx == 0xFF) {
825
-    LOOP_XYZE(i) {
825
+    LOOP_LOGICAL_AXES(i) {
826 826
       if (!I2CPE_anyaxis || parser.seen_test(axis_codes[i])) {
827 827
         const uint8_t idx = idx_from_axis(AxisEnum(i));
828 828
         if ((int8_t)idx >= 0) report_position(idx, hasU, hasO);
@@ -849,7 +849,7 @@ void I2CPositionEncodersMgr::M861() {
849 849
   if (parse()) return;
850 850
 
851 851
   if (I2CPE_idx == 0xFF) {
852
-    LOOP_XYZE(i) {
852
+    LOOP_LOGICAL_AXES(i) {
853 853
       if (!I2CPE_anyaxis || parser.seen(axis_codes[i])) {
854 854
         const uint8_t idx = idx_from_axis(AxisEnum(i));
855 855
         if ((int8_t)idx >= 0) report_status(idx);
@@ -877,7 +877,7 @@ void I2CPositionEncodersMgr::M862() {
877 877
   if (parse()) return;
878 878
 
879 879
   if (I2CPE_idx == 0xFF) {
880
-    LOOP_XYZE(i) {
880
+    LOOP_LOGICAL_AXES(i) {
881 881
       if (!I2CPE_anyaxis || parser.seen(axis_codes[i])) {
882 882
         const uint8_t idx = idx_from_axis(AxisEnum(i));
883 883
         if ((int8_t)idx >= 0) test_axis(idx);
@@ -908,7 +908,7 @@ void I2CPositionEncodersMgr::M863() {
908 908
   const uint8_t iterations = constrain(parser.byteval('P', 1), 1, 10);
909 909
 
910 910
   if (I2CPE_idx == 0xFF) {
911
-    LOOP_XYZE(i) {
911
+    LOOP_LOGICAL_AXES(i) {
912 912
       if (!I2CPE_anyaxis || parser.seen(axis_codes[i])) {
913 913
         const uint8_t idx = idx_from_axis(AxisEnum(i));
914 914
         if ((int8_t)idx >= 0) calibrate_steps_mm(idx, iterations);
@@ -984,7 +984,7 @@ void I2CPositionEncodersMgr::M865() {
984 984
   if (parse()) return;
985 985
 
986 986
   if (!I2CPE_addr) {
987
-    LOOP_XYZE(i) {
987
+    LOOP_LOGICAL_AXES(i) {
988 988
       if (!I2CPE_anyaxis || parser.seen(axis_codes[i])) {
989 989
         const uint8_t idx = idx_from_axis(AxisEnum(i));
990 990
         if ((int8_t)idx >= 0) report_module_firmware(encoders[idx].get_address());
@@ -1015,7 +1015,7 @@ void I2CPositionEncodersMgr::M866() {
1015 1015
   const bool hasR = parser.seen_test('R');
1016 1016
 
1017 1017
   if (I2CPE_idx == 0xFF) {
1018
-    LOOP_XYZE(i) {
1018
+    LOOP_LOGICAL_AXES(i) {
1019 1019
       if (!I2CPE_anyaxis || parser.seen(axis_codes[i])) {
1020 1020
         const uint8_t idx = idx_from_axis(AxisEnum(i));
1021 1021
         if ((int8_t)idx >= 0) {
@@ -1053,7 +1053,7 @@ void I2CPositionEncodersMgr::M867() {
1053 1053
   const int8_t onoff = parser.seenval('S') ? parser.value_int() : -1;
1054 1054
 
1055 1055
   if (I2CPE_idx == 0xFF) {
1056
-    LOOP_XYZE(i) {
1056
+    LOOP_LOGICAL_AXES(i) {
1057 1057
       if (!I2CPE_anyaxis || parser.seen(axis_codes[i])) {
1058 1058
         const uint8_t idx = idx_from_axis(AxisEnum(i));
1059 1059
         if ((int8_t)idx >= 0) {
@@ -1089,7 +1089,7 @@ void I2CPositionEncodersMgr::M868() {
1089 1089
   const float newThreshold = parser.seenval('T') ? parser.value_float() : -9999;
1090 1090
 
1091 1091
   if (I2CPE_idx == 0xFF) {
1092
-    LOOP_XYZE(i) {
1092
+    LOOP_LOGICAL_AXES(i) {
1093 1093
       if (!I2CPE_anyaxis || parser.seen(axis_codes[i])) {
1094 1094
         const uint8_t idx = idx_from_axis(AxisEnum(i));
1095 1095
         if ((int8_t)idx >= 0) {
@@ -1123,7 +1123,7 @@ void I2CPositionEncodersMgr::M869() {
1123 1123
   if (parse()) return;
1124 1124
 
1125 1125
   if (I2CPE_idx == 0xFF) {
1126
-    LOOP_XYZE(i) {
1126
+    LOOP_LOGICAL_AXES(i) {
1127 1127
       if (!I2CPE_anyaxis || parser.seen(axis_codes[i])) {
1128 1128
         const uint8_t idx = idx_from_axis(AxisEnum(i));
1129 1129
         if ((int8_t)idx >= 0) report_error(idx);

+ 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_XYZ(i) if (norm_jog[i]) {
166
+    LOOP_LINEAR_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
     }

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

@@ -549,7 +549,7 @@ void PrintJobRecovery::resume() {
549 549
   TERN_(HAS_HOME_OFFSET, home_offset = info.home_offset);
550 550
   TERN_(HAS_POSITION_SHIFT, position_shift = info.position_shift);
551 551
   #if HAS_HOME_OFFSET || HAS_POSITION_SHIFT
552
-    LOOP_XYZ(i) update_workspace_offset((AxisEnum)i);
552
+    LOOP_LINEAR_AXES(i) update_workspace_offset((AxisEnum)i);
553 553
   #endif
554 554
 
555 555
   // Relative axis modes
@@ -581,7 +581,7 @@ void PrintJobRecovery::resume() {
581 581
     if (info.valid_head) {
582 582
       if (info.valid_head == info.valid_foot) {
583 583
         DEBUG_ECHOPGM("current_position: ");
584
-        LOOP_XYZE(i) {
584
+        LOOP_LOGICAL_AXES(i) {
585 585
           if (i) DEBUG_CHAR(',');
586 586
           DEBUG_DECIMAL(info.current_position[i]);
587 587
         }
@@ -599,7 +599,7 @@ void PrintJobRecovery::resume() {
599 599
 
600 600
         #if HAS_HOME_OFFSET
601 601
           DEBUG_ECHOPGM("home_offset: ");
602
-          LOOP_XYZ(i) {
602
+          LOOP_LINEAR_AXES(i) {
603 603
             if (i) DEBUG_CHAR(',');
604 604
             DEBUG_DECIMAL(info.home_offset[i]);
605 605
           }
@@ -608,7 +608,7 @@ void PrintJobRecovery::resume() {
608 608
 
609 609
         #if HAS_POSITION_SHIFT
610 610
           DEBUG_ECHOPGM("position_shift: ");
611
-          LOOP_XYZ(i) {
611
+          LOOP_LINEAR_AXES(i) {
612 612
             if (i) DEBUG_CHAR(',');
613 613
             DEBUG_DECIMAL(info.position_shift[i]);
614 614
           }

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

@@ -220,7 +220,7 @@ void GcodeSuite::G28() {
220 220
 
221 221
   #if ENABLED(MARLIN_DEV_MODE)
222 222
     if (parser.seen_test('S')) {
223
-      LOOP_XYZ(a) set_axis_is_at_home((AxisEnum)a);
223
+      LOOP_LINEAR_AXES(a) set_axis_is_at_home((AxisEnum)a);
224 224
       sync_plan_position();
225 225
       SERIAL_ECHOLNPGM("Simulated Homing");
226 226
       report_current_position();

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

@@ -347,7 +347,7 @@ static float auto_tune_a() {
347 347
   abc_float_t delta_e = { 0.0f }, delta_t = { 0.0f };
348 348
 
349 349
   delta_t.reset();
350
-  LOOP_XYZ(axis) {
350
+  LOOP_LINEAR_AXES(axis) {
351 351
     delta_t[axis] = diff;
352 352
     calc_kinematics_diff_probe_points(z_pt, delta_e, delta_r, delta_t);
353 353
     delta_t[axis] = 0;
@@ -525,7 +525,7 @@ void GcodeSuite::G33() {
525 525
 
526 526
         case 1:
527 527
           test_precision = 0.0f; // forced end
528
-          LOOP_XYZ(axis) e_delta[axis] = +Z4(CEN);
528
+          LOOP_LINEAR_AXES(axis) e_delta[axis] = +Z4(CEN);
529 529
           break;
530 530
 
531 531
         case 2:
@@ -573,14 +573,14 @@ void GcodeSuite::G33() {
573 573
       // Normalize angles to least-squares
574 574
       if (_angle_results) {
575 575
         float a_sum = 0.0f;
576
-        LOOP_XYZ(axis) a_sum += delta_tower_angle_trim[axis];
577
-        LOOP_XYZ(axis) delta_tower_angle_trim[axis] -= a_sum / 3.0f;
576
+        LOOP_LINEAR_AXES(axis) a_sum += delta_tower_angle_trim[axis];
577
+        LOOP_LINEAR_AXES(axis) delta_tower_angle_trim[axis] -= a_sum / 3.0f;
578 578
       }
579 579
 
580 580
       // adjust delta_height and endstops by the max amount
581 581
       const float z_temp = _MAX(delta_endstop_adj.a, delta_endstop_adj.b, delta_endstop_adj.c);
582 582
       delta_height -= z_temp;
583
-      LOOP_XYZ(axis) delta_endstop_adj[axis] -= z_temp;
583
+      LOOP_LINEAR_AXES(axis) delta_endstop_adj[axis] -= z_temp;
584 584
     }
585 585
     recalc_delta_settings();
586 586
     NOMORE(zero_std_dev_min, zero_std_dev);

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

@@ -55,8 +55,8 @@ void GcodeSuite::M425() {
55 55
     }
56 56
   };
57 57
 
58
-  LOOP_XYZ(a) {
59
-    if (axis_can_calibrate(a) && parser.seen(XYZ_CHAR(a))) {
58
+  LOOP_LINEAR_AXES(a) {
59
+    if (axis_can_calibrate(a) && parser.seen(AXIS_CHAR(a))) {
60 60
       planner.synchronize();
61 61
       backlash.distance_mm[a] = parser.has_value() ? parser.value_linear_units() : backlash.get_measurement(AxisEnum(a));
62 62
       noArgs = false;
@@ -83,8 +83,8 @@ void GcodeSuite::M425() {
83 83
     SERIAL_ECHOLNPGM("active:");
84 84
     SERIAL_ECHOLNPAIR("  Correction Amount/Fade-out:     F", backlash.get_correction(), " (F1.0 = full, F0.0 = none)");
85 85
     SERIAL_ECHOPGM("  Backlash Distance (mm):        ");
86
-    LOOP_XYZ(a) if (axis_can_calibrate(a)) {
87
-      SERIAL_CHAR(' ', XYZ_CHAR(a));
86
+    LOOP_LINEAR_AXES(a) if (axis_can_calibrate(a)) {
87
+      SERIAL_CHAR(' ', AXIS_CHAR(a));
88 88
       SERIAL_ECHO(backlash.distance_mm[a]);
89 89
       SERIAL_EOL();
90 90
     }
@@ -96,8 +96,8 @@ void GcodeSuite::M425() {
96 96
     #if ENABLED(MEASURE_BACKLASH_WHEN_PROBING)
97 97
       SERIAL_ECHOPGM("  Average measured backlash (mm):");
98 98
       if (backlash.has_any_measurement()) {
99
-        LOOP_XYZ(a) if (axis_can_calibrate(a) && backlash.has_measurement(AxisEnum(a))) {
100
-          SERIAL_CHAR(' ', XYZ_CHAR(a));
99
+        LOOP_LINEAR_AXES(a) if (axis_can_calibrate(a) && backlash.has_measurement(AxisEnum(a))) {
100
+          SERIAL_CHAR(' ', AXIS_CHAR(a));
101 101
           SERIAL_ECHO(backlash.get_measurement(AxisEnum(a)));
102 102
         }
103 103
       }

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

@@ -39,11 +39,11 @@
39 39
    */
40 40
   void GcodeSuite::M666() {
41 41
     DEBUG_SECTION(log_M666, "M666", DEBUGGING(LEVELING));
42
-    LOOP_XYZ(i) {
43
-      if (parser.seen(XYZ_CHAR(i))) {
42
+    LOOP_LINEAR_AXES(i) {
43
+      if (parser.seen(AXIS_CHAR(i))) {
44 44
         const float v = parser.value_linear_units();
45 45
         if (v * Z_HOME_DIR <= 0) delta_endstop_adj[i] = v;
46
-        if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("delta_endstop_adj[", AS_CHAR(XYZ_CHAR(i)), "] = ", delta_endstop_adj[i]);
46
+        if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("delta_endstop_adj[", AS_CHAR(AXIS_CHAR(i)), "] = ", delta_endstop_adj[i]);
47 47
       }
48 48
     }
49 49
   }

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

@@ -86,7 +86,7 @@ void GcodeSuite::M852() {
86 86
 
87 87
   // When skew is changed the current position changes
88 88
   if (setval) {
89
-    set_current_from_steppers_for_axis(ALL_AXES);
89
+    set_current_from_steppers_for_axis(ALL_AXES_MASK);
90 90
     sync_plan_position();
91 91
     report_current_position();
92 92
   }

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

@@ -86,7 +86,7 @@ void GcodeSuite::M201() {
86 86
     if (parser.seenval('G')) planner.xy_freq_min_speed_factor = constrain(parser.value_float(), 1, 100) / 100;
87 87
   #endif
88 88
 
89
-  LOOP_XYZE(i) {
89
+  LOOP_LOGICAL_AXES(i) {
90 90
     if (parser.seenval(axis_codes[i])) {
91 91
       const uint8_t a = (i == E_AXIS ? uint8_t(E_AXIS_N(target_extruder)) : i);
92 92
       planner.set_max_acceleration(a, parser.value_axis_units((AxisEnum)a));
@@ -104,7 +104,7 @@ void GcodeSuite::M203() {
104 104
   const int8_t target_extruder = get_target_extruder_from_command();
105 105
   if (target_extruder < 0) return;
106 106
 
107
-  LOOP_XYZE(i)
107
+  LOOP_LOGICAL_AXES(i)
108 108
     if (parser.seenval(axis_codes[i])) {
109 109
       const uint8_t a = (i == E_AXIS ? uint8_t(E_AXIS_N(target_extruder)) : i);
110 110
       planner.set_max_feedrate(a, parser.value_axis_units((AxisEnum)a));

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

@@ -67,7 +67,7 @@ void GcodeSuite::M92() {
67 67
   if (!parser.seen("XYZE" TERN_(MAGIC_NUMBERS_GCODE, "HL")))
68 68
     return report_M92(true, target_extruder);
69 69
 
70
-  LOOP_XYZE(i) {
70
+  LOOP_LOGICAL_AXES(i) {
71 71
     if (parser.seenval(axis_codes[i])) {
72 72
       if (i == E_AXIS) {
73 73
         const float value = parser.value_per_axis_units((AxisEnum)(E_AXIS_N(target_extruder)));

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

@@ -34,7 +34,7 @@
34 34
  */
35 35
 void GcodeSuite::M350() {
36 36
   if (parser.seen('S')) LOOP_LE_N(i, 4) stepper.microstep_mode(i, parser.value_byte());
37
-  LOOP_XYZE(i) if (parser.seen(axis_codes[i])) stepper.microstep_mode(i, parser.value_byte());
37
+  LOOP_LOGICAL_AXES(i) if (parser.seen(axis_codes[i])) stepper.microstep_mode(i, parser.value_byte());
38 38
   if (parser.seen('B')) stepper.microstep_mode(4, parser.value_byte());
39 39
   stepper.microstep_readings();
40 40
 }
@@ -46,15 +46,15 @@ void GcodeSuite::M350() {
46 46
 void GcodeSuite::M351() {
47 47
   if (parser.seenval('S')) switch (parser.value_byte()) {
48 48
     case 1:
49
-      LOOP_XYZE(i) if (parser.seenval(axis_codes[i])) stepper.microstep_ms(i, parser.value_byte(), -1, -1);
49
+      LOOP_LOGICAL_AXES(i) if (parser.seenval(axis_codes[i])) stepper.microstep_ms(i, parser.value_byte(), -1, -1);
50 50
       if (parser.seenval('B')) stepper.microstep_ms(4, parser.value_byte(), -1, -1);
51 51
       break;
52 52
     case 2:
53
-      LOOP_XYZE(i) if (parser.seenval(axis_codes[i])) stepper.microstep_ms(i, -1, parser.value_byte(), -1);
53
+      LOOP_LOGICAL_AXES(i) if (parser.seenval(axis_codes[i])) stepper.microstep_ms(i, -1, parser.value_byte(), -1);
54 54
       if (parser.seenval('B')) stepper.microstep_ms(4, -1, parser.value_byte(), -1);
55 55
       break;
56 56
     case 3:
57
-      LOOP_XYZE(i) if (parser.seenval(axis_codes[i])) stepper.microstep_ms(i, -1, -1, parser.value_byte());
57
+      LOOP_LOGICAL_AXES(i) if (parser.seenval(axis_codes[i])) stepper.microstep_ms(i, -1, -1, parser.value_byte());
58 58
       if (parser.seenval('B')) stepper.microstep_ms(4, -1, -1, parser.value_byte());
59 59
       break;
60 60
   }

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

@@ -141,7 +141,7 @@
141 141
 
142 142
         HOTEND_LOOP() {
143 143
           DEBUG_ECHOPAIR_P(SP_T_STR, e);
144
-          LOOP_XYZ(a) DEBUG_ECHOPAIR("  hotend_offset[", e, "].", AS_CHAR(XYZ_CHAR(a) | 0x20), "=", hotend_offset[e][a]);
144
+          LOOP_LINEAR_AXES(a) DEBUG_ECHOPAIR("  hotend_offset[", e, "].", AS_CHAR(AXIS_CHAR(a) | 0x20), "=", hotend_offset[e][a]);
145 145
           DEBUG_EOL();
146 146
         }
147 147
         DEBUG_EOL();

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

@@ -234,7 +234,7 @@ void GcodeSuite::M906() {
234 234
     const uint8_t index = parser.byteval('I');
235 235
   #endif
236 236
 
237
-  LOOP_XYZE(i) if (uint16_t value = parser.intval(axis_codes[i])) {
237
+  LOOP_LOGICAL_AXES(i) if (uint16_t value = parser.intval(axis_codes[i])) {
238 238
 
239 239
     report_current = false;
240 240
 

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

@@ -44,7 +44,7 @@
44 44
 void GcodeSuite::M907() {
45 45
   #if HAS_MOTOR_CURRENT_SPI
46 46
 
47
-    LOOP_XYZE(i) if (parser.seenval(axis_codes[i])) stepper.set_digipot_current(i, parser.value_int());
47
+    LOOP_LOGICAL_AXES(i) if (parser.seenval(axis_codes[i])) stepper.set_digipot_current(i, parser.value_int());
48 48
     if (parser.seenval('B')) stepper.set_digipot_current(4, parser.value_int());
49 49
     if (parser.seenval('S')) LOOP_LE_N(i, 4) stepper.set_digipot_current(i, parser.value_int());
50 50
 
@@ -64,7 +64,7 @@ void GcodeSuite::M907() {
64 64
 
65 65
   #if HAS_MOTOR_CURRENT_I2C
66 66
     // this one uses actual amps in floating point
67
-    LOOP_XYZE(i) if (parser.seenval(axis_codes[i])) digipot_i2c.set_current(i, parser.value_float());
67
+    LOOP_LOGICAL_AXES(i) if (parser.seenval(axis_codes[i])) digipot_i2c.set_current(i, parser.value_float());
68 68
     // Additional extruders use B,C,D for channels 4,5,6.
69 69
     // TODO: Change these parameters because 'E' is used. B<index>?
70 70
     for (uint8_t i = E_AXIS + 1; i < DIGIPOT_I2C_NUM_CHANNELS; i++)
@@ -76,7 +76,7 @@ void GcodeSuite::M907() {
76 76
       const float dac_percent = parser.value_float();
77 77
       LOOP_LE_N(i, 4) stepper_dac.set_current_percent(i, dac_percent);
78 78
     }
79
-    LOOP_XYZE(i) if (parser.seenval(axis_codes[i])) stepper_dac.set_current_percent(i, parser.value_float());
79
+    LOOP_LOGICAL_AXES(i) if (parser.seenval(axis_codes[i])) stepper_dac.set_current_percent(i, parser.value_float());
80 80
   #endif
81 81
 }
82 82
 

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

@@ -71,11 +71,11 @@ void GcodeSuite::G61(void) {
71 71
   else {
72 72
     if (parser.seen("XYZ")) {
73 73
       DEBUG_ECHOPAIR(STR_RESTORING_POS " S", slot);
74
-      LOOP_XYZ(i) {
75
-        destination[i] = parser.seen(XYZ_CHAR(i))
74
+      LOOP_LINEAR_AXES(i) {
75
+        destination[i] = parser.seen(AXIS_CHAR(i))
76 76
           ? stored_position[slot][i] + parser.value_axis_units((AxisEnum)i)
77 77
           : current_position[i];
78
-        DEBUG_CHAR(' ', XYZ_CHAR(i));
78
+        DEBUG_CHAR(' ', AXIS_CHAR(i));
79 79
         DEBUG_ECHO_F(destination[i]);
80 80
       }
81 81
       DEBUG_EOL();

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

@@ -32,12 +32,12 @@
32 32
  * M122: Debug TMC drivers
33 33
  */
34 34
 void GcodeSuite::M122() {
35
-  xyze_bool_t print_axis = ARRAY_N_1(XYZE, false);
35
+  xyze_bool_t print_axis = ARRAY_N_1(LOGICAL_AXES, false);
36 36
 
37 37
   bool print_all = true;
38
-  LOOP_XYZE(i) if (parser.seen(axis_codes[i])) { print_axis[i] = true; print_all = false; }
38
+  LOOP_LOGICAL_AXES(i) if (parser.seen(axis_codes[i])) { print_axis[i] = true; print_all = false; }
39 39
 
40
-  if (print_all) LOOP_XYZE(i) print_axis[i] = true;
40
+  if (print_all) LOOP_LOGICAL_AXES(i) print_axis[i] = true;
41 41
 
42 42
   if (parser.boolval('I')) restore_stepper_drivers();
43 43
 

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

@@ -50,7 +50,7 @@ static void set_stealth_status(const bool enable, const int8_t target_extruder)
50 50
     const uint8_t index = parser.byteval('I');
51 51
   #endif
52 52
 
53
-  LOOP_XYZE(i) if (parser.seen(axis_codes[i])) {
53
+  LOOP_LOGICAL_AXES(i) if (parser.seen(axis_codes[i])) {
54 54
     switch (i) {
55 55
       case X_AXIS:
56 56
         #if AXIS_HAS_STEALTHCHOP(X)

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

@@ -52,7 +52,7 @@ void GcodeSuite::M906() {
52 52
     const uint8_t index = parser.byteval('I');
53 53
   #endif
54 54
 
55
-  LOOP_XYZE(i) if (uint16_t value = parser.intval(axis_codes[i])) {
55
+  LOOP_LOGICAL_AXES(i) if (uint16_t value = parser.intval(axis_codes[i])) {
56 56
     report = false;
57 57
     switch (i) {
58 58
       case X_AXIS:

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

@@ -209,7 +209,7 @@
209 209
     #if AXIS_IS_TMC(X) || AXIS_IS_TMC(X2) || AXIS_IS_TMC(Y) || AXIS_IS_TMC(Y2) || AXIS_IS_TMC(Z) || AXIS_IS_TMC(Z2) || AXIS_IS_TMC(Z3) || AXIS_IS_TMC(Z4)
210 210
       const uint8_t index = parser.byteval('I');
211 211
     #endif
212
-    LOOP_XYZE(i) if (int32_t value = parser.longval(axis_codes[i])) {
212
+    LOOP_LOGICAL_AXES(i) if (int32_t value = parser.longval(axis_codes[i])) {
213 213
       report = false;
214 214
       switch (i) {
215 215
         case X_AXIS:
@@ -338,7 +338,7 @@
338 338
 
339 339
     bool report = true;
340 340
     const uint8_t index = parser.byteval('I');
341
-    LOOP_XYZ(i) if (parser.seen(XYZ_CHAR(i))) {
341
+    LOOP_LINEAR_AXES(i) if (parser.seen(AXIS_CHAR(i))) {
342 342
       const int16_t value = parser.value_int();
343 343
       report = false;
344 344
       switch (i) {

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

@@ -149,8 +149,8 @@ void GcodeSuite::get_destination_from_command() {
149 149
   #endif
150 150
 
151 151
   // Get new XYZ position, whether absolute or relative
152
-  LOOP_XYZ(i) {
153
-    if ( (seen[i] = parser.seenval(XYZ_CHAR(i))) ) {
152
+  LOOP_LINEAR_AXES(i) {
153
+    if ( (seen[i] = parser.seenval(AXIS_CHAR(i))) ) {
154 154
       const float v = parser.value_axis_units((AxisEnum)i);
155 155
       if (skip_move)
156 156
         destination[i] = current_position[i];

+ 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_XYZ(i) {
42
+  LOOP_LINEAR_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);

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

@@ -61,7 +61,7 @@ void GcodeSuite::G92() {
61 61
 
62 62
     #if ENABLED(CNC_COORDINATE_SYSTEMS) && !IS_SCARA
63 63
       case 1:                                                         // G92.1 - Zero the Workspace Offset
64
-        LOOP_XYZ(i) if (position_shift[i]) {
64
+        LOOP_LINEAR_AXES(i) if (position_shift[i]) {
65 65
           position_shift[i] = 0;
66 66
           update_workspace_offset((AxisEnum)i);
67 67
         }
@@ -70,7 +70,7 @@ void GcodeSuite::G92() {
70 70
 
71 71
     #if ENABLED(POWER_LOSS_RECOVERY)
72 72
       case 9:                                                         // G92.9 - Set Current Position directly (like Marlin 1.0)
73
-        LOOP_XYZE(i) {
73
+        LOOP_LOGICAL_AXES(i) {
74 74
           if (parser.seenval(axis_codes[i])) {
75 75
             if (i == E_AXIS) sync_E = true; else sync_XYZE = true;
76 76
             current_position[i] = parser.value_axis_units((AxisEnum)i);
@@ -80,7 +80,7 @@ void GcodeSuite::G92() {
80 80
     #endif
81 81
 
82 82
     case 0:
83
-      LOOP_XYZE(i) {
83
+      LOOP_LOGICAL_AXES(i) {
84 84
         if (parser.seenval(axis_codes[i])) {
85 85
           const float l = parser.value_axis_units((AxisEnum)i),       // Given axis coordinate value, converted to millimeters
86 86
                       v = i == E_AXIS ? l : LOGICAL_TO_NATIVE(l, i),  // Axis position in NATIVE space (applying the existing offset)

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

@@ -42,8 +42,8 @@ void M206_report() {
42 42
  * ***              In the 2.0 release, it will simply be disabled by default.
43 43
  */
44 44
 void GcodeSuite::M206() {
45
-  LOOP_XYZ(i)
46
-    if (parser.seen(XYZ_CHAR(i)))
45
+  LOOP_LINEAR_AXES(i)
46
+    if (parser.seen(AXIS_CHAR(i)))
47 47
       set_home_offset((AxisEnum)i, parser.value_linear_units());
48 48
 
49 49
   #if ENABLED(MORGAN_SCARA)
@@ -72,7 +72,7 @@ void GcodeSuite::M428() {
72 72
   if (homing_needed_error()) return;
73 73
 
74 74
   xyz_float_t diff;
75
-  LOOP_XYZ(i) {
75
+  LOOP_LINEAR_AXES(i) {
76 76
     diff[i] = base_home_pos((AxisEnum)i) - current_position[i];
77 77
     if (!WITHIN(diff[i], -20, 20) && home_dir((AxisEnum)i) > 0)
78 78
       diff[i] = -current_position[i];
@@ -84,7 +84,7 @@ void GcodeSuite::M428() {
84 84
     }
85 85
   }
86 86
 
87
-  LOOP_XYZ(i) set_home_offset((AxisEnum)i, diff[i]);
87
+  LOOP_LINEAR_AXES(i) set_home_offset((AxisEnum)i, diff[i]);
88 88
   report_current_position();
89 89
   LCD_MESSAGEPGM(MSG_HOME_OFFSETS_APPLIED);
90 90
   BUZZ(100, 659);

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

@@ -47,8 +47,8 @@
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_XYZ(a) {
51
-      SERIAL_CHAR(' ', XYZ_CHAR(a), ':');
50
+    LOOP_LINEAR_AXES(a) {
51
+      SERIAL_CHAR(' ', AXIS_CHAR(a), ':');
52 52
       SERIAL_ECHO(dtostrf(pos[a], 1, precision, str));
53 53
     }
54 54
     SERIAL_EOL();
@@ -153,7 +153,7 @@
153 153
     #endif // HAS_L64XX
154 154
 
155 155
     SERIAL_ECHOPGM("Stepper:");
156
-    LOOP_XYZE(i) {
156
+    LOOP_LOGICAL_AXES(i) {
157 157
       SERIAL_CHAR(' ', axis_codes[i], ':');
158 158
       SERIAL_ECHO(stepper.position((AxisEnum)i));
159 159
     }

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

@@ -69,8 +69,8 @@
69 69
  */
70 70
 void GcodeSuite::M290() {
71 71
   #if ENABLED(BABYSTEP_XY)
72
-    LOOP_XYZ(a)
73
-      if (parser.seenval(XYZ_CHAR(a)) || (a == Z_AXIS && parser.seenval('S'))) {
72
+    LOOP_LINEAR_AXES(a)
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);
76 76
         #if ENABLED(BABYSTEP_ZPROBE_OFFSET)

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

@@ -38,7 +38,7 @@ inline void G38_single_probe(const uint8_t move_value) {
38 38
   planner.synchronize();
39 39
   G38_move = 0;
40 40
   endstops.hit_on_purpose();
41
-  set_current_from_steppers_for_axis(ALL_AXES);
41
+  set_current_from_steppers_for_axis(ALL_AXES_MASK);
42 42
   sync_plan_position();
43 43
 }
44 44
 
@@ -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_XYZ(i) {
52
+    LOOP_LINEAR_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_XYZ(i)
122
+  LOOP_LINEAR_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

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

@@ -651,22 +651,38 @@
651 651
 #endif
652 652
 
653 653
 /**
654
- * DISTINCT_E_FACTORS affects how some E factors are accessed
654
+ * Number of Linear Axes (e.g., XYZ)
655
+ * All the logical axes except for the tool (E) axis
656
+ */
657
+#ifndef LINEAR_AXES
658
+  #define LINEAR_AXES XYZ
659
+#endif
660
+
661
+/**
662
+ * Number of Logical Axes (e.g., XYZE)
663
+ * All the logical axes that can be commanded directly by G-code.
664
+ * Delta maps stepper-specific values to ABC steppers.
665
+ */
666
+#if EXTRUDERS
667
+  #define LOGICAL_AXES INCREMENT(LINEAR_AXES)
668
+#else
669
+  #define LOGICAL_AXES LINEAR_AXES
670
+#endif
671
+
672
+/**
673
+ * DISTINCT_E_FACTORS affects whether Extruders use different settings
655 674
  */
656 675
 #if ENABLED(DISTINCT_E_FACTORS) && E_STEPPERS > 1
657 676
   #define DISTINCT_E E_STEPPERS
658
-  #define XYZE_N (XYZ + E_STEPPERS)
677
+  #define DISTINCT_AXES (LINEAR_AXES + E_STEPPERS)
659 678
   #define E_INDEX_N(E) (E)
660
-  #define E_AXIS_N(E) AxisEnum(E_AXIS + E)
661
-  #define UNUSED_E(E) NOOP
662 679
 #else
663 680
   #undef DISTINCT_E_FACTORS
664 681
   #define DISTINCT_E 1
665
-  #define XYZE_N XYZE
682
+  #define DISTINCT_AXES LOGICAL_AXES
666 683
   #define E_INDEX_N(E) 0
667
-  #define E_AXIS_N(E) E_AXIS
668
-  #define UNUSED_E(E) UNUSED(E)
669 684
 #endif
685
+#define E_AXIS_N(E) AxisEnum(E_AXIS + E_INDEX_N(E))
670 686
 
671 687
 /**
672 688
  * The BLTouch Probe emulates a servo probe

+ 12
- 12
Marlin/src/inc/SanityCheck.h View File

@@ -2819,22 +2819,22 @@ constexpr float sanity_arr_1[] = DEFAULT_AXIS_STEPS_PER_UNIT,
2819 2819
   #define _EXTRA_NOTE ""
2820 2820
 #endif
2821 2821
 
2822
-static_assert(COUNT(sanity_arr_1) >= XYZE,   "DEFAULT_AXIS_STEPS_PER_UNIT requires X, Y, Z and E elements.");
2823
-static_assert(COUNT(sanity_arr_1) <= XYZE_N, "DEFAULT_AXIS_STEPS_PER_UNIT has too many elements." _EXTRA_NOTE);
2822
+static_assert(COUNT(sanity_arr_1) >= LOGICAL_AXES,  "DEFAULT_AXIS_STEPS_PER_UNIT requires X, Y, Z and E elements.");
2823
+static_assert(COUNT(sanity_arr_1) <= DISTINCT_AXES, "DEFAULT_AXIS_STEPS_PER_UNIT has too many elements." _EXTRA_NOTE);
2824 2824
 static_assert(   _ARR_TEST(1,0) && _ARR_TEST(1,1) && _ARR_TEST(1,2)
2825 2825
               && _ARR_TEST(1,3) && _ARR_TEST(1,4) && _ARR_TEST(1,5)
2826 2826
               && _ARR_TEST(1,6) && _ARR_TEST(1,7) && _ARR_TEST(1,8),
2827 2827
               "DEFAULT_AXIS_STEPS_PER_UNIT values must be positive.");
2828 2828
 
2829
-static_assert(COUNT(sanity_arr_2) >= XYZE,   "DEFAULT_MAX_FEEDRATE requires X, Y, Z and E elements.");
2830
-static_assert(COUNT(sanity_arr_2) <= XYZE_N, "DEFAULT_MAX_FEEDRATE has too many elements." _EXTRA_NOTE);
2829
+static_assert(COUNT(sanity_arr_2) >= LOGICAL_AXES,  "DEFAULT_MAX_FEEDRATE requires X, Y, Z and E elements.");
2830
+static_assert(COUNT(sanity_arr_2) <= DISTINCT_AXES, "DEFAULT_MAX_FEEDRATE has too many elements." _EXTRA_NOTE);
2831 2831
 static_assert(   _ARR_TEST(2,0) && _ARR_TEST(2,1) && _ARR_TEST(2,2)
2832 2832
               && _ARR_TEST(2,3) && _ARR_TEST(2,4) && _ARR_TEST(2,5)
2833 2833
               && _ARR_TEST(2,6) && _ARR_TEST(2,7) && _ARR_TEST(2,8),
2834 2834
               "DEFAULT_MAX_FEEDRATE values must be positive.");
2835 2835
 
2836
-static_assert(COUNT(sanity_arr_3) >= XYZE,   "DEFAULT_MAX_ACCELERATION requires X, Y, Z and E elements.");
2837
-static_assert(COUNT(sanity_arr_3) <= XYZE_N, "DEFAULT_MAX_ACCELERATION has too many elements." _EXTRA_NOTE);
2836
+static_assert(COUNT(sanity_arr_3) >= LOGICAL_AXES,  "DEFAULT_MAX_ACCELERATION requires X, Y, Z and E elements.");
2837
+static_assert(COUNT(sanity_arr_3) <= DISTINCT_AXES, "DEFAULT_MAX_ACCELERATION has too many elements." _EXTRA_NOTE);
2838 2838
 static_assert(   _ARR_TEST(3,0) && _ARR_TEST(3,1) && _ARR_TEST(3,2)
2839 2839
               && _ARR_TEST(3,3) && _ARR_TEST(3,4) && _ARR_TEST(3,5)
2840 2840
               && _ARR_TEST(3,6) && _ARR_TEST(3,7) && _ARR_TEST(3,8),
@@ -2843,8 +2843,8 @@ static_assert(   _ARR_TEST(3,0) && _ARR_TEST(3,1) && _ARR_TEST(3,2)
2843 2843
 #if ENABLED(LIMITED_MAX_ACCEL_EDITING)
2844 2844
   #ifdef MAX_ACCEL_EDIT_VALUES
2845 2845
     constexpr float sanity_arr_4[] = MAX_ACCEL_EDIT_VALUES;
2846
-    static_assert(COUNT(sanity_arr_4) >= XYZE, "MAX_ACCEL_EDIT_VALUES requires X, Y, Z and E elements.");
2847
-    static_assert(COUNT(sanity_arr_4) <= XYZE, "MAX_ACCEL_EDIT_VALUES has too many elements. X, Y, Z and E elements only.");
2846
+    static_assert(COUNT(sanity_arr_4) >= LOGICAL_AXES, "MAX_ACCEL_EDIT_VALUES requires X, Y, Z and E elements.");
2847
+    static_assert(COUNT(sanity_arr_4) <= LOGICAL_AXES, "MAX_ACCEL_EDIT_VALUES has too many elements. X, Y, Z and E elements only.");
2848 2848
     static_assert(   _ARR_TEST(4,0) && _ARR_TEST(4,1) && _ARR_TEST(4,2)
2849 2849
                   && _ARR_TEST(4,3) && _ARR_TEST(4,4) && _ARR_TEST(4,5)
2850 2850
                   && _ARR_TEST(4,6) && _ARR_TEST(4,7) && _ARR_TEST(4,8),
@@ -2855,8 +2855,8 @@ static_assert(   _ARR_TEST(3,0) && _ARR_TEST(3,1) && _ARR_TEST(3,2)
2855 2855
 #if ENABLED(LIMITED_MAX_FR_EDITING)
2856 2856
   #ifdef MAX_FEEDRATE_EDIT_VALUES
2857 2857
     constexpr float sanity_arr_5[] = MAX_FEEDRATE_EDIT_VALUES;
2858
-    static_assert(COUNT(sanity_arr_5) >= XYZE, "MAX_FEEDRATE_EDIT_VALUES requires X, Y, Z and E elements.");
2859
-    static_assert(COUNT(sanity_arr_5) <= XYZE, "MAX_FEEDRATE_EDIT_VALUES has too many elements. X, Y, Z and E elements only.");
2858
+    static_assert(COUNT(sanity_arr_5) >= LOGICAL_AXES, "MAX_FEEDRATE_EDIT_VALUES requires X, Y, Z and E elements.");
2859
+    static_assert(COUNT(sanity_arr_5) <= LOGICAL_AXES, "MAX_FEEDRATE_EDIT_VALUES has too many elements. X, Y, Z and E elements only.");
2860 2860
     static_assert(   _ARR_TEST(5,0) && _ARR_TEST(5,1) && _ARR_TEST(5,2)
2861 2861
                   && _ARR_TEST(5,3) && _ARR_TEST(5,4) && _ARR_TEST(5,5)
2862 2862
                   && _ARR_TEST(5,6) && _ARR_TEST(5,7) && _ARR_TEST(5,8),
@@ -2867,8 +2867,8 @@ static_assert(   _ARR_TEST(3,0) && _ARR_TEST(3,1) && _ARR_TEST(3,2)
2867 2867
 #if ENABLED(LIMITED_JERK_EDITING)
2868 2868
   #ifdef MAX_JERK_EDIT_VALUES
2869 2869
     constexpr float sanity_arr_6[] = MAX_JERK_EDIT_VALUES;
2870
-    static_assert(COUNT(sanity_arr_6) >= XYZE, "MAX_JERK_EDIT_VALUES requires X, Y, Z and E elements.");
2871
-    static_assert(COUNT(sanity_arr_6) <= XYZE, "MAX_JERK_EDIT_VALUES has too many elements. X, Y, Z and E elements only.");
2870
+    static_assert(COUNT(sanity_arr_6) >= LOGICAL_AXES, "MAX_JERK_EDIT_VALUES requires X, Y, Z and E elements.");
2871
+    static_assert(COUNT(sanity_arr_6) <= LOGICAL_AXES, "MAX_JERK_EDIT_VALUES has too many elements. X, Y, Z and E elements only.");
2872 2872
     static_assert(   _ARR_TEST(6,0) && _ARR_TEST(6,1) && _ARR_TEST(6,2)
2873 2873
                   && _ARR_TEST(6,3) && _ARR_TEST(6,4) && _ARR_TEST(6,5)
2874 2874
                   && _ARR_TEST(6,6) && _ARR_TEST(6,7) && _ARR_TEST(6,8),

+ 6
- 6
Marlin/src/lcd/marlinui.cpp View File

@@ -684,7 +684,7 @@ void MarlinUI::quick_feedback(const bool clear_buttons/*=true*/) {
684 684
   #if ENABLED(MULTI_MANUAL)
685 685
     int8_t ManualMove::e_index = 0;
686 686
   #endif
687
-  AxisEnum ManualMove::axis = NO_AXIS;
687
+  AxisEnum ManualMove::axis = NO_AXIS_MASK;
688 688
 
689 689
   /**
690 690
    * If a manual move has been posted and its time has arrived, and if the planner
@@ -695,7 +695,7 @@ void MarlinUI::quick_feedback(const bool clear_buttons/*=true*/) {
695 695
    *
696 696
    * To post a manual move:
697 697
    *   - Update current_position to the new place you want to go.
698
-   *   - Set manual_move.axis to an axis like X_AXIS. Use ALL_AXES for diagonal moves.
698
+   *   - Set manual_move.axis to an axis like X_AXIS. Use ALL_AXES_MASK for diagonal moves.
699 699
    *   - Set manual_move.start_time to a point in the future (in ms) when the move should be done.
700 700
    *
701 701
    * For kinematic machines:
@@ -710,7 +710,7 @@ void MarlinUI::quick_feedback(const bool clear_buttons/*=true*/) {
710 710
     if (processing) return;   // Prevent re-entry from idle() calls
711 711
 
712 712
     // Add a manual move to the queue?
713
-    if (axis != NO_AXIS && ELAPSED(millis(), start_time) && !planner.is_full()) {
713
+    if (axis != NO_AXIS_MASK && ELAPSED(millis(), start_time) && !planner.is_full()) {
714 714
 
715 715
       const feedRate_t fr_mm_s = (axis <= E_AXIS) ? manual_feedrate_mm_s[axis] : XY_PROBE_FEEDRATE_MM_S;
716 716
 
@@ -722,7 +722,7 @@ void MarlinUI::quick_feedback(const bool clear_buttons/*=true*/) {
722 722
         #endif
723 723
 
724 724
         // Apply a linear offset to a single axis
725
-        if (axis == ALL_AXES)
725
+        if (axis == ALL_AXES_MASK)
726 726
           destination = all_axes_destination;
727 727
         else if (axis <= XYZE) {
728 728
           destination = current_position;
@@ -731,7 +731,7 @@ void MarlinUI::quick_feedback(const bool clear_buttons/*=true*/) {
731 731
 
732 732
         // Reset for the next move
733 733
         offset = 0;
734
-        axis = NO_AXIS;
734
+        axis = NO_AXIS_MASK;
735 735
 
736 736
         // DELTA and SCARA machines use segmented moves, which could fill the planner during the call to
737 737
         // move_to_destination. This will cause idle() to be called, which can then call this function while the
@@ -748,7 +748,7 @@ void MarlinUI::quick_feedback(const bool clear_buttons/*=true*/) {
748 748
 
749 749
         //SERIAL_ECHOLNPAIR("Add planner.move with Axis ", AS_CHAR(axis_codes[axis]), " at FR ", fr_mm_s);
750 750
 
751
-        axis = NO_AXIS;
751
+        axis = NO_AXIS_MASK;
752 752
 
753 753
       #endif
754 754
     }

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

@@ -64,7 +64,7 @@ void menu_backlash();
64 64
 
65 65
   void menu_dac() {
66 66
     static xyze_uint8_t driverPercent;
67
-    LOOP_XYZE(i) driverPercent[i] = stepper_dac.get_current_percent((AxisEnum)i);
67
+    LOOP_LOGICAL_AXES(i) driverPercent[i] = stepper_dac.get_current_percent((AxisEnum)i);
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); })

+ 1
- 1
Marlin/src/lcd/menu/menu_bed_leveling.cpp View File

@@ -206,7 +206,7 @@
206 206
 #if ENABLED(MESH_EDIT_MENU)
207 207
 
208 208
   inline void refresh_planner() {
209
-    set_current_from_steppers_for_axis(ALL_AXES);
209
+    set_current_from_steppers_for_axis(ALL_AXES_MASK);
210 210
     sync_plan_position();
211 211
   }
212 212
 

+ 1
- 1
Marlin/src/lcd/menu/menu_ubl.cpp View File

@@ -430,7 +430,7 @@ void ubl_map_move_to_xy() {
430 430
 
431 431
   // Use the built-in manual move handler to move to the mesh point.
432 432
   ui.manual_move.set_destination(xy);
433
-  ui.manual_move.soon(ALL_AXES);
433
+  ui.manual_move.soon(ALL_AXES_MASK);
434 434
 }
435 435
 
436 436
 inline int32_t grid_index(const uint8_t x, const uint8_t y) {

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

@@ -395,7 +395,7 @@ uint8_t L64XX_Marlin::get_user_input(uint8_t &driver_count, L64XX_axis_t axis_in
395 395
   }
396 396
 
397 397
   uint8_t found_displacement = false;
398
-  LOOP_XYZE(i) if (uint16_t _displacement = parser.intval(axis_codes[i])) {
398
+  LOOP_LOGICAL_AXES(i) if (uint16_t _displacement = parser.intval(axis_codes[i])) {
399 399
     found_displacement = true;
400 400
     displacement = _displacement;
401 401
     uint8_t axis_offset = parser.byteval('J');

+ 5
- 5
Marlin/src/module/motion.cpp View File

@@ -124,7 +124,7 @@ xyze_pos_t destination; // {0}
124 124
       "Offsets for the first hotend must be 0.0."
125 125
     );
126 126
     // Transpose from [XYZ][HOTENDS] to [HOTENDS][XYZ]
127
-    HOTEND_LOOP() LOOP_XYZ(a) hotend_offset[e][a] = tmp[a][e];
127
+    HOTEND_LOOP() LOOP_LINEAR_AXES(a) hotend_offset[e][a] = tmp[a][e];
128 128
     #if ENABLED(DUAL_X_CARRIAGE)
129 129
       hotend_offset[1].x = _MAX(X2_HOME_POS, X2_MAX_POS);
130 130
     #endif
@@ -282,7 +282,7 @@ void report_current_position_projected() {
282 282
 void quickstop_stepper() {
283 283
   planner.quick_stop();
284 284
   planner.synchronize();
285
-  set_current_from_steppers_for_axis(ALL_AXES);
285
+  set_current_from_steppers_for_axis(ALL_AXES_MASK);
286 286
   sync_plan_position();
287 287
 }
288 288
 
@@ -360,7 +360,7 @@ void set_current_from_steppers_for_axis(const AxisEnum axis) {
360 360
     planner.unapply_modifiers(pos, true);
361 361
   #endif
362 362
 
363
-  if (axis == ALL_AXES)
363
+  if (axis == ALL_AXES_MASK)
364 364
     current_position = pos;
365 365
   else
366 366
     current_position[axis] = pos[axis];
@@ -681,7 +681,7 @@ void restore_feedrate_and_scaling() {
681 681
     #endif
682 682
 
683 683
     if (DEBUGGING(LEVELING))
684
-      SERIAL_ECHOLNPAIR("Axis ", AS_CHAR(XYZ_CHAR(axis)), " min:", soft_endstop.min[axis], " max:", soft_endstop.max[axis]);
684
+      SERIAL_ECHOLNPAIR("Axis ", AS_CHAR(AXIS_CHAR(axis)), " min:", soft_endstop.min[axis], " max:", soft_endstop.max[axis]);
685 685
   }
686 686
 
687 687
   /**
@@ -1951,7 +1951,7 @@ void set_axis_is_at_home(const AxisEnum axis) {
1951 1951
 #if HAS_WORKSPACE_OFFSET
1952 1952
   void update_workspace_offset(const AxisEnum axis) {
1953 1953
     workspace_offset[axis] = home_offset[axis] + position_shift[axis];
1954
-    if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("Axis ", AS_CHAR(XYZ_CHAR(axis)), " home_offset = ", home_offset[axis], " position_shift = ", position_shift[axis]);
1954
+    if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("Axis ", AS_CHAR(AXIS_CHAR(axis)), " home_offset = ", home_offset[axis], " position_shift = ", position_shift[axis]);
1955 1955
   }
1956 1956
 #endif
1957 1957
 

+ 7
- 7
Marlin/src/module/planner.cpp View File

@@ -136,9 +136,9 @@ planner_settings_t Planner::settings;           // Initialized by settings.load(
136 136
   laser_state_t Planner::laser_inline;          // Current state for blocks
137 137
 #endif
138 138
 
139
-uint32_t Planner::max_acceleration_steps_per_s2[XYZE_N]; // (steps/s^2) Derived from mm_per_s2
139
+uint32_t Planner::max_acceleration_steps_per_s2[DISTINCT_AXES]; // (steps/s^2) Derived from mm_per_s2
140 140
 
141
-float Planner::steps_to_mm[XYZE_N];             // (mm) Millimeters per step
141
+float Planner::steps_to_mm[DISTINCT_AXES];      // (mm) Millimeters per step
142 142
 
143 143
 #if HAS_JUNCTION_DEVIATION
144 144
   float Planner::junction_deviation_mm;         // (mm) M205 J
@@ -2201,7 +2201,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move,
2201 2201
   float speed_factor = 1.0f; // factor <1 decreases speed
2202 2202
 
2203 2203
   // Linear axes first with less logic
2204
-  LOOP_XYZ(i) {
2204
+  LOOP_LINEAR_AXES(i) {
2205 2205
     current_speed[i] = steps_dist_mm[i] * inverse_secs;
2206 2206
     const feedRate_t cs = ABS(current_speed[i]),
2207 2207
                  max_fr = settings.max_feedrate_mm_s[i];
@@ -2593,7 +2593,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move,
2593 2593
     const float extra_xyjerk = (de <= 0) ? TRAVEL_EXTRA_XYJERK : 0;
2594 2594
 
2595 2595
     uint8_t limited = 0;
2596
-    TERN(HAS_LINEAR_E_JERK, LOOP_XYZ, LOOP_XYZE)(i) {
2596
+    TERN(HAS_LINEAR_E_JERK, LOOP_LINEAR_AXES, LOOP_LOGICAL_AXES)(i) {
2597 2597
       const float jerk = ABS(current_speed[i]),   // cs : Starting from zero, change in speed for this axis
2598 2598
                   maxj = (max_jerk[i] + (i == X_AXIS || i == Y_AXIS ? extra_xyjerk : 0.0f)); // mj : The max jerk setting for this axis
2599 2599
       if (jerk > maxj) {                          // cs > mj : New current speed too fast?
@@ -2631,7 +2631,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move,
2631 2631
         vmax_junction = previous_nominal_speed;
2632 2632
 
2633 2633
       // Now limit the jerk in all axes.
2634
-      TERN(HAS_LINEAR_E_JERK, LOOP_XYZ, LOOP_XYZE)(axis) {
2634
+      TERN(HAS_LINEAR_E_JERK, LOOP_LINEAR_AXES, LOOP_LOGICAL_AXES)(axis) {
2635 2635
         // Limit an axis. We have to differentiate: coasting, reversal of an axis, full stop.
2636 2636
         float v_exit = previous_speed[axis] * smaller_speed_factor,
2637 2637
               v_entry = current_speed[axis];
@@ -3033,7 +3033,7 @@ void Planner::reset_acceleration_rates() {
3033 3033
     #define AXIS_CONDITION true
3034 3034
   #endif
3035 3035
   uint32_t highest_rate = 1;
3036
-  LOOP_XYZE_N(i) {
3036
+  LOOP_DISTINCT_AXES(i) {
3037 3037
     max_acceleration_steps_per_s2[i] = settings.max_acceleration_mm_per_s2[i] * settings.axis_steps_per_mm[i];
3038 3038
     if (AXIS_CONDITION) NOLESS(highest_rate, max_acceleration_steps_per_s2[i]);
3039 3039
   }
@@ -3046,7 +3046,7 @@ void Planner::reset_acceleration_rates() {
3046 3046
  * Must be called whenever settings.axis_steps_per_mm changes!
3047 3047
  */
3048 3048
 void Planner::refresh_positioning() {
3049
-  LOOP_XYZE_N(i) steps_to_mm[i] = 1.0f / settings.axis_steps_per_mm[i];
3049
+  LOOP_DISTINCT_AXES(i) steps_to_mm[i] = 1.0f / settings.axis_steps_per_mm[i];
3050 3050
   set_position_mm(current_position);
3051 3051
   reset_acceleration_rates();
3052 3052
 }

+ 9
- 9
Marlin/src/module/planner.h View File

@@ -268,10 +268,10 @@ typedef struct block_t {
268 268
 #endif
269 269
 
270 270
 typedef struct {
271
-   uint32_t max_acceleration_mm_per_s2[XYZE_N], // (mm/s^2) M201 XYZE
271
+   uint32_t max_acceleration_mm_per_s2[DISTINCT_AXES], // (mm/s^2) M201 XYZE
272 272
             min_segment_time_us;                // (µs) M205 B
273
-      float axis_steps_per_mm[XYZE_N];          // (steps) M92 XYZE - Steps per millimeter
274
- feedRate_t max_feedrate_mm_s[XYZE_N];          // (mm/s) M203 XYZE - Max speeds
273
+      float axis_steps_per_mm[DISTINCT_AXES];   // (steps) M92 XYZE - Steps per millimeter
274
+ feedRate_t max_feedrate_mm_s[DISTINCT_AXES];   // (mm/s) M203 XYZE - Max speeds
275 275
       float acceleration,                       // (mm/s^2) M204 S - Normal acceleration. DEFAULT ACCELERATION for all printing moves.
276 276
             retract_acceleration,               // (mm/s^2) M204 R - Retract acceleration. Filament pull-back and push-forward while standing still in the other axes
277 277
             travel_acceleration;                // (mm/s^2) M204 T - Travel acceleration. DEFAULT ACCELERATION for all NON printing moves.
@@ -360,13 +360,13 @@ class Planner {
360 360
       static laser_state_t laser_inline;
361 361
     #endif
362 362
 
363
-    static uint32_t max_acceleration_steps_per_s2[XYZE_N]; // (steps/s^2) Derived from mm_per_s2
364
-    static float steps_to_mm[XYZE_N];           // Millimeters per step
363
+    static uint32_t max_acceleration_steps_per_s2[DISTINCT_AXES]; // (steps/s^2) Derived from mm_per_s2
364
+    static float steps_to_mm[DISTINCT_AXES];          // Millimeters per step
365 365
 
366 366
     #if HAS_JUNCTION_DEVIATION
367
-      static float junction_deviation_mm;       // (mm) M205 J
367
+      static float junction_deviation_mm;             // (mm) M205 J
368 368
       #if HAS_LINEAR_E_JERK
369
-        static float max_e_jerk[DISTINCT_E];    // Calculated from junction_deviation_mm
369
+        static float max_e_jerk[DISTINCT_E];          // Calculated from junction_deviation_mm
370 370
       #endif
371 371
     #endif
372 372
 
@@ -1014,13 +1014,13 @@ class Planner {
1014 1014
 
1015 1015
       FORCE_INLINE static void normalize_junction_vector(xyze_float_t &vector) {
1016 1016
         float magnitude_sq = 0;
1017
-        LOOP_XYZE(idx) if (vector[idx]) magnitude_sq += sq(vector[idx]);
1017
+        LOOP_LOGICAL_AXES(idx) if (vector[idx]) magnitude_sq += sq(vector[idx]);
1018 1018
         vector *= RSQRT(magnitude_sq);
1019 1019
       }
1020 1020
 
1021 1021
       FORCE_INLINE static float limit_value_by_axis_maximum(const_float_t max_value, xyze_float_t &unit_vec) {
1022 1022
         float limit_value = max_value;
1023
-        LOOP_XYZE(idx) {
1023
+        LOOP_LOGICAL_AXES(idx) {
1024 1024
           if (unit_vec[idx]) {
1025 1025
             if (limit_value * ABS(unit_vec[idx]) > settings.max_acceleration_mm_per_s2[idx])
1026 1026
               limit_value = ABS(settings.max_acceleration_mm_per_s2[idx] / unit_vec[idx]);

+ 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_XYZ(i) set_axis_is_at_home((AxisEnum)i);
257
+    LOOP_LINEAR_AXES(i) set_axis_is_at_home((AxisEnum)i);
258 258
 
259 259
     sync_plan_position();
260 260
   }

+ 13
- 14
Marlin/src/module/settings.cpp View File

@@ -194,7 +194,7 @@ typedef struct SettingsDataStruct {
194 194
   //
195 195
   // DISTINCT_E_FACTORS
196 196
   //
197
-  uint8_t   esteppers;                                  // XYZE_N - XYZ
197
+  uint8_t   esteppers;                                  // DISTINCT_AXES - LINEAR_AXES
198 198
 
199 199
   planner_settings_t planner_settings;
200 200
 
@@ -385,7 +385,7 @@ typedef struct SettingsDataStruct {
385 385
   // HAS_MOTOR_CURRENT_PWM
386 386
   //
387 387
   #ifndef MOTOR_CURRENT_COUNT
388
-    #define MOTOR_CURRENT_COUNT 3
388
+    #define MOTOR_CURRENT_COUNT LINEAR_AXES
389 389
   #endif
390 390
   uint32_t motor_current_setting[MOTOR_CURRENT_COUNT];  // M907 X Z E
391 391
 
@@ -516,7 +516,7 @@ void MarlinSettings::postprocess() {
516 516
   #endif
517 517
 
518 518
   // Software endstops depend on home_offset
519
-  LOOP_XYZ(i) {
519
+  LOOP_LINEAR_AXES(i) {
520 520
     update_workspace_offset((AxisEnum)i);
521 521
     update_software_endstops((AxisEnum)i);
522 522
   }
@@ -637,9 +637,8 @@ void MarlinSettings::postprocess() {
637 637
 
638 638
     working_crc = 0; // clear before first "real data"
639 639
 
640
+    const uint8_t esteppers = COUNT(planner.settings.axis_steps_per_mm) - LINEAR_AXES;
640 641
     _FIELD_TEST(esteppers);
641
-
642
-    const uint8_t esteppers = COUNT(planner.settings.axis_steps_per_mm) - XYZ;
643 642
     EEPROM_WRITE(esteppers);
644 643
 
645 644
     //
@@ -1513,16 +1512,16 @@ void MarlinSettings::postprocess() {
1513 1512
       {
1514 1513
         // Get only the number of E stepper parameters previously stored
1515 1514
         // Any steppers added later are set to their defaults
1516
-        uint32_t tmp1[XYZ + esteppers];
1517
-        float tmp2[XYZ + esteppers];
1518
-        feedRate_t tmp3[XYZ + esteppers];
1515
+        uint32_t tmp1[LINEAR_AXES + esteppers];
1516
+        float tmp2[LINEAR_AXES + esteppers];
1517
+        feedRate_t tmp3[LINEAR_AXES + esteppers];
1519 1518
         EEPROM_READ((uint8_t *)tmp1, sizeof(tmp1)); // max_acceleration_mm_per_s2
1520 1519
         EEPROM_READ(planner.settings.min_segment_time_us);
1521 1520
         EEPROM_READ((uint8_t *)tmp2, sizeof(tmp2)); // axis_steps_per_mm
1522 1521
         EEPROM_READ((uint8_t *)tmp3, sizeof(tmp3)); // max_feedrate_mm_s
1523 1522
 
1524
-        if (!validating) LOOP_XYZE_N(i) {
1525
-          const bool in = (i < esteppers + XYZ);
1523
+        if (!validating) LOOP_DISTINCT_AXES(i) {
1524
+          const bool in = (i < esteppers + LINEAR_AXES);
1526 1525
           planner.settings.max_acceleration_mm_per_s2[i] = in ? tmp1[i] : pgm_read_dword(&_DMA[ALIM(i, _DMA)]);
1527 1526
           planner.settings.axis_steps_per_mm[i]          = in ? tmp2[i] : pgm_read_float(&_DASU[ALIM(i, _DASU)]);
1528 1527
           planner.settings.max_feedrate_mm_s[i]          = in ? tmp3[i] : pgm_read_float(&_DMF[ALIM(i, _DMF)]);
@@ -1540,7 +1539,7 @@ void MarlinSettings::postprocess() {
1540 1539
             EEPROM_READ(dummyf);
1541 1540
           #endif
1542 1541
         #else
1543
-          for (uint8_t q = XYZE; q--;) EEPROM_READ(dummyf);
1542
+          for (uint8_t q = LOGICAL_AXES; q--;) EEPROM_READ(dummyf);
1544 1543
         #endif
1545 1544
 
1546 1545
         EEPROM_READ(TERN(CLASSIC_JERK, dummyf, planner.junction_deviation_mm));
@@ -2582,7 +2581,7 @@ void MarlinSettings::postprocess() {
2582 2581
  * M502 - Reset Configuration
2583 2582
  */
2584 2583
 void MarlinSettings::reset() {
2585
-  LOOP_XYZE_N(i) {
2584
+  LOOP_DISTINCT_AXES(i) {
2586 2585
     planner.settings.max_acceleration_mm_per_s2[i] = pgm_read_dword(&_DMA[ALIM(i, _DMA)]);
2587 2586
     planner.settings.axis_steps_per_mm[i] = pgm_read_float(&_DASU[ALIM(i, _DASU)]);
2588 2587
     planner.settings.max_feedrate_mm_s[i] = pgm_read_float(&_DMF[ALIM(i, _DMF)]);
@@ -2706,7 +2705,7 @@ void MarlinSettings::reset() {
2706 2705
     constexpr float dpo[] = NOZZLE_TO_PROBE_OFFSET;
2707 2706
     static_assert(COUNT(dpo) == 3, "NOZZLE_TO_PROBE_OFFSET must contain offsets for X, Y, and Z.");
2708 2707
     #if HAS_PROBE_XY_OFFSET
2709
-      LOOP_XYZ(a) probe.offset[a] = dpo[a];
2708
+      LOOP_LINEAR_AXES(a) probe.offset[a] = dpo[a];
2710 2709
     #else
2711 2710
       probe.offset.set(0, 0, dpo[Z_AXIS]);
2712 2711
     #endif
@@ -3856,7 +3855,7 @@ void MarlinSettings::reset() {
3856 3855
         );
3857 3856
       #elif HAS_MOTOR_CURRENT_SPI
3858 3857
         SERIAL_ECHOPGM("  M907");                              // SPI-based has 5 values:
3859
-        LOOP_XYZE(q) {                                         // X Y Z E (map to X Y Z E0 by default)
3858
+        LOOP_LOGICAL_AXES(q) {                                 // X Y Z E (map to X Y Z E0 by default)
3860 3859
           SERIAL_CHAR(' ', axis_codes[q]);
3861 3860
           SERIAL_ECHO(stepper.motor_current_setting[q]);
3862 3861
         }

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

@@ -250,7 +250,7 @@ class Stepper {
250 250
         #ifndef PWM_MOTOR_CURRENT
251 251
           #define PWM_MOTOR_CURRENT DEFAULT_PWM_MOTOR_CURRENT
252 252
         #endif
253
-        #define MOTOR_CURRENT_COUNT XYZ
253
+        #define MOTOR_CURRENT_COUNT LINEAR_AXES
254 254
       #elif HAS_MOTOR_CURRENT_SPI
255 255
         static constexpr uint32_t digipot_count[] = DIGIPOT_MOTOR_CURRENT;
256 256
         #define MOTOR_CURRENT_COUNT COUNT(Stepper::digipot_count)

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

@@ -1181,7 +1181,7 @@ void tool_change(const uint8_t new_tool, bool no_move/*=false*/) {
1181 1181
       sync_plan_position();
1182 1182
 
1183 1183
       #if ENABLED(DELTA)
1184
-        //LOOP_XYZ(i) update_software_endstops(i); // or modify the constrain function
1184
+        //LOOP_LINEAR_AXES(i) update_software_endstops(i); // or modify the constrain function
1185 1185
         const bool safe_to_move = current_position.z < delta_clip_start_height - 1;
1186 1186
       #else
1187 1187
         constexpr bool safe_to_move = true;

Loading…
Cancel
Save