Browse Source

♻️ Refactor axis counts and loops

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

38
Marlin/src/core/types.h

@ -47,25 +47,23 @@ struct IF<true, L, R> { typedef L type; };
// - X_HEAD, Y_HEAD, and Z_HEAD should be used for Steppers on Core kinematics
//
enum AxisEnum : uint8_t {
X_AXIS = 0, A_AXIS = 0,
Y_AXIS = 1, B_AXIS = 1,
Z_AXIS = 2, C_AXIS = 2,
E_AXIS = 3,
X_HEAD = 4, Y_HEAD = 5, Z_HEAD = 6,
E0_AXIS = 3,
X_AXIS = 0, A_AXIS = X_AXIS,
Y_AXIS = 1, B_AXIS = Y_AXIS,
Z_AXIS = 2, C_AXIS = Z_AXIS,
E_AXIS,
X_HEAD, Y_HEAD, Z_HEAD,
E0_AXIS = E_AXIS,
E1_AXIS, E2_AXIS, E3_AXIS, E4_AXIS, E5_AXIS, E6_AXIS, E7_AXIS,
ALL_AXES = 0xFE, NO_AXIS = 0xFF
ALL_AXES_MASK = 0xFE, NO_AXIS_MASK = 0xFF
};
//
// Loop over XYZE axes
// Loop over axes
//
#define LOOP_XYZ(VAR) LOOP_S_LE_N(VAR, X_AXIS, Z_AXIS)
#define LOOP_XYZE(VAR) LOOP_S_LE_N(VAR, X_AXIS, E_AXIS)
#define LOOP_XYZE_N(VAR) LOOP_S_L_N(VAR, X_AXIS, XYZE_N)
#define LOOP_ABC(VAR) LOOP_S_LE_N(VAR, A_AXIS, C_AXIS)
#define LOOP_ABCE(VAR) LOOP_S_LE_N(VAR, A_AXIS, E_AXIS)
#define LOOP_ABCE_N(VAR) LOOP_S_L_N(VAR, A_AXIS, XYZE_N)
#define LOOP_LINEAR_AXES(VAR) LOOP_S_L_N(VAR, X_AXIS, LINEAR_AXES)
#define LOOP_LOGICAL_AXES(VAR) LOOP_S_L_N(VAR, X_AXIS, LOGICAL_AXES)
#define LOOP_DISTINCT_AXES(VAR) LOOP_S_L_N(VAR, X_AXIS, DISTINCT_AXES)
//
// feedRate_t is just a humble float
@ -201,8 +199,8 @@ struct XYval {
FI void set(const T (&arr)[XY]) { x = arr[0]; y = arr[1]; }
FI void set(const T (&arr)[XYZ]) { x = arr[0]; y = arr[1]; }
FI void set(const T (&arr)[XYZE]) { x = arr[0]; y = arr[1]; }
#if XYZE_N > XYZE
FI void set(const T (&arr)[XYZE_N]) { x = arr[0]; y = arr[1]; }
#if DISTINCT_AXES > LOGICAL_AXES
FI void set(const T (&arr)[DISTINCT_AXES]) { x = arr[0]; y = arr[1]; }
#endif
FI void reset() { x = y = 0; }
FI T magnitude() const { return (T)sqrtf(x*x + y*y); }
@ -312,8 +310,8 @@ struct XYZval {
FI void set(const T (&arr)[XY]) { x = arr[0]; y = arr[1]; }
FI void set(const T (&arr)[XYZ]) { x = arr[0]; y = arr[1]; z = arr[2]; }
FI void set(const T (&arr)[XYZE]) { x = arr[0]; y = arr[1]; z = arr[2]; }
#if XYZE_N > XYZE
FI void set(const T (&arr)[XYZE_N]) { x = arr[0]; y = arr[1]; z = arr[2]; }
#if DISTINCT_AXES > XYZE
FI void set(const T (&arr)[DISTINCT_AXES]) { x = arr[0]; y = arr[1]; z = arr[2]; }
#endif
FI void reset() { x = y = z = 0; }
FI T magnitude() const { return (T)sqrtf(x*x + y*y + z*z); }
@ -427,8 +425,8 @@ struct XYZEval {
FI void set(const T (&arr)[XY]) { x = arr[0]; y = arr[1]; }
FI void set(const T (&arr)[XYZ]) { x = arr[0]; y = arr[1]; z = arr[2]; }
FI void set(const T (&arr)[XYZE]) { x = arr[0]; y = arr[1]; z = arr[2]; e = arr[3]; }
#if XYZE_N > XYZE
FI void set(const T (&arr)[XYZE_N]) { x = arr[0]; y = arr[1]; z = arr[2]; e = arr[3]; }
#if DISTINCT_AXES > XYZE
FI void set(const T (&arr)[DISTINCT_AXES]) { x = arr[0]; y = arr[1]; z = arr[2]; e = arr[3]; }
#endif
FI XYZEval<T> copy() const { return *this; }
FI XYZEval<T> ABS() const { return { T(_ABS(x)), T(_ABS(y)), T(_ABS(z)), T(_ABS(e)) }; }
@ -518,4 +516,4 @@ struct XYZEval {
#undef FI
const xyze_char_t axis_codes { 'X', 'Y', 'Z', 'E' };
#define XYZ_CHAR(A) ((char)('X' + A))
#define AXIS_CHAR(A) ((char)('X' + A))

4
Marlin/src/core/utility.cpp

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

2
Marlin/src/feature/backlash.cpp

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

4
Marlin/src/feature/dac/dac_mcp4728.cpp

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

2
Marlin/src/feature/dac/stepper_dac.cpp

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

22
Marlin/src/feature/encoder_i2c.cpp

@ -337,7 +337,7 @@ bool I2CPositionEncoder::test_axis() {
ec = false;
xyze_pos_t startCoord, endCoord;
LOOP_XYZ(a) {
LOOP_LINEAR_AXES(a) {
startCoord[a] = planner.get_axis_position_mm((AxisEnum)a);
endCoord[a] = planner.get_axis_position_mm((AxisEnum)a);
}
@ -392,7 +392,7 @@ void I2CPositionEncoder::calibrate_steps_mm(const uint8_t iter) {
travelDistance = endDistance - startDistance;
xyze_pos_t startCoord, endCoord;
LOOP_XYZ(a) {
LOOP_LINEAR_AXES(a) {
startCoord[a] = planner.get_axis_position_mm((AxisEnum)a);
endCoord[a] = planner.get_axis_position_mm((AxisEnum)a);
}
@ -822,7 +822,7 @@ void I2CPositionEncodersMgr::M860() {
const bool hasU = parser.seen_test('U'), hasO = parser.seen_test('O');
if (I2CPE_idx == 0xFF) {
LOOP_XYZE(i) {
LOOP_LOGICAL_AXES(i) {
if (!I2CPE_anyaxis || parser.seen_test(axis_codes[i])) {
const uint8_t idx = idx_from_axis(AxisEnum(i));
if ((int8_t)idx >= 0) report_position(idx, hasU, hasO);
@ -849,7 +849,7 @@ void I2CPositionEncodersMgr::M861() {
if (parse()) return;
if (I2CPE_idx == 0xFF) {
LOOP_XYZE(i) {
LOOP_LOGICAL_AXES(i) {
if (!I2CPE_anyaxis || parser.seen(axis_codes[i])) {
const uint8_t idx = idx_from_axis(AxisEnum(i));
if ((int8_t)idx >= 0) report_status(idx);
@ -877,7 +877,7 @@ void I2CPositionEncodersMgr::M862() {
if (parse()) return;
if (I2CPE_idx == 0xFF) {
LOOP_XYZE(i) {
LOOP_LOGICAL_AXES(i) {
if (!I2CPE_anyaxis || parser.seen(axis_codes[i])) {
const uint8_t idx = idx_from_axis(AxisEnum(i));
if ((int8_t)idx >= 0) test_axis(idx);
@ -908,7 +908,7 @@ void I2CPositionEncodersMgr::M863() {
const uint8_t iterations = constrain(parser.byteval('P', 1), 1, 10);
if (I2CPE_idx == 0xFF) {
LOOP_XYZE(i) {
LOOP_LOGICAL_AXES(i) {
if (!I2CPE_anyaxis || parser.seen(axis_codes[i])) {
const uint8_t idx = idx_from_axis(AxisEnum(i));
if ((int8_t)idx >= 0) calibrate_steps_mm(idx, iterations);
@ -984,7 +984,7 @@ void I2CPositionEncodersMgr::M865() {
if (parse()) return;
if (!I2CPE_addr) {
LOOP_XYZE(i) {
LOOP_LOGICAL_AXES(i) {
if (!I2CPE_anyaxis || parser.seen(axis_codes[i])) {
const uint8_t idx = idx_from_axis(AxisEnum(i));
if ((int8_t)idx >= 0) report_module_firmware(encoders[idx].get_address());
@ -1015,7 +1015,7 @@ void I2CPositionEncodersMgr::M866() {
const bool hasR = parser.seen_test('R');
if (I2CPE_idx == 0xFF) {
LOOP_XYZE(i) {
LOOP_LOGICAL_AXES(i) {
if (!I2CPE_anyaxis || parser.seen(axis_codes[i])) {
const uint8_t idx = idx_from_axis(AxisEnum(i));
if ((int8_t)idx >= 0) {
@ -1053,7 +1053,7 @@ void I2CPositionEncodersMgr::M867() {
const int8_t onoff = parser.seenval('S') ? parser.value_int() : -1;
if (I2CPE_idx == 0xFF) {
LOOP_XYZE(i) {
LOOP_LOGICAL_AXES(i) {
if (!I2CPE_anyaxis || parser.seen(axis_codes[i])) {
const uint8_t idx = idx_from_axis(AxisEnum(i));
if ((int8_t)idx >= 0) {
@ -1089,7 +1089,7 @@ void I2CPositionEncodersMgr::M868() {
const float newThreshold = parser.seenval('T') ? parser.value_float() : -9999;
if (I2CPE_idx == 0xFF) {
LOOP_XYZE(i) {
LOOP_LOGICAL_AXES(i) {
if (!I2CPE_anyaxis || parser.seen(axis_codes[i])) {
const uint8_t idx = idx_from_axis(AxisEnum(i));
if ((int8_t)idx >= 0) {
@ -1123,7 +1123,7 @@ void I2CPositionEncodersMgr::M869() {
if (parse()) return;
if (I2CPE_idx == 0xFF) {
LOOP_XYZE(i) {
LOOP_LOGICAL_AXES(i) {
if (!I2CPE_anyaxis || parser.seen(axis_codes[i])) {
const uint8_t idx = idx_from_axis(AxisEnum(i));
if ((int8_t)idx >= 0) report_error(idx);

2
Marlin/src/feature/joystick.cpp

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

8
Marlin/src/feature/powerloss.cpp

@ -549,7 +549,7 @@ void PrintJobRecovery::resume() {
TERN_(HAS_HOME_OFFSET, home_offset = info.home_offset);
TERN_(HAS_POSITION_SHIFT, position_shift = info.position_shift);
#if HAS_HOME_OFFSET || HAS_POSITION_SHIFT
LOOP_XYZ(i) update_workspace_offset((AxisEnum)i);
LOOP_LINEAR_AXES(i) update_workspace_offset((AxisEnum)i);
#endif
// Relative axis modes
@ -581,7 +581,7 @@ void PrintJobRecovery::resume() {
if (info.valid_head) {
if (info.valid_head == info.valid_foot) {
DEBUG_ECHOPGM("current_position: ");
LOOP_XYZE(i) {
LOOP_LOGICAL_AXES(i) {
if (i) DEBUG_CHAR(',');
DEBUG_DECIMAL(info.current_position[i]);
}
@ -599,7 +599,7 @@ void PrintJobRecovery::resume() {
#if HAS_HOME_OFFSET
DEBUG_ECHOPGM("home_offset: ");
LOOP_XYZ(i) {
LOOP_LINEAR_AXES(i) {
if (i) DEBUG_CHAR(',');
DEBUG_DECIMAL(info.home_offset[i]);
}
@ -608,7 +608,7 @@ void PrintJobRecovery::resume() {
#if HAS_POSITION_SHIFT
DEBUG_ECHOPGM("position_shift: ");
LOOP_XYZ(i) {
LOOP_LINEAR_AXES(i) {
if (i) DEBUG_CHAR(',');
DEBUG_DECIMAL(info.position_shift[i]);
}

2
Marlin/src/gcode/calibrate/G28.cpp

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

10
Marlin/src/gcode/calibrate/G33.cpp

@ -347,7 +347,7 @@ static float auto_tune_a() {
abc_float_t delta_e = { 0.0f }, delta_t = { 0.0f };
delta_t.reset();
LOOP_XYZ(axis) {
LOOP_LINEAR_AXES(axis) {
delta_t[axis] = diff;
calc_kinematics_diff_probe_points(z_pt, delta_e, delta_r, delta_t);
delta_t[axis] = 0;
@ -525,7 +525,7 @@ void GcodeSuite::G33() {
case 1:
test_precision = 0.0f; // forced end
LOOP_XYZ(axis) e_delta[axis] = +Z4(CEN);
LOOP_LINEAR_AXES(axis) e_delta[axis] = +Z4(CEN);
break;
case 2:
@ -573,14 +573,14 @@ void GcodeSuite::G33() {
// Normalize angles to least-squares
if (_angle_results) {
float a_sum = 0.0f;
LOOP_XYZ(axis) a_sum += delta_tower_angle_trim[axis];
LOOP_XYZ(axis) delta_tower_angle_trim[axis] -= a_sum / 3.0f;
LOOP_LINEAR_AXES(axis) a_sum += delta_tower_angle_trim[axis];
LOOP_LINEAR_AXES(axis) delta_tower_angle_trim[axis] -= a_sum / 3.0f;
}
// adjust delta_height and endstops by the max amount
const float z_temp = _MAX(delta_endstop_adj.a, delta_endstop_adj.b, delta_endstop_adj.c);
delta_height -= z_temp;
LOOP_XYZ(axis) delta_endstop_adj[axis] -= z_temp;
LOOP_LINEAR_AXES(axis) delta_endstop_adj[axis] -= z_temp;
}
recalc_delta_settings();
NOMORE(zero_std_dev_min, zero_std_dev);

12
Marlin/src/gcode/calibrate/M425.cpp

@ -55,8 +55,8 @@ void GcodeSuite::M425() {
}
};
LOOP_XYZ(a) {
if (axis_can_calibrate(a) && parser.seen(XYZ_CHAR(a))) {
LOOP_LINEAR_AXES(a) {
if (axis_can_calibrate(a) && parser.seen(AXIS_CHAR(a))) {
planner.synchronize();
backlash.distance_mm[a] = parser.has_value() ? parser.value_linear_units() : backlash.get_measurement(AxisEnum(a));
noArgs = false;
@ -83,8 +83,8 @@ void GcodeSuite::M425() {
SERIAL_ECHOLNPGM("active:");
SERIAL_ECHOLNPAIR(" Correction Amount/Fade-out: F", backlash.get_correction(), " (F1.0 = full, F0.0 = none)");
SERIAL_ECHOPGM(" Backlash Distance (mm): ");
LOOP_XYZ(a) if (axis_can_calibrate(a)) {
SERIAL_CHAR(' ', XYZ_CHAR(a));
LOOP_LINEAR_AXES(a) if (axis_can_calibrate(a)) {
SERIAL_CHAR(' ', AXIS_CHAR(a));
SERIAL_ECHO(backlash.distance_mm[a]);
SERIAL_EOL();
}
@ -96,8 +96,8 @@ void GcodeSuite::M425() {
#if ENABLED(MEASURE_BACKLASH_WHEN_PROBING)
SERIAL_ECHOPGM(" Average measured backlash (mm):");
if (backlash.has_any_measurement()) {
LOOP_XYZ(a) if (axis_can_calibrate(a) && backlash.has_measurement(AxisEnum(a))) {
SERIAL_CHAR(' ', XYZ_CHAR(a));
LOOP_LINEAR_AXES(a) if (axis_can_calibrate(a) && backlash.has_measurement(AxisEnum(a))) {
SERIAL_CHAR(' ', AXIS_CHAR(a));
SERIAL_ECHO(backlash.get_measurement(AxisEnum(a)));
}
}

6
Marlin/src/gcode/calibrate/M666.cpp

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

2
Marlin/src/gcode/calibrate/M852.cpp

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

4
Marlin/src/gcode/config/M200-M205.cpp

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

2
Marlin/src/gcode/config/M92.cpp

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

8
Marlin/src/gcode/control/M350_M351.cpp

@ -34,7 +34,7 @@
*/
void GcodeSuite::M350() {
if (parser.seen('S')) LOOP_LE_N(i, 4) stepper.microstep_mode(i, parser.value_byte());
LOOP_XYZE(i) if (parser.seen(axis_codes[i])) stepper.microstep_mode(i, parser.value_byte());
LOOP_LOGICAL_AXES(i) if (parser.seen(axis_codes[i])) stepper.microstep_mode(i, parser.value_byte());
if (parser.seen('B')) stepper.microstep_mode(4, parser.value_byte());
stepper.microstep_readings();
}
@ -46,15 +46,15 @@ void GcodeSuite::M350() {
void GcodeSuite::M351() {
if (parser.seenval('S')) switch (parser.value_byte()) {
case 1:
LOOP_XYZE(i) if (parser.seenval(axis_codes[i])) stepper.microstep_ms(i, parser.value_byte(), -1, -1);
LOOP_LOGICAL_AXES(i) if (parser.seenval(axis_codes[i])) stepper.microstep_ms(i, parser.value_byte(), -1, -1);
if (parser.seenval('B')) stepper.microstep_ms(4, parser.value_byte(), -1, -1);
break;
case 2:
LOOP_XYZE(i) if (parser.seenval(axis_codes[i])) stepper.microstep_ms(i, -1, parser.value_byte(), -1);
LOOP_LOGICAL_AXES(i) if (parser.seenval(axis_codes[i])) stepper.microstep_ms(i, -1, parser.value_byte(), -1);
if (parser.seenval('B')) stepper.microstep_ms(4, -1, parser.value_byte(), -1);
break;
case 3:
LOOP_XYZE(i) if (parser.seenval(axis_codes[i])) stepper.microstep_ms(i, -1, -1, parser.value_byte());
LOOP_LOGICAL_AXES(i) if (parser.seenval(axis_codes[i])) stepper.microstep_ms(i, -1, -1, parser.value_byte());
if (parser.seenval('B')) stepper.microstep_ms(4, -1, -1, parser.value_byte());
break;
}

2
Marlin/src/gcode/control/M605.cpp

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

2
Marlin/src/gcode/feature/L6470/M906.cpp

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

6
Marlin/src/gcode/feature/digipot/M907-M910.cpp

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

6
Marlin/src/gcode/feature/pause/G61.cpp

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

6
Marlin/src/gcode/feature/trinamic/M122.cpp

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

2
Marlin/src/gcode/feature/trinamic/M569.cpp

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

2
Marlin/src/gcode/feature/trinamic/M906.cpp

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

4
Marlin/src/gcode/feature/trinamic/M911-M914.cpp

@ -209,7 +209,7 @@
#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)
const uint8_t index = parser.byteval('I');
#endif
LOOP_XYZE(i) if (int32_t value = parser.longval(axis_codes[i])) {
LOOP_LOGICAL_AXES(i) if (int32_t value = parser.longval(axis_codes[i])) {
report = false;
switch (i) {
case X_AXIS:
@ -338,7 +338,7 @@
bool report = true;
const uint8_t index = parser.byteval('I');
LOOP_XYZ(i) if (parser.seen(XYZ_CHAR(i))) {
LOOP_LINEAR_AXES(i) if (parser.seen(AXIS_CHAR(i))) {
const int16_t value = parser.value_int();
report = false;
switch (i) {

4
Marlin/src/gcode/gcode.cpp

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

2
Marlin/src/gcode/geometry/G53-G59.cpp

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

6
Marlin/src/gcode/geometry/G92.cpp

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

8
Marlin/src/gcode/geometry/M206_M428.cpp

@ -42,8 +42,8 @@ void M206_report() {
* *** In the 2.0 release, it will simply be disabled by default.
*/
void GcodeSuite::M206() {
LOOP_XYZ(i)
if (parser.seen(XYZ_CHAR(i)))
LOOP_LINEAR_AXES(i)
if (parser.seen(AXIS_CHAR(i)))
set_home_offset((AxisEnum)i, parser.value_linear_units());
#if ENABLED(MORGAN_SCARA)
@ -72,7 +72,7 @@ void GcodeSuite::M428() {
if (homing_needed_error()) return;
xyz_float_t diff;
LOOP_XYZ(i) {
LOOP_LINEAR_AXES(i) {
diff[i] = base_home_pos((AxisEnum)i) - current_position[i];
if (!WITHIN(diff[i], -20, 20) && home_dir((AxisEnum)i) > 0)
diff[i] = -current_position[i];
@ -84,7 +84,7 @@ void GcodeSuite::M428() {
}
}
LOOP_XYZ(i) set_home_offset((AxisEnum)i, diff[i]);
LOOP_LINEAR_AXES(i) set_home_offset((AxisEnum)i, diff[i]);
report_current_position();
LCD_MESSAGEPGM(MSG_HOME_OFFSETS_APPLIED);
BUZZ(100, 659);

6
Marlin/src/gcode/host/M114.cpp

@ -47,8 +47,8 @@
void report_linear_axis_pos(const xyz_pos_t &pos, const uint8_t precision=3) {
char str[12];
LOOP_XYZ(a) {
SERIAL_CHAR(' ', XYZ_CHAR(a), ':');
LOOP_LINEAR_AXES(a) {
SERIAL_CHAR(' ', AXIS_CHAR(a), ':');
SERIAL_ECHO(dtostrf(pos[a], 1, precision, str));
}
SERIAL_EOL();
@ -153,7 +153,7 @@
#endif // HAS_L64XX
SERIAL_ECHOPGM("Stepper:");
LOOP_XYZE(i) {
LOOP_LOGICAL_AXES(i) {
SERIAL_CHAR(' ', axis_codes[i], ':');
SERIAL_ECHO(stepper.position((AxisEnum)i));
}

4
Marlin/src/gcode/motion/M290.cpp

@ -69,8 +69,8 @@
*/
void GcodeSuite::M290() {
#if ENABLED(BABYSTEP_XY)
LOOP_XYZ(a)
if (parser.seenval(XYZ_CHAR(a)) || (a == Z_AXIS && parser.seenval('S'))) {
LOOP_LINEAR_AXES(a)
if (parser.seenval(AXIS_CHAR(a)) || (a == Z_AXIS && parser.seenval('S'))) {
const float offs = constrain(parser.value_axis_units((AxisEnum)a), -2, 2);
babystep.add_mm((AxisEnum)a, offs);
#if ENABLED(BABYSTEP_ZPROBE_OFFSET)

6
Marlin/src/gcode/probe/G38.cpp

@ -38,7 +38,7 @@ inline void G38_single_probe(const uint8_t move_value) {
planner.synchronize();
G38_move = 0;
endstops.hit_on_purpose();
set_current_from_steppers_for_axis(ALL_AXES);
set_current_from_steppers_for_axis(ALL_AXES_MASK);
sync_plan_position();
}
@ -49,7 +49,7 @@ inline bool G38_run_probe() {
#if MULTIPLE_PROBING > 1
// Get direction of move and retract
xyz_float_t retract_mm;
LOOP_XYZ(i) {
LOOP_LINEAR_AXES(i) {
const float dist = destination[i] - current_position[i];
retract_mm[i] = ABS(dist) < G38_MINIMUM_MOVE ? 0 : home_bump_mm((AxisEnum)i) * (dist > 0 ? -1 : 1);
}
@ -119,7 +119,7 @@ void GcodeSuite::G38(const int8_t subcode) {
;
// If any axis has enough movement, do the move
LOOP_XYZ(i)
LOOP_LINEAR_AXES(i)
if (ABS(destination[i] - current_position[i]) >= G38_MINIMUM_MOVE) {
if (!parser.seenval('F')) feedrate_mm_s = homing_feedrate((AxisEnum)i);
// If G38.2 fails throw an error

30
Marlin/src/inc/Conditionals_LCD.h

@ -651,22 +651,38 @@
#endif
/**
* DISTINCT_E_FACTORS affects how some E factors are accessed
* Number of Linear Axes (e.g., XYZ)
* All the logical axes except for the tool (E) axis
*/
#ifndef LINEAR_AXES
#define LINEAR_AXES XYZ
#endif
/**
* Number of Logical Axes (e.g., XYZE)
* All the logical axes that can be commanded directly by G-code.
* Delta maps stepper-specific values to ABC steppers.
*/
#if EXTRUDERS
#define LOGICAL_AXES INCREMENT(LINEAR_AXES)
#else
#define LOGICAL_AXES LINEAR_AXES
#endif
/**
* DISTINCT_E_FACTORS affects whether Extruders use different settings
*/
#if ENABLED(DISTINCT_E_FACTORS) && E_STEPPERS > 1
#define DISTINCT_E E_STEPPERS
#define XYZE_N (XYZ + E_STEPPERS)
#define DISTINCT_AXES (LINEAR_AXES + E_STEPPERS)
#define E_INDEX_N(E) (E)
#define E_AXIS_N(E) AxisEnum(E_AXIS + E)
#define UNUSED_E(E) NOOP
#else
#undef DISTINCT_E_FACTORS
#define DISTINCT_E 1
#define XYZE_N XYZE
#define DISTINCT_AXES LOGICAL_AXES
#define E_INDEX_N(E) 0
#define E_AXIS_N(E) E_AXIS
#define UNUSED_E(E) UNUSED(E)
#endif
#define E_AXIS_N(E) AxisEnum(E_AXIS + E_INDEX_N(E))
/**
* The BLTouch Probe emulates a servo probe

24
Marlin/src/inc/SanityCheck.h

@ -2819,22 +2819,22 @@ constexpr float sanity_arr_1[] = DEFAULT_AXIS_STEPS_PER_UNIT,
#define _EXTRA_NOTE ""
#endif
static_assert(COUNT(sanity_arr_1) >= XYZE, "DEFAULT_AXIS_STEPS_PER_UNIT requires X, Y, Z and E elements.");
static_assert(COUNT(sanity_arr_1) <= XYZE_N, "DEFAULT_AXIS_STEPS_PER_UNIT has too many elements." _EXTRA_NOTE);
static_assert(COUNT(sanity_arr_1) >= LOGICAL_AXES, "DEFAULT_AXIS_STEPS_PER_UNIT requires X, Y, Z and E elements.");
static_assert(COUNT(sanity_arr_1) <= DISTINCT_AXES, "DEFAULT_AXIS_STEPS_PER_UNIT has too many elements." _EXTRA_NOTE);
static_assert( _ARR_TEST(1,0) && _ARR_TEST(1,1) && _ARR_TEST(1,2)
&& _ARR_TEST(1,3) && _ARR_TEST(1,4) && _ARR_TEST(1,5)
&& _ARR_TEST(1,6) && _ARR_TEST(1,7) && _ARR_TEST(1,8),
"DEFAULT_AXIS_STEPS_PER_UNIT values must be positive.");
static_assert(COUNT(sanity_arr_2) >= XYZE, "DEFAULT_MAX_FEEDRATE requires X, Y, Z and E elements.");
static_assert(COUNT(sanity_arr_2) <= XYZE_N, "DEFAULT_MAX_FEEDRATE has too many elements." _EXTRA_NOTE);
static_assert(COUNT(sanity_arr_2) >= LOGICAL_AXES, "DEFAULT_MAX_FEEDRATE requires X, Y, Z and E elements.");
static_assert(COUNT(sanity_arr_2) <= DISTINCT_AXES, "DEFAULT_MAX_FEEDRATE has too many elements." _EXTRA_NOTE);
static_assert( _ARR_TEST(2,0) && _ARR_TEST(2,1) && _ARR_TEST(2,2)
&& _ARR_TEST(2,3) && _ARR_TEST(2,4) && _ARR_TEST(2,5)
&& _ARR_TEST(2,6) && _ARR_TEST(2,7) && _ARR_TEST(2,8),
"DEFAULT_MAX_FEEDRATE values must be positive.");
static_assert(COUNT(sanity_arr_3) >= XYZE, "DEFAULT_MAX_ACCELERATION requires X, Y, Z and E elements.");
static_assert(COUNT(sanity_arr_3) <= XYZE_N, "DEFAULT_MAX_ACCELERATION has too many elements." _EXTRA_NOTE);
static_assert(COUNT(sanity_arr_3) >= LOGICAL_AXES, "DEFAULT_MAX_ACCELERATION requires X, Y, Z and E elements.");
static_assert(COUNT(sanity_arr_3) <= DISTINCT_AXES, "DEFAULT_MAX_ACCELERATION has too many elements." _EXTRA_NOTE);
static_assert( _ARR_TEST(3,0) && _ARR_TEST(3,1) && _ARR_TEST(3,2)
&& _ARR_TEST(3,3) && _ARR_TEST(3,4) && _ARR_TEST(3,5)
&& _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)
#if ENABLED(LIMITED_MAX_ACCEL_EDITING)
#ifdef MAX_ACCEL_EDIT_VALUES
constexpr float sanity_arr_4[] = MAX_ACCEL_EDIT_VALUES;
static_assert(COUNT(sanity_arr_4) >= XYZE, "MAX_ACCEL_EDIT_VALUES requires X, Y, Z and E elements.");
static_assert(COUNT(sanity_arr_4) <= XYZE, "MAX_ACCEL_EDIT_VALUES has too many elements. X, Y, Z and E elements only.");
static_assert(COUNT(sanity_arr_4) >= LOGICAL_AXES, "MAX_ACCEL_EDIT_VALUES requires X, Y, Z and E elements.");
static_assert(COUNT(sanity_arr_4) <= LOGICAL_AXES, "MAX_ACCEL_EDIT_VALUES has too many elements. X, Y, Z and E elements only.");
static_assert( _ARR_TEST(4,0) && _ARR_TEST(4,1) && _ARR_TEST(4,2)
&& _ARR_TEST(4,3) && _ARR_TEST(4,4) && _ARR_TEST(4,5)
&& _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)
#if ENABLED(LIMITED_MAX_FR_EDITING)
#ifdef MAX_FEEDRATE_EDIT_VALUES
constexpr float sanity_arr_5[] = MAX_FEEDRATE_EDIT_VALUES;
static_assert(COUNT(sanity_arr_5) >= XYZE, "MAX_FEEDRATE_EDIT_VALUES requires X, Y, Z and E elements.");
static_assert(COUNT(sanity_arr_5) <= XYZE, "MAX_FEEDRATE_EDIT_VALUES has too many elements. X, Y, Z and E elements only.");
static_assert(COUNT(sanity_arr_5) >= LOGICAL_AXES, "MAX_FEEDRATE_EDIT_VALUES requires X, Y, Z and E elements.");
static_assert(COUNT(sanity_arr_5) <= LOGICAL_AXES, "MAX_FEEDRATE_EDIT_VALUES has too many elements. X, Y, Z and E elements only.");
static_assert( _ARR_TEST(5,0) && _ARR_TEST(5,1) && _ARR_TEST(5,2)
&& _ARR_TEST(5,3) && _ARR_TEST(5,4) && _ARR_TEST(5,5)
&& _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)
#if ENABLED(LIMITED_JERK_EDITING)
#ifdef MAX_JERK_EDIT_VALUES
constexpr float sanity_arr_6[] = MAX_JERK_EDIT_VALUES;
static_assert(COUNT(sanity_arr_6) >= XYZE, "MAX_JERK_EDIT_VALUES requires X, Y, Z and E elements.");
static_assert(COUNT(sanity_arr_6) <= XYZE, "MAX_JERK_EDIT_VALUES has too many elements. X, Y, Z and E elements only.");
static_assert(COUNT(sanity_arr_6) >= LOGICAL_AXES, "MAX_JERK_EDIT_VALUES requires X, Y, Z and E elements.");
static_assert(COUNT(sanity_arr_6) <= LOGICAL_AXES, "MAX_JERK_EDIT_VALUES has too many elements. X, Y, Z and E elements only.");
static_assert( _ARR_TEST(6,0) && _ARR_TEST(6,1) && _ARR_TEST(6,2)
&& _ARR_TEST(6,3) && _ARR_TEST(6,4) && _ARR_TEST(6,5)
&& _ARR_TEST(6,6) && _ARR_TEST(6,7) && _ARR_TEST(6,8),

12
Marlin/src/lcd/marlinui.cpp

@ -684,7 +684,7 @@ void MarlinUI::quick_feedback(const bool clear_buttons/*=true*/) {
#if ENABLED(MULTI_MANUAL)
int8_t ManualMove::e_index = 0;
#endif
AxisEnum ManualMove::axis = NO_AXIS;
AxisEnum ManualMove::axis = NO_AXIS_MASK;
/**
* 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*/) {
*
* To post a manual move:
* - Update current_position to the new place you want to go.
* - Set manual_move.axis to an axis like X_AXIS. Use ALL_AXES for diagonal moves.
* - Set manual_move.axis to an axis like X_AXIS. Use ALL_AXES_MASK for diagonal moves.
* - Set manual_move.start_time to a point in the future (in ms) when the move should be done.
*
* For kinematic machines:
@ -710,7 +710,7 @@ void MarlinUI::quick_feedback(const bool clear_buttons/*=true*/) {
if (processing) return; // Prevent re-entry from idle() calls
// Add a manual move to the queue?
if (axis != NO_AXIS && ELAPSED(millis(), start_time) && !planner.is_full()) {
if (axis != NO_AXIS_MASK && ELAPSED(millis(), start_time) && !planner.is_full()) {
const feedRate_t fr_mm_s = (axis <= E_AXIS) ? manual_feedrate_mm_s[axis] : XY_PROBE_FEEDRATE_MM_S;
@ -722,7 +722,7 @@ void MarlinUI::quick_feedback(const bool clear_buttons/*=true*/) {
#endif
// Apply a linear offset to a single axis
if (axis == ALL_AXES)
if (axis == ALL_AXES_MASK)
destination = all_axes_destination;
else if (axis <= XYZE) {
destination = current_position;
@ -731,7 +731,7 @@ void MarlinUI::quick_feedback(const bool clear_buttons/*=true*/) {
// Reset for the next move
offset = 0;
axis = NO_AXIS;
axis = NO_AXIS_MASK;
// DELTA and SCARA machines use segmented moves, which could fill the planner during the call to
// 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*/) {
//SERIAL_ECHOLNPAIR("Add planner.move with Axis ", AS_CHAR(axis_codes[axis]), " at FR ", fr_mm_s);
axis = NO_AXIS;
axis = NO_AXIS_MASK;
#endif
}

2
Marlin/src/lcd/menu/menu_advanced.cpp

@ -64,7 +64,7 @@ void menu_backlash();
void menu_dac() {
static xyze_uint8_t driverPercent;
LOOP_XYZE(i) driverPercent[i] = stepper_dac.get_current_percent((AxisEnum)i);
LOOP_LOGICAL_AXES(i) driverPercent[i] = stepper_dac.get_current_percent((AxisEnum)i);
START_MENU();
BACK_ITEM(MSG_ADVANCED_SETTINGS);
#define EDIT_DAC_PERCENT(A) EDIT_ITEM(uint8, MSG_DAC_PERCENT_##A, &driverPercent[_AXIS(A)], 0, 100, []{ stepper_dac.set_current_percents(driverPercent); })

2
Marlin/src/lcd/menu/menu_bed_leveling.cpp

@ -206,7 +206,7 @@
#if ENABLED(MESH_EDIT_MENU)
inline void refresh_planner() {
set_current_from_steppers_for_axis(ALL_AXES);
set_current_from_steppers_for_axis(ALL_AXES_MASK);
sync_plan_position();
}

2
Marlin/src/lcd/menu/menu_ubl.cpp

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

2
Marlin/src/libs/L64XX/L64XX_Marlin.cpp

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

10
Marlin/src/module/motion.cpp

@ -124,7 +124,7 @@ xyze_pos_t destination; // {0}
"Offsets for the first hotend must be 0.0."
);
// Transpose from [XYZ][HOTENDS] to [HOTENDS][XYZ]
HOTEND_LOOP() LOOP_XYZ(a) hotend_offset[e][a] = tmp[a][e];
HOTEND_LOOP() LOOP_LINEAR_AXES(a) hotend_offset[e][a] = tmp[a][e];
#if ENABLED(DUAL_X_CARRIAGE)
hotend_offset[1].x = _MAX(X2_HOME_POS, X2_MAX_POS);
#endif
@ -282,7 +282,7 @@ void report_current_position_projected() {
void quickstop_stepper() {
planner.quick_stop();
planner.synchronize();
set_current_from_steppers_for_axis(ALL_AXES);
set_current_from_steppers_for_axis(ALL_AXES_MASK);
sync_plan_position();
}
@ -360,7 +360,7 @@ void set_current_from_steppers_for_axis(const AxisEnum axis) {
planner.unapply_modifiers(pos, true);
#endif
if (axis == ALL_AXES)
if (axis == ALL_AXES_MASK)
current_position = pos;
else
current_position[axis] = pos[axis];
@ -681,7 +681,7 @@ void restore_feedrate_and_scaling() {
#endif
if (DEBUGGING(LEVELING))
SERIAL_ECHOLNPAIR("Axis ", AS_CHAR(XYZ_CHAR(axis)), " min:", soft_endstop.min[axis], " max:", soft_endstop.max[axis]);
SERIAL_ECHOLNPAIR("Axis ", AS_CHAR(AXIS_CHAR(axis)), " min:", soft_endstop.min[axis], " max:", soft_endstop.max[axis]);
}
/**
@ -1951,7 +1951,7 @@ void set_axis_is_at_home(const AxisEnum axis) {
#if HAS_WORKSPACE_OFFSET
void update_workspace_offset(const AxisEnum axis) {
workspace_offset[axis] = home_offset[axis] + position_shift[axis];
if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("Axis ", AS_CHAR(XYZ_CHAR(axis)), " home_offset = ", home_offset[axis], " position_shift = ", position_shift[axis]);
if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("Axis ", AS_CHAR(AXIS_CHAR(axis)), " home_offset = ", home_offset[axis], " position_shift = ", position_shift[axis]);
}
#endif

14
Marlin/src/module/planner.cpp

@ -136,9 +136,9 @@ planner_settings_t Planner::settings; // Initialized by settings.load(
laser_state_t Planner::laser_inline; // Current state for blocks
#endif
uint32_t Planner::max_acceleration_steps_per_s2[XYZE_N]; // (steps/s^2) Derived from mm_per_s2
uint32_t Planner::max_acceleration_steps_per_s2[DISTINCT_AXES]; // (steps/s^2) Derived from mm_per_s2
float Planner::steps_to_mm[XYZE_N]; // (mm) Millimeters per step
float Planner::steps_to_mm[DISTINCT_AXES]; // (mm) Millimeters per step
#if HAS_JUNCTION_DEVIATION
float Planner::junction_deviation_mm; // (mm) M205 J
@ -2201,7 +2201,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move,
float speed_factor = 1.0f; // factor <1 decreases speed
// Linear axes first with less logic
LOOP_XYZ(i) {
LOOP_LINEAR_AXES(i) {
current_speed[i] = steps_dist_mm[i] * inverse_secs;
const feedRate_t cs = ABS(current_speed[i]),
max_fr = settings.max_feedrate_mm_s[i];
@ -2593,7 +2593,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move,
const float extra_xyjerk = (de <= 0) ? TRAVEL_EXTRA_XYJERK : 0;
uint8_t limited = 0;
TERN(HAS_LINEAR_E_JERK, LOOP_XYZ, LOOP_XYZE)(i) {
TERN(HAS_LINEAR_E_JERK, LOOP_LINEAR_AXES, LOOP_LOGICAL_AXES)(i) {
const float jerk = ABS(current_speed[i]), // cs : Starting from zero, change in speed for this axis
maxj = (max_jerk[i] + (i == X_AXIS || i == Y_AXIS ? extra_xyjerk : 0.0f)); // mj : The max jerk setting for this axis
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,
vmax_junction = previous_nominal_speed;
// Now limit the jerk in all axes.
TERN(HAS_LINEAR_E_JERK, LOOP_XYZ, LOOP_XYZE)(axis) {
TERN(HAS_LINEAR_E_JERK, LOOP_LINEAR_AXES, LOOP_LOGICAL_AXES)(axis) {
// Limit an axis. We have to differentiate: coasting, reversal of an axis, full stop.
float v_exit = previous_speed[axis] * smaller_speed_factor,
v_entry = current_speed[axis];
@ -3033,7 +3033,7 @@ void Planner::reset_acceleration_rates() {
#define AXIS_CONDITION true
#endif
uint32_t highest_rate = 1;
LOOP_XYZE_N(i) {
LOOP_DISTINCT_AXES(i) {
max_acceleration_steps_per_s2[i] = settings.max_acceleration_mm_per_s2[i] * settings.axis_steps_per_mm[i];
if (AXIS_CONDITION) NOLESS(highest_rate, max_acceleration_steps_per_s2[i]);
}
@ -3046,7 +3046,7 @@ void Planner::reset_acceleration_rates() {
* Must be called whenever settings.axis_steps_per_mm changes!
*/
void Planner::refresh_positioning() {
LOOP_XYZE_N(i) steps_to_mm[i] = 1.0f / settings.axis_steps_per_mm[i];
LOOP_DISTINCT_AXES(i) steps_to_mm[i] = 1.0f / settings.axis_steps_per_mm[i];
set_position_mm(current_position);
reset_acceleration_rates();
}

18
Marlin/src/module/planner.h

@ -268,10 +268,10 @@ typedef struct block_t {
#endif
typedef struct {
uint32_t max_acceleration_mm_per_s2[XYZE_N], // (mm/s^2) M201 XYZE
uint32_t max_acceleration_mm_per_s2[DISTINCT_AXES], // (mm/s^2) M201 XYZE
min_segment_time_us; // (µs) M205 B
float axis_steps_per_mm[XYZE_N]; // (steps) M92 XYZE - Steps per millimeter
feedRate_t max_feedrate_mm_s[XYZE_N]; // (mm/s) M203 XYZE - Max speeds
float axis_steps_per_mm[DISTINCT_AXES]; // (steps) M92 XYZE - Steps per millimeter
feedRate_t max_feedrate_mm_s[DISTINCT_AXES]; // (mm/s) M203 XYZE - Max speeds
float acceleration, // (mm/s^2) M204 S - Normal acceleration. DEFAULT ACCELERATION for all printing moves.
retract_acceleration, // (mm/s^2) M204 R - Retract acceleration. Filament pull-back and push-forward while standing still in the other axes
travel_acceleration; // (mm/s^2) M204 T - Travel acceleration. DEFAULT ACCELERATION for all NON printing moves.
@ -360,13 +360,13 @@ class Planner {
static laser_state_t laser_inline;
#endif
static uint32_t max_acceleration_steps_per_s2[XYZE_N]; // (steps/s^2) Derived from mm_per_s2
static float steps_to_mm[XYZE_N]; // Millimeters per step
static uint32_t max_acceleration_steps_per_s2[DISTINCT_AXES]; // (steps/s^2) Derived from mm_per_s2
static float steps_to_mm[DISTINCT_AXES]; // Millimeters per step
#if HAS_JUNCTION_DEVIATION
static float junction_deviation_mm; // (mm) M205 J
static float junction_deviation_mm; // (mm) M205 J
#if HAS_LINEAR_E_JERK
static float max_e_jerk[DISTINCT_E]; // Calculated from junction_deviation_mm
static float max_e_jerk[DISTINCT_E]; // Calculated from junction_deviation_mm
#endif
#endif
@ -1014,13 +1014,13 @@ class Planner {
FORCE_INLINE static void normalize_junction_vector(xyze_float_t &vector) {
float magnitude_sq = 0;
LOOP_XYZE(idx) if (vector[idx]) magnitude_sq += sq(vector[idx]);
LOOP_LOGICAL_AXES(idx) if (vector[idx]) magnitude_sq += sq(vector[idx]);
vector *= RSQRT(magnitude_sq);
}
FORCE_INLINE static float limit_value_by_axis_maximum(const_float_t max_value, xyze_float_t &unit_vec) {
float limit_value = max_value;
LOOP_XYZE(idx) {
LOOP_LOGICAL_AXES(idx) {
if (unit_vec[idx]) {
if (limit_value * ABS(unit_vec[idx]) > settings.max_acceleration_mm_per_s2[idx])
limit_value = ABS(settings.max_acceleration_mm_per_s2[idx] / unit_vec[idx]);

2
Marlin/src/module/scara.cpp

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

27
Marlin/src/module/settings.cpp

@ -194,7 +194,7 @@ typedef struct SettingsDataStruct {
//
// DISTINCT_E_FACTORS
//
uint8_t esteppers; // XYZE_N - XYZ
uint8_t esteppers; // DISTINCT_AXES - LINEAR_AXES
planner_settings_t planner_settings;
@ -385,7 +385,7 @@ typedef struct SettingsDataStruct {
// HAS_MOTOR_CURRENT_PWM
//
#ifndef MOTOR_CURRENT_COUNT
#define MOTOR_CURRENT_COUNT 3
#define MOTOR_CURRENT_COUNT LINEAR_AXES
#endif
uint32_t motor_current_setting[MOTOR_CURRENT_COUNT]; // M907 X Z E
@ -516,7 +516,7 @@ void MarlinSettings::postprocess() {
#endif
// Software endstops depend on home_offset
LOOP_XYZ(i) {
LOOP_LINEAR_AXES(i) {
update_workspace_offset((AxisEnum)i);
update_software_endstops((AxisEnum)i);
}
@ -637,9 +637,8 @@ void MarlinSettings::postprocess() {
working_crc = 0; // clear before first "real data"
const uint8_t esteppers = COUNT(planner.settings.axis_steps_per_mm) - LINEAR_AXES;
_FIELD_TEST(esteppers);
const uint8_t esteppers = COUNT(planner.settings.axis_steps_per_mm) - XYZ;
EEPROM_WRITE(esteppers);
//
@ -1513,16 +1512,16 @@ void MarlinSettings::postprocess() {
{
// Get only the number of E stepper parameters previously stored
// Any steppers added later are set to their defaults
uint32_t tmp1[XYZ + esteppers];
float tmp2[XYZ + esteppers];
feedRate_t tmp3[XYZ + esteppers];
uint32_t tmp1[LINEAR_AXES + esteppers];
float tmp2[LINEAR_AXES + esteppers];
feedRate_t tmp3[LINEAR_AXES + esteppers];
EEPROM_READ((uint8_t *)tmp1, sizeof(tmp1)); // max_acceleration_mm_per_s2
EEPROM_READ(planner.settings.min_segment_time_us);
EEPROM_READ((uint8_t *)tmp2, sizeof(tmp2)); // axis_steps_per_mm
EEPROM_READ((uint8_t *)tmp3, sizeof(tmp3)); // max_feedrate_mm_s
if (!validating) LOOP_XYZE_N(i) {
const bool in = (i < esteppers + XYZ);
if (!validating) LOOP_DISTINCT_AXES(i) {
const bool in = (i < esteppers + LINEAR_AXES);
planner.settings.max_acceleration_mm_per_s2[i] = in ? tmp1[i] : pgm_read_dword(&_DMA[ALIM(i, _DMA)]);
planner.settings.axis_steps_per_mm[i] = in ? tmp2[i] : pgm_read_float(&_DASU[ALIM(i, _DASU)]);
planner.settings.max_feedrate_mm_s[i] = in ? tmp3[i] : pgm_read_float(&_DMF[ALIM(i, _DMF)]);
@ -1540,7 +1539,7 @@ void MarlinSettings::postprocess() {
EEPROM_READ(dummyf);
#endif
#else
for (uint8_t q = XYZE; q--;) EEPROM_READ(dummyf);
for (uint8_t q = LOGICAL_AXES; q--;) EEPROM_READ(dummyf);
#endif
EEPROM_READ(TERN(CLASSIC_JERK, dummyf, planner.junction_deviation_mm));
@ -2582,7 +2581,7 @@ void MarlinSettings::postprocess() {
* M502 - Reset Configuration
*/
void MarlinSettings::reset() {
LOOP_XYZE_N(i) {
LOOP_DISTINCT_AXES(i) {
planner.settings.max_acceleration_mm_per_s2[i] = pgm_read_dword(&_DMA[ALIM(i, _DMA)]);
planner.settings.axis_steps_per_mm[i] = pgm_read_float(&_DASU[ALIM(i, _DASU)]);
planner.settings.max_feedrate_mm_s[i] = pgm_read_float(&_DMF[ALIM(i, _DMF)]);
@ -2706,7 +2705,7 @@ void MarlinSettings::reset() {
constexpr float dpo[] = NOZZLE_TO_PROBE_OFFSET;
static_assert(COUNT(dpo) == 3, "NOZZLE_TO_PROBE_OFFSET must contain offsets for X, Y, and Z.");
#if HAS_PROBE_XY_OFFSET
LOOP_XYZ(a) probe.offset[a] = dpo[a];
LOOP_LINEAR_AXES(a) probe.offset[a] = dpo[a];
#else
probe.offset.set(0, 0, dpo[Z_AXIS]);
#endif
@ -3856,7 +3855,7 @@ void MarlinSettings::reset() {
);
#elif HAS_MOTOR_CURRENT_SPI
SERIAL_ECHOPGM(" M907"); // SPI-based has 5 values:
LOOP_XYZE(q) { // X Y Z E (map to X Y Z E0 by default)
LOOP_LOGICAL_AXES(q) { // X Y Z E (map to X Y Z E0 by default)
SERIAL_CHAR(' ', axis_codes[q]);
SERIAL_ECHO(stepper.motor_current_setting[q]);
}

2
Marlin/src/module/stepper.h

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

2
Marlin/src/module/tool_change.cpp

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

Loading…
Cancel
Save