diff --git a/Marlin/src/HAL/AVR/pinsDebug.h b/Marlin/src/HAL/AVR/pinsDebug.h index 6bf9f33a0c..55fddb05b8 100644 --- a/Marlin/src/HAL/AVR/pinsDebug.h +++ b/Marlin/src/HAL/AVR/pinsDebug.h @@ -38,7 +38,7 @@ // portModeRegister takes a different argument #define digitalPinToTimer_DEBUG(p) digitalPinToTimer(p) #define digitalPinToBitMask_DEBUG(p) digitalPinToBitMask(p) - #define digitalPinToPort_DEBUG(p) digitalPinToPort_Teensy(p) + #define digitalPinToPort_DEBUG(p) digitalPinToPort(p) #define GET_PINMODE(pin) (*portModeRegister(pin) & digitalPinToBitMask_DEBUG(pin)) #elif AVR_ATmega2560_FAMILY_PLUS_70 // So we can access/display all the pins on boards using more than 70 diff --git a/Marlin/src/HAL/LPC1768/inc/SanityCheck.h b/Marlin/src/HAL/LPC1768/inc/SanityCheck.h index a6286ba6f4..46a876a836 100644 --- a/Marlin/src/HAL/LPC1768/inc/SanityCheck.h +++ b/Marlin/src/HAL/LPC1768/inc/SanityCheck.h @@ -144,7 +144,7 @@ static_assert(DISABLED(BAUD_RATE_GCODE), "BAUD_RATE_GCODE is not yet supported o #error "Serial port pins (2) conflict with Z4 pins!" #elif ANY_RX(2, X_DIR_PIN, Y_DIR_PIN) #error "Serial port pins (2) conflict with other pins!" - #elif Y_HOME_DIR < 0 && IS_TX2(Y_STOP_PIN) + #elif Y_HOME_TO_MIN && IS_TX2(Y_STOP_PIN) #error "Serial port pins (2) conflict with Y endstop pin!" #elif HAS_CUSTOM_PROBE_PIN && IS_TX2(Z_MIN_PROBE_PIN) #error "Serial port pins (2) conflict with probe pin!" diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index 5c43dc8b62..38bfd3dd23 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -1492,7 +1492,7 @@ void setup() { #endif #if HAS_TRINAMIC_CONFIG && DISABLED(PSU_DEFAULT_OFF) - SETUP_RUN(test_tmc_connection(true, true, true, true)); + SETUP_RUN(test_tmc_connection()); #endif #if HAS_DRIVER_SAFE_POWER_PROTECT diff --git a/Marlin/src/core/debug_section.h b/Marlin/src/core/debug_section.h index 2862d35af1..ef1511e6f0 100644 --- a/Marlin/src/core/debug_section.h +++ b/Marlin/src/core/debug_section.h @@ -44,6 +44,6 @@ private: SERIAL_ECHOPGM_P(the_msg); } SERIAL_CHAR(' '); - print_xyz(current_position); + print_pos(current_position); } }; diff --git a/Marlin/src/core/language.h b/Marlin/src/core/language.h index de29535f87..df6821cb1c 100644 --- a/Marlin/src/core/language.h +++ b/Marlin/src/core/language.h @@ -140,25 +140,7 @@ #define STR_RESEND "Resend: " #define STR_UNKNOWN_COMMAND "Unknown command: \"" #define STR_ACTIVE_EXTRUDER "Active Extruder: " -#define STR_X_MIN "x_min" -#define STR_X_MAX "x_max" -#define STR_X2_MIN "x2_min" -#define STR_X2_MAX "x2_max" -#define STR_Y_MIN "y_min" -#define STR_Y_MAX "y_max" -#define STR_Y2_MIN "y2_min" -#define STR_Y2_MAX "y2_max" -#define STR_Z_MIN "z_min" -#define STR_Z_MAX "z_max" -#define STR_Z2_MIN "z2_min" -#define STR_Z2_MAX "z2_max" -#define STR_Z3_MIN "z3_min" -#define STR_Z3_MAX "z3_max" -#define STR_Z4_MIN "z4_min" -#define STR_Z4_MAX "z4_max" -#define STR_Z_PROBE "z_probe" -#define STR_PROBE_EN "probe_en" -#define STR_FILAMENT_RUNOUT_SENSOR "filament" + #define STR_PROBE_OFFSET "Probe Offset" #define STR_SKEW_MIN "min_skew_factor: " #define STR_SKEW_MAX "max_skew_factor: " @@ -277,14 +259,30 @@ #define STR_REMINDER_SAVE_SETTINGS "Remember to save!" #define STR_PASSWORD_SET "Password is " -// LCD Menu Messages - -#define LANGUAGE_DATA_INCL_(M) STRINGIFY_(fontdata/langdata_##M.h) -#define LANGUAGE_DATA_INCL(M) LANGUAGE_DATA_INCL_(M) - -#define LANGUAGE_INCL_(M) STRINGIFY_(../lcd/language/language_##M.h) -#define LANGUAGE_INCL(M) LANGUAGE_INCL_(M) +// +// Endstop Names used by Endstops::report_states +// +#define STR_X_MIN "x_min" +#define STR_X_MAX "x_max" +#define STR_X2_MIN "x2_min" +#define STR_X2_MAX "x2_max" +#define STR_Y_MIN "y_min" +#define STR_Y_MAX "y_max" +#define STR_Y2_MIN "y2_min" +#define STR_Y2_MAX "y2_max" +#define STR_Z_MIN "z_min" +#define STR_Z_MAX "z_max" +#define STR_Z2_MIN "z2_min" +#define STR_Z2_MAX "z2_max" +#define STR_Z3_MIN "z3_min" +#define STR_Z3_MAX "z3_max" +#define STR_Z4_MIN "z4_min" +#define STR_Z4_MAX "z4_max" +#define STR_Z_PROBE "z_probe" +#define STR_PROBE_EN "probe_en" +#define STR_FILAMENT_RUNOUT_SENSOR "filament" +// General axis names #define STR_X "X" #define STR_Y "Y" #define STR_Z "Z" @@ -386,6 +384,14 @@ #define LCD_STR_E6 "E" LCD_STR_N6 #define LCD_STR_E7 "E" LCD_STR_N7 +// Include localized LCD Menu Messages + +#define LANGUAGE_DATA_INCL_(M) STRINGIFY_(fontdata/langdata_##M.h) +#define LANGUAGE_DATA_INCL(M) LANGUAGE_DATA_INCL_(M) + +#define LANGUAGE_INCL_(M) STRINGIFY_(../lcd/language/language_##M.h) +#define LANGUAGE_INCL(M) LANGUAGE_INCL_(M) + // Use superscripts, if possible. Evaluated at point of use. #define SUPERSCRIPT_TWO TERN(NOT_EXTENDED_ISO10646_1_5X7, "^2", "²") #define SUPERSCRIPT_THREE TERN(NOT_EXTENDED_ISO10646_1_5X7, "^3", "³") diff --git a/Marlin/src/core/serial.cpp b/Marlin/src/core/serial.cpp index 28442594ce..b4184fcd62 100644 --- a/Marlin/src/core/serial.cpp +++ b/Marlin/src/core/serial.cpp @@ -101,7 +101,7 @@ void print_bin(uint16_t val) { } } -void print_xyz(const_float_t x, const_float_t y, const_float_t z, PGM_P const prefix/*=nullptr*/, PGM_P const suffix/*=nullptr*/) { +void print_pos(const_float_t x, const_float_t y, const_float_t z, PGM_P const prefix/*=nullptr*/, PGM_P const suffix/*=nullptr*/) { if (prefix) serialprintPGM(prefix); SERIAL_ECHOPAIR_P(SP_X_STR, x, SP_Y_STR, y, SP_Z_STR, z); if (suffix) serialprintPGM(suffix); else SERIAL_EOL(); diff --git a/Marlin/src/core/serial.h b/Marlin/src/core/serial.h index 5c08be5c92..74b96dbb64 100644 --- a/Marlin/src/core/serial.h +++ b/Marlin/src/core/serial.h @@ -310,11 +310,11 @@ void serialprint_truefalse(const bool tf); void serial_spaces(uint8_t count); void print_bin(const uint16_t val); -void print_xyz(const_float_t x, const_float_t y, const_float_t z, PGM_P const prefix=nullptr, PGM_P const suffix=nullptr); +void print_pos(const_float_t x, const_float_t y, const_float_t z, PGM_P const prefix=nullptr, PGM_P const suffix=nullptr); -inline void print_xyz(const xyz_pos_t &xyz, PGM_P const prefix=nullptr, PGM_P const suffix=nullptr) { - print_xyz(xyz.x, xyz.y, xyz.z, prefix, suffix); +inline void print_pos(const xyz_pos_t &xyz, PGM_P const prefix=nullptr, PGM_P const suffix=nullptr) { + print_pos(xyz.x, xyz.y, xyz.z, prefix, suffix); } -#define SERIAL_POS(SUFFIX,VAR) do { print_xyz(VAR, PSTR(" " STRINGIFY(VAR) "="), PSTR(" : " SUFFIX "\n")); }while(0) -#define SERIAL_XYZ(PREFIX,V...) do { print_xyz(V, PSTR(PREFIX), nullptr); }while(0) +#define SERIAL_POS(SUFFIX,VAR) do { print_pos(VAR, PSTR(" " STRINGIFY(VAR) "="), PSTR(" : " SUFFIX "\n")); }while(0) +#define SERIAL_XYZ(PREFIX,V...) do { print_pos(V, PSTR(PREFIX), nullptr); }while(0) diff --git a/Marlin/src/core/types.h b/Marlin/src/core/types.h index 79a79b739b..b7ae85eb2e 100644 --- a/Marlin/src/core/types.h +++ b/Marlin/src/core/types.h @@ -29,6 +29,16 @@ class __FlashStringHelper; typedef const __FlashStringHelper *progmem_str; +// +// Conditional type assignment magic. For example... +// +// typename IF<(MYOPT==12), int, float>::type myvar; +// +template +struct IF { typedef R type; }; +template +struct IF { typedef L type; }; + // // Enumerated axis indices // @@ -37,35 +47,23 @@ typedef const __FlashStringHelper *progmem_str; // - 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_ENUM = 0xFE, NO_AXIS_ENUM = 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) - -// -// Conditional type assignment magic. For example... -// -// typename IF<(MYOPT==12), int, float>::type myvar; -// -template -struct IF { typedef R type; }; -template -struct IF { typedef L type; }; +#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 copy() const { return *this; } FI XYZEval 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)) diff --git a/Marlin/src/core/utility.cpp b/Marlin/src/core/utility.cpp index 3d7897f95a..f4cdef43c8 100644 --- a/Marlin/src/core/utility.cpp +++ b/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); } diff --git a/Marlin/src/feature/backlash.cpp b/Marlin/src/feature/backlash.cpp index 610cfcb565..5ab95d1577 100644 --- a/Marlin/src/feature/backlash.cpp +++ b/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); diff --git a/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp b/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp index 6f1425b60c..b5773b0d46 100644 --- a/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp +++ b/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp @@ -581,7 +581,7 @@ void unified_bed_leveling::G29() { // use cases for the users. So we can wait and see what to do with it. // - if (parser.seen_test('K')) // Kompare Current Mesh Data to Specified Stored Mesh + if (parser.seen('K')) // Kompare Current Mesh Data to Specified Stored Mesh g29_compare_current_mesh_to_stored_mesh(); #endif // UBL_DEVEL_DEBUGGING diff --git a/Marlin/src/feature/caselight.cpp b/Marlin/src/feature/caselight.cpp index fb0f6e3bee..5a4e2b2579 100644 --- a/Marlin/src/feature/caselight.cpp +++ b/Marlin/src/feature/caselight.cpp @@ -44,10 +44,6 @@ bool CaseLight::on = CASE_LIGHT_DEFAULT_ON; LEDColor CaseLight::color = { init_case_light[0], init_case_light[1], init_case_light[2], TERN_(HAS_WHITE_LED, init_case_light[3]) }; #endif -#ifndef INVERT_CASE_LIGHT - #define INVERT_CASE_LIGHT false -#endif - void CaseLight::update(const bool sflag) { #if CASELIGHT_USES_BRIGHTNESS /** @@ -64,7 +60,7 @@ void CaseLight::update(const bool sflag) { if (sflag && on) brightness = brightness_sav; // Restore last brightness for M355 S1 - const uint8_t i = on ? brightness : 0, n10ct = INVERT_CASE_LIGHT ? 255 - i : i; + const uint8_t i = on ? brightness : 0, n10ct = ENABLED(INVERT_CASE_LIGHT) ? 255 - i : i; UNUSED(n10ct); #endif @@ -86,7 +82,7 @@ void CaseLight::update(const bool sflag) { else #endif { - const bool s = on ? !INVERT_CASE_LIGHT : INVERT_CASE_LIGHT; + const bool s = on ? TERN(INVERT_CASE_LIGHT, LOW, HIGH) : TERN(INVERT_CASE_LIGHT, HIGH, LOW); WRITE(CASE_LIGHT_PIN, s ? HIGH : LOW); } diff --git a/Marlin/src/feature/cooler.h b/Marlin/src/feature/cooler.h index 1e24c729f3..9bd98d0b10 100644 --- a/Marlin/src/feature/cooler.h +++ b/Marlin/src/feature/cooler.h @@ -78,10 +78,8 @@ public: // Get the total flow (in liters per minute) since the last reading static void calc_flowrate() { - //flowmeter_interrupt_disable(); - // const uint16_t pulses = flowpulses; - //flowmeter_interrupt_enable(); - flowrate = flowpulses * 60.0f * (1000.0f / (FLOWMETER_INTERVAL)) * (1000.0f / (FLOWMETER_PPL)); + // flowrate = (litres) * (seconds) = litres per minute + flowrate = (flowpulses / (float)FLOWMETER_PPL) * ((1000.0f / (float)FLOWMETER_INTERVAL) * 60.0f); flowpulses = 0; } diff --git a/Marlin/src/feature/dac/dac_mcp4728.cpp b/Marlin/src/feature/dac/dac_mcp4728.cpp index 2b57037d99..ddbaced086 100644 --- a/Marlin/src/feature/dac/dac_mcp4728.cpp +++ b/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])); } diff --git a/Marlin/src/feature/dac/stepper_dac.cpp b/Marlin/src/feature/dac/stepper_dac.cpp index 5170a35511..1cb0813daa 100644 --- a/Marlin/src/feature/dac/stepper_dac.cpp +++ b/Marlin/src/feature/dac/stepper_dac.cpp @@ -51,7 +51,7 @@ int StepperDAC::init() { mcp4728.setVref_all(DAC_STEPPER_VREF); mcp4728.setGain_all(DAC_STEPPER_GAIN); - if (mcp4728.getDrvPct(0) < 1 || mcp4728.getDrvPct(1) < 1 || mcp4728.getDrvPct(2) < 1 || mcp4728.getDrvPct(3) < 1 ) { + if (mcp4728.getDrvPct(0) < 1 || mcp4728.getDrvPct(1) < 1 || mcp4728.getDrvPct(2) < 1 || mcp4728.getDrvPct(3) < 1) { mcp4728.setDrvPct(dac_channel_pct); mcp4728.eepromWrite(); } @@ -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); } diff --git a/Marlin/src/feature/encoder_i2c.cpp b/Marlin/src/feature/encoder_i2c.cpp index b3265b2c59..d6c88613fd 100644 --- a/Marlin/src/feature/encoder_i2c.cpp +++ b/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); diff --git a/Marlin/src/feature/joystick.cpp b/Marlin/src/feature/joystick.cpp index 2cc61ec5a3..d8e6cef3b6 100644 --- a/Marlin/src/feature/joystick.cpp +++ b/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]); } diff --git a/Marlin/src/feature/powerloss.cpp b/Marlin/src/feature/powerloss.cpp index 3764af13d0..a512022320 100644 --- a/Marlin/src/feature/powerloss.cpp +++ b/Marlin/src/feature/powerloss.cpp @@ -197,7 +197,7 @@ void PrintJobRecovery::save(const bool force/*=false*/, const float zraise/*=POW #endif #endif - #if EXTRUDERS + #if HAS_EXTRUDERS HOTEND_LOOP() info.target_temperature[e] = thermalManager.degTargetHotend(e); #endif @@ -375,7 +375,7 @@ void PrintJobRecovery::resume() { gcode.process_subcommands_now_P(PSTR("G92.9E0")); // Reset E to 0 - #if Z_HOME_DIR > 0 + #if Z_HOME_TO_MAX float z_now = z_raised; @@ -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]); } diff --git a/Marlin/src/feature/tmc_util.cpp b/Marlin/src/feature/tmc_util.cpp index a4f71414a6..9c4fbf08df 100644 --- a/Marlin/src/feature/tmc_util.cpp +++ b/Marlin/src/feature/tmc_util.cpp @@ -211,7 +211,7 @@ SERIAL_PRINTLN(data.drv_status, HEX); if (data.is_ot) SERIAL_ECHOLNPGM("overtemperature"); if (data.is_s2g) SERIAL_ECHOLNPGM("coil short circuit"); - TERN_(TMC_DEBUG, tmc_report_all(true, true, true, true)); + TERN_(TMC_DEBUG, tmc_report_all()); kill(PSTR("Driver error")); } #endif @@ -889,7 +889,7 @@ * M122 report functions */ - void tmc_report_all(bool print_x, const bool print_y, const bool print_z, const bool print_e) { + void tmc_report_all(const bool print_x/*=true*/, const bool print_y/*=true*/, const bool print_z/*=true*/, const bool print_e/*=true*/) { #define TMC_REPORT(LABEL, ITEM) do{ SERIAL_ECHOPGM(LABEL); tmc_debug_loop(ITEM, print_x, print_y, print_z, print_e); }while(0) #define DRV_REPORT(LABEL, ITEM) do{ SERIAL_ECHOPGM(LABEL); drv_status_loop(ITEM, print_x, print_y, print_z, print_e); }while(0) TMC_REPORT("\t", TMC_CODES); @@ -1214,7 +1214,7 @@ static bool test_connection(TMC &st) { return test_result; } -void test_tmc_connection(const bool test_x, const bool test_y, const bool test_z, const bool test_e) { +void test_tmc_connection(const bool test_x/*=true*/, const bool test_y/*=true*/, const bool test_z/*=true*/, const bool test_e/*=true*/) { uint8_t axis_connection = 0; if (test_x) { diff --git a/Marlin/src/feature/tmc_util.h b/Marlin/src/feature/tmc_util.h index 1767313ba2..a0e07ab8a8 100644 --- a/Marlin/src/feature/tmc_util.h +++ b/Marlin/src/feature/tmc_util.h @@ -341,13 +341,13 @@ void tmc_print_current(TMC &st) { #endif void monitor_tmc_drivers(); -void test_tmc_connection(const bool test_x, const bool test_y, const bool test_z, const bool test_e); +void test_tmc_connection(const bool test_x=true, const bool test_y=true, const bool test_z=true, const bool test_e=true); #if ENABLED(TMC_DEBUG) #if ENABLED(MONITOR_DRIVER_STATUS) void tmc_set_report_interval(const uint16_t update_interval); #endif - void tmc_report_all(const bool print_x, const bool print_y, const bool print_z, const bool print_e); + void tmc_report_all(const bool print_x=true, const bool print_y=true, const bool print_z=true, const bool print_e=true); void tmc_get_registers(const bool print_x, const bool print_y, const bool print_z, const bool print_e); #endif diff --git a/Marlin/src/gcode/calibrate/G28.cpp b/Marlin/src/gcode/calibrate/G28.cpp index 92bbb8e6c5..aacfcfa42f 100644 --- a/Marlin/src/gcode/calibrate/G28.cpp +++ b/Marlin/src/gcode/calibrate/G28.cpp @@ -73,7 +73,7 @@ current_position.set(0.0, 0.0); sync_plan_position(); - const int x_axis_home_dir = x_home_dir(active_extruder); + const int x_axis_home_dir = TOOL_X_HOME_DIR(active_extruder); const float mlx = max_length(X_AXIS), mly = max_length(Y_AXIS), @@ -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(); diff --git a/Marlin/src/gcode/calibrate/G33.cpp b/Marlin/src/gcode/calibrate/G33.cpp index a8de519335..14ac53aeba 100644 --- a/Marlin/src/gcode/calibrate/G33.cpp +++ b/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); diff --git a/Marlin/src/gcode/calibrate/G425.cpp b/Marlin/src/gcode/calibrate/G425.cpp index 0918bc9d4f..2fb4502267 100644 --- a/Marlin/src/gcode/calibrate/G425.cpp +++ b/Marlin/src/gcode/calibrate/G425.cpp @@ -194,16 +194,20 @@ float measuring_movement(const AxisEnum axis, const int dir, const bool stop_sta inline float measure(const AxisEnum axis, const int dir, const bool stop_state, float * const backlash_ptr, const float uncertainty) { const bool fast = uncertainty == CALIBRATION_MEASUREMENT_UNKNOWN; - // Save position - destination = current_position; - const float start_pos = destination[axis]; + // Save the current position of the specified axis + const float start_pos = current_position[axis]; + + // Take a measurement. Only the specified axis will be affected. const float measured_pos = measuring_movement(axis, dir, stop_state, fast); + // Measure backlash if (backlash_ptr && !fast) { const float release_pos = measuring_movement(axis, -dir, !stop_state, fast); *backlash_ptr = ABS(release_pos - measured_pos); } - // Return to starting position + + // Move back to the starting position + destination = current_position; destination[axis] = start_pos; do_blocking_move_to(destination, MMM_TO_MMS(CALIBRATION_FEEDRATE_TRAVEL)); return measured_pos; @@ -235,12 +239,12 @@ inline void probe_side(measurements_t &m, const float uncertainty, const side_t } #endif #if AXIS_CAN_CALIBRATE(X) + case RIGHT: dir = -1; case LEFT: axis = X_AXIS; break; - case RIGHT: axis = X_AXIS; dir = -1; break; #endif #if AXIS_CAN_CALIBRATE(Y) + case BACK: dir = -1; case FRONT: axis = Y_AXIS; break; - case BACK: axis = Y_AXIS; dir = -1; break; #endif default: return; } @@ -303,16 +307,8 @@ inline void probe_sides(measurements_t &m, const float uncertainty) { // The difference between the known and the measured location // of the calibration object is the positional error - m.pos_error.x = (0 - #if HAS_X_CENTER - + true_center.x - m.obj_center.x - #endif - ); - m.pos_error.y = (0 - #if HAS_Y_CENTER - + true_center.y - m.obj_center.y - #endif - ); + m.pos_error.x = TERN0(HAS_X_CENTER, true_center.x - m.obj_center.x); + m.pos_error.y = TERN0(HAS_Y_CENTER, true_center.y - m.obj_center.y); m.pos_error.z = true_center.z - m.obj_center.z; } @@ -589,12 +585,12 @@ void GcodeSuite::G425() { SET_SOFT_ENDSTOP_LOOSE(true); measurements_t m; - float uncertainty = parser.seenval('U') ? parser.value_float() : CALIBRATION_MEASUREMENT_UNCERTAIN; + const float uncertainty = parser.floatval('U', CALIBRATION_MEASUREMENT_UNCERTAIN); - if (parser.seen('B')) + if (parser.seen_test('B')) calibrate_backlash(m, uncertainty); - else if (parser.seen('T')) - calibrate_toolhead(m, uncertainty, parser.has_value() ? parser.value_int() : active_extruder); + else if (parser.seen_test('T')) + calibrate_toolhead(m, uncertainty, parser.intval('T', active_extruder)); #if ENABLED(CALIBRATION_REPORTING) else if (parser.seen('V')) { probe_sides(m, uncertainty); diff --git a/Marlin/src/gcode/calibrate/M425.cpp b/Marlin/src/gcode/calibrate/M425.cpp index 40441ac08d..432144f491 100644 --- a/Marlin/src/gcode/calibrate/M425.cpp +++ b/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))); } } diff --git a/Marlin/src/gcode/calibrate/M666.cpp b/Marlin/src/gcode/calibrate/M666.cpp index 75becf13f3..a3a48cd3fc 100644 --- a/Marlin/src/gcode/calibrate/M666.cpp +++ b/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]); } } } diff --git a/Marlin/src/gcode/calibrate/M852.cpp b/Marlin/src/gcode/calibrate/M852.cpp index e52f03b86c..6f1e984bc3 100644 --- a/Marlin/src/gcode/calibrate/M852.cpp +++ b/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_ENUM); sync_plan_position(); report_current_position(); } diff --git a/Marlin/src/gcode/config/M200-M205.cpp b/Marlin/src/gcode/config/M200-M205.cpp index cb17fc45a6..06751f41c4 100644 --- a/Marlin/src/gcode/config/M200-M205.cpp +++ b/Marlin/src/gcode/config/M200-M205.cpp @@ -86,8 +86,8 @@ void GcodeSuite::M201() { if (parser.seenval('G')) planner.xy_freq_min_speed_factor = constrain(parser.value_float(), 1, 100) / 100; #endif - LOOP_XYZE(i) { - if (parser.seen(axis_codes[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,8 +104,8 @@ void GcodeSuite::M203() { const int8_t target_extruder = get_target_extruder_from_command(); if (target_extruder < 0) return; - LOOP_XYZE(i) - if (parser.seen(axis_codes[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)); } @@ -147,24 +147,14 @@ void GcodeSuite::M204() { * J = Junction Deviation (mm) (If not using CLASSIC_JERK) */ void GcodeSuite::M205() { - #if HAS_JUNCTION_DEVIATION - #define J_PARAM "J" - #else - #define J_PARAM - #endif - #if HAS_CLASSIC_JERK - #define XYZE_PARAM "XYZE" - #else - #define XYZE_PARAM - #endif - if (!parser.seen("BST" J_PARAM XYZE_PARAM)) return; + if (!parser.seen("BST" TERN_(HAS_JUNCTION_DEVIATION, "J") TERN_(HAS_CLASSIC_JERK, "XYZE"))) return; //planner.synchronize(); - if (parser.seen('B')) planner.settings.min_segment_time_us = parser.value_ulong(); - if (parser.seen('S')) planner.settings.min_feedrate_mm_s = parser.value_linear_units(); - if (parser.seen('T')) planner.settings.min_travel_feedrate_mm_s = parser.value_linear_units(); + if (parser.seenval('B')) planner.settings.min_segment_time_us = parser.value_ulong(); + if (parser.seenval('S')) planner.settings.min_feedrate_mm_s = parser.value_linear_units(); + if (parser.seenval('T')) planner.settings.min_travel_feedrate_mm_s = parser.value_linear_units(); #if HAS_JUNCTION_DEVIATION - if (parser.seen('J')) { + if (parser.seenval('J')) { const float junc_dev = parser.value_linear_units(); if (WITHIN(junc_dev, 0.01f, 0.3f)) { planner.junction_deviation_mm = junc_dev; @@ -175,9 +165,9 @@ void GcodeSuite::M205() { } #endif #if HAS_CLASSIC_JERK - if (parser.seen('X')) planner.set_max_jerk(X_AXIS, parser.value_linear_units()); - if (parser.seen('Y')) planner.set_max_jerk(Y_AXIS, parser.value_linear_units()); - if (parser.seen('Z')) { + if (parser.seenval('X')) planner.set_max_jerk(X_AXIS, parser.value_linear_units()); + if (parser.seenval('Y')) planner.set_max_jerk(Y_AXIS, parser.value_linear_units()); + if (parser.seenval('Z')) { planner.set_max_jerk(Z_AXIS, parser.value_linear_units()); #if HAS_MESH && DISABLED(LIMITED_JERK_EDITING) if (planner.max_jerk.z <= 0.1f) @@ -185,7 +175,7 @@ void GcodeSuite::M205() { #endif } #if HAS_CLASSIC_E_JERK - if (parser.seen('E')) planner.set_max_jerk(E_AXIS, parser.value_linear_units()); + if (parser.seenval('E')) planner.set_max_jerk(E_AXIS, parser.value_linear_units()); #endif #endif } diff --git a/Marlin/src/gcode/config/M221.cpp b/Marlin/src/gcode/config/M221.cpp index 7ba22d1901..e380bfb1c7 100644 --- a/Marlin/src/gcode/config/M221.cpp +++ b/Marlin/src/gcode/config/M221.cpp @@ -23,7 +23,7 @@ #include "../gcode.h" #include "../../module/planner.h" -#if EXTRUDERS +#if HAS_EXTRUDERS /** * M221: Set extrusion percentage (M221 T0 S95) diff --git a/Marlin/src/gcode/config/M92.cpp b/Marlin/src/gcode/config/M92.cpp index bdb95db8d6..06c47b8253 100644 --- a/Marlin/src/gcode/config/M92.cpp +++ b/Marlin/src/gcode/config/M92.cpp @@ -42,7 +42,7 @@ void report_M92(const bool echo=true, const int8_t e=-1) { } #endif - UNUSED_E(e); + UNUSED(e); } /** @@ -64,13 +64,10 @@ void GcodeSuite::M92() { if (target_extruder < 0) return; // No arguments? Show M92 report. - if (!parser.seen("XYZE" - #if ENABLED(MAGIC_NUMBERS_GCODE) - "HL" - #endif - )) return report_M92(true, target_extruder); + 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))); diff --git a/Marlin/src/gcode/control/M17_M18_M84.cpp b/Marlin/src/gcode/control/M17_M18_M84.cpp index b35b465331..f02508a901 100644 --- a/Marlin/src/gcode/control/M17_M18_M84.cpp +++ b/Marlin/src/gcode/control/M17_M18_M84.cpp @@ -34,10 +34,10 @@ */ void GcodeSuite::M17() { if (parser.seen("XYZE")) { - if (parser.seen('X')) ENABLE_AXIS_X(); - if (parser.seen('Y')) ENABLE_AXIS_Y(); - if (parser.seen('Z')) ENABLE_AXIS_Z(); - if (TERN0(HAS_E_STEPPER_ENABLE, parser.seen('E'))) enable_e_steppers(); + if (parser.seen_test('X')) ENABLE_AXIS_X(); + if (parser.seen_test('Y')) ENABLE_AXIS_Y(); + if (parser.seen_test('Z')) ENABLE_AXIS_Z(); + if (TERN0(HAS_E_STEPPER_ENABLE, parser.seen_test('E'))) enable_e_steppers(); } else { LCD_MESSAGEPGM(MSG_NO_MOVE); @@ -56,10 +56,10 @@ void GcodeSuite::M18_M84() { else { if (parser.seen("XYZE")) { planner.synchronize(); - if (parser.seen('X')) DISABLE_AXIS_X(); - if (parser.seen('Y')) DISABLE_AXIS_Y(); - if (parser.seen('Z')) DISABLE_AXIS_Z(); - if (TERN0(HAS_E_STEPPER_ENABLE, parser.seen('E'))) disable_e_steppers(); + if (parser.seen_test('X')) DISABLE_AXIS_X(); + if (parser.seen_test('Y')) DISABLE_AXIS_Y(); + if (parser.seen_test('Z')) DISABLE_AXIS_Z(); + if (TERN0(HAS_E_STEPPER_ENABLE, parser.seen_test('E'))) disable_e_steppers(); } else planner.finish_and_disable(); diff --git a/Marlin/src/gcode/control/M211.cpp b/Marlin/src/gcode/control/M211.cpp index 2049f1eb69..2ba777ba65 100644 --- a/Marlin/src/gcode/control/M211.cpp +++ b/Marlin/src/gcode/control/M211.cpp @@ -39,8 +39,8 @@ void GcodeSuite::M211() { SERIAL_ECHOPGM(STR_SOFT_ENDSTOPS); if (parser.seen('S')) soft_endstop._enabled = parser.value_bool(); serialprint_onoff(soft_endstop._enabled); - print_xyz(l_soft_min, PSTR(STR_SOFT_MIN), PSTR(" ")); - print_xyz(l_soft_max, PSTR(STR_SOFT_MAX)); + print_pos(l_soft_min, PSTR(STR_SOFT_MIN), PSTR(" ")); + print_pos(l_soft_max, PSTR(STR_SOFT_MAX)); } #endif diff --git a/Marlin/src/gcode/control/M350_M351.cpp b/Marlin/src/gcode/control/M350_M351.cpp index 463bd2ad58..a92238e4bb 100644 --- a/Marlin/src/gcode/control/M350_M351.cpp +++ b/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; } diff --git a/Marlin/src/gcode/control/M605.cpp b/Marlin/src/gcode/control/M605.cpp index e0c79f0e54..ac84ac6217 100644 --- a/Marlin/src/gcode/control/M605.cpp +++ b/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(); diff --git a/Marlin/src/gcode/feature/L6470/M906.cpp b/Marlin/src/gcode/feature/L6470/M906.cpp index 3638fae45b..87614e9c73 100644 --- a/Marlin/src/gcode/feature/L6470/M906.cpp +++ b/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; diff --git a/Marlin/src/gcode/feature/digipot/M907-M910.cpp b/Marlin/src/gcode/feature/digipot/M907-M910.cpp index e463666207..ee9801eda9 100644 --- a/Marlin/src/gcode/feature/digipot/M907-M910.cpp +++ b/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? 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 } diff --git a/Marlin/src/gcode/feature/pause/G61.cpp b/Marlin/src/gcode/feature/pause/G61.cpp index bb11464902..a6d7cb3094 100644 --- a/Marlin/src/gcode/feature/pause/G61.cpp +++ b/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(); diff --git a/Marlin/src/gcode/feature/trinamic/M122.cpp b/Marlin/src/gcode/feature/trinamic/M122.cpp index c338e48df4..054d145c8c 100644 --- a/Marlin/src/gcode/feature/trinamic/M122.cpp +++ b/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(); diff --git a/Marlin/src/gcode/feature/trinamic/M569.cpp b/Marlin/src/gcode/feature/trinamic/M569.cpp index a92812004f..8f1c0ed819 100644 --- a/Marlin/src/gcode/feature/trinamic/M569.cpp +++ b/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) diff --git a/Marlin/src/gcode/feature/trinamic/M906.cpp b/Marlin/src/gcode/feature/trinamic/M906.cpp index e834ebd67d..86e0cd2987 100644 --- a/Marlin/src/gcode/feature/trinamic/M906.cpp +++ b/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: diff --git a/Marlin/src/gcode/feature/trinamic/M911-M914.cpp b/Marlin/src/gcode/feature/trinamic/M911-M914.cpp index 8c840db5bf..c4b4a8772e 100644 --- a/Marlin/src/gcode/feature/trinamic/M911-M914.cpp +++ b/Marlin/src/gcode/feature/trinamic/M911-M914.cpp @@ -35,10 +35,19 @@ #define M91x_USE(ST) (AXIS_DRIVER_TYPE(ST, TMC2130) || AXIS_DRIVER_TYPE(ST, TMC2160) || AXIS_DRIVER_TYPE(ST, TMC2208) || AXIS_DRIVER_TYPE(ST, TMC2209) || AXIS_DRIVER_TYPE(ST, TMC2660) || AXIS_DRIVER_TYPE(ST, TMC5130) || AXIS_DRIVER_TYPE(ST, TMC5160)) #define M91x_USE_E(N) (E_STEPPERS > N && M91x_USE(E##N)) - #define M91x_SOME_X (M91x_USE(X) || M91x_USE(X2)) - #define M91x_SOME_Y (M91x_USE(Y) || M91x_USE(Y2)) - #define M91x_SOME_Z (M91x_USE(Z) || M91x_USE(Z2) || M91x_USE(Z3) || M91x_USE(Z4)) - #define M91x_SOME_E (M91x_USE_E(0) || M91x_USE_E(1) || M91x_USE_E(2) || M91x_USE_E(3) || M91x_USE_E(4) || M91x_USE_E(5) || M91x_USE_E(6) || M91x_USE_E(7)) + #if M91x_USE(X) || M91x_USE(X2) + #define M91x_SOME_X 1 + #endif + #if M91x_USE(Y) || M91x_USE(Y2) + #define M91x_SOME_Y 1 + #endif + #if M91x_USE(Z) || M91x_USE(Z2) || M91x_USE(Z3) || M91x_USE(Z4) + #define M91x_SOME_Z 1 + #endif + + #if M91x_USE_E(0) || M91x_USE_E(1) || M91x_USE_E(2) || M91x_USE_E(3) || M91x_USE_E(4) || M91x_USE_E(5) || M91x_USE_E(6) || M91x_USE_E(7) + #define M91x_SOME_E 1 + #endif #if !M91x_SOME_X && !M91x_SOME_Y && !M91x_SOME_Z && !M91x_SOME_E #error "MONITOR_DRIVER_STATUS requires at least one TMC2130, 2160, 2208, 2209, 2660, 5130, or 5160." @@ -112,31 +121,12 @@ * M912 E1 ; clear E1 only */ void GcodeSuite::M912() { - #if M91x_SOME_X - const bool hasX = parser.seen(axis_codes.x); - #else - constexpr bool hasX = false; - #endif - - #if M91x_SOME_Y - const bool hasY = parser.seen(axis_codes.y); - #else - constexpr bool hasY = false; - #endif - - #if M91x_SOME_Z - const bool hasZ = parser.seen(axis_codes.z); - #else - constexpr bool hasZ = false; - #endif - - #if M91x_SOME_E - const bool hasE = parser.seen(axis_codes.e); - #else - constexpr bool hasE = false; - #endif + const bool hasX = TERN0(M91x_SOME_X, parser.seen(axis_codes.x)), + hasY = TERN0(M91x_SOME_Y, parser.seen(axis_codes.y)), + hasZ = TERN0(M91x_SOME_Z, parser.seen(axis_codes.z)), + hasE = TERN0(M91x_SOME_E, parser.seen(axis_codes.e)); - const bool hasNone = !hasX && !hasY && !hasZ && !hasE; + const bool hasNone = !hasE && !hasX && !hasY && !hasZ; #if M91x_SOME_X const int8_t xval = int8_t(parser.byteval(axis_codes.x, 0xFF)); @@ -219,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: @@ -348,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) { diff --git a/Marlin/src/gcode/gcode.cpp b/Marlin/src/gcode/gcode.cpp index 9e3deb9a53..67eec794af 100644 --- a/Marlin/src/gcode/gcode.cpp +++ b/Marlin/src/gcode/gcode.cpp @@ -144,7 +144,7 @@ int8_t GcodeSuite::get_target_e_stepper_from_command() { * - Set the feedrate, if included */ void GcodeSuite::get_destination_from_command() { - xyze_bool_t seen = { false, false, false, false }; + xyze_bool_t seen{false}; #if ENABLED(CANCEL_OBJECTS) const bool &skip_move = cancelable.skipping; @@ -153,8 +153,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]; @@ -277,7 +277,7 @@ void GcodeSuite::dwell(millis_t time) { */ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) { KEEPALIVE_STATE(IN_HANDLER); - + #if ENABLED(MKS_WIFI) serial_index_t port = queue.ring_buffer.command_port(); DEBUG("Gcode: %c %d Port: %d",parser.command_letter,parser.codenum, port.index); @@ -556,7 +556,7 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) { case 100: M100(); break; // M100: Free Memory Report #endif - #if EXTRUDERS + #if HAS_EXTRUDERS case 104: M104(); break; // M104: Set hot end temperature case 109: M109(); break; // M109: Wait for hotend temperature to reach target #endif @@ -612,7 +612,7 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) { #endif #if ENABLED(AUTO_REPORT_POSITION) - case 154: M154(); break; // M155: Set position auto-report interval + case 154: M154(); break; // M154: Set position auto-report interval #endif #if BOTH(AUTO_REPORT_TEMPERATURES, HAS_TEMP_SENSOR) @@ -642,8 +642,10 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) { #endif case 81: M81(); break; // M81: Turn off Power, including Power Supply, if possible - case 82: M82(); break; // M82: Set E axis normal mode (same as other axes) - case 83: M83(); break; // M83: Set E axis relative mode + #if HAS_EXTRUDERS + case 82: M82(); break; // M82: Set E axis normal mode (same as other axes) + case 83: M83(); break; // M83: Set E axis relative mode + #endif case 18: case 84: M18_M84(); break; // M18/M84: Disable Steppers / Set Timeout case 85: M85(); break; // M85: Set inactivity stepper shutdown timeout case 92: M92(); break; // M92: Set the steps-per-unit for one or more axes @@ -730,7 +732,7 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) { case 220: M220(); break; // M220: Set Feedrate Percentage: S ("FR" on your LCD) - #if EXTRUDERS + #if HAS_EXTRUDERS case 221: M221(); break; // M221: Set Flow Percentage #endif diff --git a/Marlin/src/gcode/gcode.h b/Marlin/src/gcode/gcode.h index cdf04cd0f2..6f8568730b 100644 --- a/Marlin/src/gcode/gcode.h +++ b/Marlin/src/gcode/gcode.h @@ -633,10 +633,13 @@ private: #if ENABLED(PSU_CONTROL) static void M80(); #endif - static void M81(); - static void M82(); - static void M83(); + + #if HAS_EXTRUDERS + static void M82(); + static void M83(); + #endif + static void M85(); static void M92(); @@ -644,9 +647,10 @@ private: static void M100(); #endif - #if EXTRUDERS - static void M104(); - static void M109(); + #if HAS_EXTRUDERS + static void M104_M109(const bool isM109); + FORCE_INLINE static void M104() { M104_M109(false); } + FORCE_INLINE static void M109() { M104_M109(true); } #endif static void M105(); @@ -696,8 +700,9 @@ private: #endif #if HAS_HEATED_BED - static void M140(); - static void M190(); + static void M140_M190(const bool isM190); + FORCE_INLINE static void M140() { M140_M190(false); } + FORCE_INLINE static void M190() { M140_M190(true); } #endif #if HAS_HEATED_CHAMBER @@ -776,7 +781,7 @@ private: static void M220(); - #if EXTRUDERS + #if HAS_EXTRUDERS static void M221(); #endif diff --git a/Marlin/src/gcode/geometry/G53-G59.cpp b/Marlin/src/gcode/geometry/G53-G59.cpp index 05bc522768..a5a9f70a8b 100644 --- a/Marlin/src/gcode/geometry/G53-G59.cpp +++ b/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); diff --git a/Marlin/src/gcode/geometry/G92.cpp b/Marlin/src/gcode/geometry/G92.cpp index 30620be6f9..a9970b1e9c 100644 --- a/Marlin/src/gcode/geometry/G92.cpp +++ b/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) diff --git a/Marlin/src/gcode/geometry/M206_M428.cpp b/Marlin/src/gcode/geometry/M206_M428.cpp index ac2420fcc3..e65540eb8c 100644 --- a/Marlin/src/gcode/geometry/M206_M428.cpp +++ b/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); diff --git a/Marlin/src/gcode/host/M114.cpp b/Marlin/src/gcode/host/M114.cpp index e5dc90fb30..2d43d33aa1 100644 --- a/Marlin/src/gcode/host/M114.cpp +++ b/Marlin/src/gcode/host/M114.cpp @@ -34,7 +34,7 @@ #include "../../core/debug_out.h" #endif - void report_xyze(const xyze_pos_t &pos, const uint8_t n=XYZE, const uint8_t precision=3) { + void report_all_axis_pos(const xyze_pos_t &pos, const uint8_t n=XYZE, const uint8_t precision=3) { char str[12]; LOOP_L_N(a, n) { SERIAL_CHAR(' ', axis_codes[a], ':'); @@ -43,12 +43,12 @@ } SERIAL_EOL(); } - inline void report_xyz(const xyze_pos_t &pos) { report_xyze(pos, XYZ); } + inline void report_linear_axis_pos(const xyze_pos_t &pos) { report_all_axis_pos(pos, XYZ); } - void report_xyz(const xyz_pos_t &pos, const uint8_t precision=3) { + 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(); @@ -57,11 +57,11 @@ void report_current_position_detail() { // Position as sent by G-code SERIAL_ECHOPGM("\nLogical:"); - report_xyz(current_position.asLogical()); + report_linear_axis_pos(current_position.asLogical()); // Cartesian position in native machine space SERIAL_ECHOPGM("Raw: "); - report_xyz(current_position); + report_linear_axis_pos(current_position); xyze_pos_t leveled = current_position; @@ -69,20 +69,20 @@ // Current position with leveling applied SERIAL_ECHOPGM("Leveled:"); planner.apply_leveling(leveled); - report_xyz(leveled); + report_linear_axis_pos(leveled); // Test planner un-leveling. This should match the Raw result. SERIAL_ECHOPGM("UnLevel:"); xyze_pos_t unleveled = leveled; planner.unapply_leveling(unleveled); - report_xyz(unleveled); + report_linear_axis_pos(unleveled); #endif #if IS_KINEMATIC // Kinematics applied to the leveled position SERIAL_ECHOPGM(TERN(IS_SCARA, "ScaraK: ", "DeltaK: ")); inverse_kinematics(leveled); // writes delta[] - report_xyz(delta); + report_linear_axis_pos(delta); #endif planner.synchronize(); @@ -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)); } @@ -165,17 +165,17 @@ planner.get_axis_position_degrees(B_AXIS) }; SERIAL_ECHOPGM("Degrees:"); - report_xyze(deg, 2); + report_all_axis_pos(deg, 2); #endif SERIAL_ECHOPGM("FromStp:"); get_cartesian_from_steppers(); // writes 'cartes' (with forward kinematics) xyze_pos_t from_steppers = { cartes.x, cartes.y, cartes.z, planner.get_axis_position_mm(E_AXIS) }; - report_xyze(from_steppers); + report_all_axis_pos(from_steppers); const xyze_float_t diff = from_steppers - leveled; SERIAL_ECHOPGM("Diff: "); - report_xyze(diff); + report_all_axis_pos(diff); TERN_(FULL_REPORT_TO_HOST_FEATURE, report_current_grblstate_moving()); } diff --git a/Marlin/src/gcode/host/M360.cpp b/Marlin/src/gcode/host/M360.cpp index f3c242526d..7a0b8e3ab0 100644 --- a/Marlin/src/gcode/host/M360.cpp +++ b/Marlin/src/gcode/host/M360.cpp @@ -28,7 +28,7 @@ #include "../../module/motion.h" #include "../../module/planner.h" -#if EXTRUDERS +#if HAS_EXTRUDERS #include "../../module/temperature.h" #endif @@ -171,7 +171,7 @@ void GcodeSuite::M360() { // Per-Extruder settings // config_line(PSTR("NumExtruder"), EXTRUDERS); - #if EXTRUDERS + #if HAS_EXTRUDERS LOOP_L_N(e, EXTRUDERS) { config_line_e(e, JERK_STR, TERN(HAS_LINEAR_E_JERK, planner.max_e_jerk[E_INDEX_N(e)], TERN(HAS_CLASSIC_JERK, planner.max_jerk.e, DEFAULT_EJERK))); config_line_e(e, PSTR("MaxSpeed"), planner.settings.max_feedrate_mm_s[E_AXIS_N(e)]); diff --git a/Marlin/src/gcode/motion/G0_G1.cpp b/Marlin/src/gcode/motion/G0_G1.cpp index 089e00ab95..73c5b11714 100644 --- a/Marlin/src/gcode/motion/G0_G1.cpp +++ b/Marlin/src/gcode/motion/G0_G1.cpp @@ -83,7 +83,7 @@ void GcodeSuite::G0_G1(TERN_(HAS_FAST_MOVES, const bool fast_move/*=false*/)) { if (MIN_AUTORETRACT <= MAX_AUTORETRACT) { // When M209 Autoretract is enabled, convert E-only moves to firmware retract/recover moves - if (fwretract.autoretract_enabled && parser.seen('E') && !(parser.seen('X') || parser.seen('Y') || parser.seen('Z'))) { + if (fwretract.autoretract_enabled && parser.seen('E') && !parser.seen("XYZ")) { const float echange = destination.e - current_position.e; // Is this a retract or recover move? if (WITHIN(ABS(echange), MIN_AUTORETRACT, MAX_AUTORETRACT) && fwretract.retracted[active_extruder] == (echange > 0.0)) { diff --git a/Marlin/src/gcode/motion/G2_G3.cpp b/Marlin/src/gcode/motion/G2_G3.cpp index 5a8324362a..41ff7e9765 100644 --- a/Marlin/src/gcode/motion/G2_G3.cpp +++ b/Marlin/src/gcode/motion/G2_G3.cpp @@ -291,12 +291,12 @@ void plan_arc( * Mixing IJ/JK/KI with R will throw an error. * * - R specifies the radius. X or Y (Y or Z / Z or X) is required. - * Omitting both XY/YZ/ZX will throw an error. - * XY/YZ/ZX must differ from the current XY/YZ/ZX. - * Mixing R with IJ/JK/KI will throw an error. + * Omitting both XY/YZ/ZX will throw an error. + * XY/YZ/ZX must differ from the current XY/YZ/ZX. + * Mixing R with IJ/JK/KI will throw an error. * * - P specifies the number of full circles to do - * before the specified arc move. + * before the specified arc move. * * Examples: * diff --git a/Marlin/src/gcode/motion/M290.cpp b/Marlin/src/gcode/motion/M290.cpp index 7e5a017783..0a858090f9 100644 --- a/Marlin/src/gcode/motion/M290.cpp +++ b/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) diff --git a/Marlin/src/gcode/parser.cpp b/Marlin/src/gcode/parser.cpp index bfa4346f03..514d6b7a5d 100644 --- a/Marlin/src/gcode/parser.cpp +++ b/Marlin/src/gcode/parser.cpp @@ -222,7 +222,7 @@ void GCodeParser::parse(char *p) { #if ENABLED(GCODE_MOTION_MODES) if (letter == 'G' - && (codenum <= TERN(ARC_SUPPORT, 3, 1) || codenum == 5 || TERN0(G38_PROBE_TARGET, codenum == 38)) + && (codenum <= TERN(ARC_SUPPORT, 3, 1) || TERN0(BEZIER_CURVE_SUPPORT, codenum == 5) || TERN0(G38_PROBE_TARGET, codenum == 38)) ) { motion_mode_codenum = codenum; TERN_(USE_GCODE_SUBCODES, motion_mode_subcode = subcode); diff --git a/Marlin/src/gcode/parser.h b/Marlin/src/gcode/parser.h index 3aec17554b..4270e04c9f 100644 --- a/Marlin/src/gcode/parser.h +++ b/Marlin/src/gcode/parser.h @@ -226,7 +226,7 @@ public: // Seen any axis parameter static inline bool seen_axis() { - return seen_test('X') || seen_test('Y') || seen_test('Z') || seen_test('E'); + return seen("XYZE"); } #if ENABLED(GCODE_QUOTED_STRINGS) diff --git a/Marlin/src/gcode/probe/G38.cpp b/Marlin/src/gcode/probe/G38.cpp index b06cd47359..6906805fca 100644 --- a/Marlin/src/gcode/probe/G38.cpp +++ b/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_ENUM); 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 diff --git a/Marlin/src/gcode/temp/M104_M109.cpp b/Marlin/src/gcode/temp/M104_M109.cpp index e54f784153..b6a3fa8507 100644 --- a/Marlin/src/gcode/temp/M104_M109.cpp +++ b/Marlin/src/gcode/temp/M104_M109.cpp @@ -28,7 +28,7 @@ #include "../../inc/MarlinConfigPre.h" -#if EXTRUDERS +#if HAS_EXTRUDERS #include "../gcode.h" #include "../../module/temperature.h" @@ -51,89 +51,29 @@ /** * M104: Set Hotend Temperature target and return immediately - * - * Parameters: - * I : Material Preset index (if material presets are defined) - * T : Tool index. If omitted, applies to the active tool - * S : The target temperature in current units - */ -void GcodeSuite::M104() { - - if (DEBUGGING(DRYRUN)) return; - - #if ENABLED(MIXING_EXTRUDER) && MIXING_VIRTUAL_TOOLS > 1 - constexpr int8_t target_extruder = 0; - #else - const int8_t target_extruder = get_target_extruder_from_command(); - if (target_extruder < 0) return; - #endif - - bool got_temp = false; - celsius_t temp = 0; - - // Accept 'I' if temperature presets are defined - #if PREHEAT_COUNT - got_temp = parser.seenval('I'); - if (got_temp) { - const uint8_t index = parser.value_byte(); - temp = ui.material_preset[_MIN(index, PREHEAT_COUNT - 1)].hotend_temp; - } - #endif - - // If no 'I' get the temperature from 'S' - if (!got_temp) { - got_temp = parser.seenval('S'); - if (got_temp) temp = parser.value_celsius(); - } - - if (got_temp) { - #if ENABLED(SINGLENOZZLE_STANDBY_TEMP) - thermalManager.singlenozzle_temp[target_extruder] = temp; - if (target_extruder != active_extruder) return; - #endif - thermalManager.setTargetHotend(temp, target_extruder); - - #if ENABLED(DUAL_X_CARRIAGE) - if (idex_is_duplicating() && target_extruder == 0) - thermalManager.setTargetHotend(temp ? temp + duplicate_extruder_temp_offset : 0, 1); - #endif - - #if ENABLED(PRINTJOB_TIMER_AUTOSTART) - /** - * Stop the timer at the end of print. Start is managed by 'heat and wait' M109. - * Hotends use EXTRUDE_MINTEMP / 2 to allow nozzles to be put into hot standby - * mode, for instance in a dual extruder setup, without affecting the running - * print timer. - */ - thermalManager.auto_job_check_timer(false, true); - #endif - } - - TERN_(AUTOTEMP, planner.autotemp_M104_M109()); -} - -/** * M109: Set Hotend Temperature target and wait * * Parameters * I : Material Preset index (if material presets are defined) * T : Tool index. If omitted, applies to the active tool - * S : The target temperature in current units. Wait for heating only. - * R : The target temperature in current units. Wait for heating and cooling. + * S : The target temperature in current units. For M109, only wait when heating up. * * With AUTOTEMP... * F : Autotemp Scaling Factor. Set non-zero to enable Auto-temp. * S : Minimum temperature, in current units. * B : Maximum temperature, in current units. * + * M109 Parameters + * R : The target temperature in current units. Wait for heating and cooling. + * * Examples - * M109 S100 : Set target to 100°. Wait until the hotend is at or above 100°. + * M104 S100 : Set target to 100° and return. * M109 R150 : Set target to 150°. Wait until the hotend gets close to 150°. * * With PRINTJOB_TIMER_AUTOSTART turning on heaters will start the print job timer * (used by printingIsActive, etc.) and turning off heaters will stop the timer. */ -void GcodeSuite::M109() { +void GcodeSuite::M104_M109(const bool isM109) { if (DEBUGGING(DRYRUN)) return; @@ -160,7 +100,7 @@ void GcodeSuite::M109() { bool no_wait_for_cooling = false; if (!got_temp) { no_wait_for_cooling = parser.seenval('S'); - got_temp = no_wait_for_cooling || parser.seenval('R'); + got_temp = no_wait_for_cooling || (isM109 && parser.seenval('R')); if (got_temp) temp = parser.value_celsius(); } @@ -182,7 +122,7 @@ void GcodeSuite::M109() { * standby mode, (e.g., in a dual extruder setup) without affecting * the running print timer. */ - thermalManager.auto_job_check_timer(true, true); + thermalManager.auto_job_check_timer(isM109, true); #endif #if HAS_STATUS_MESSAGE @@ -193,7 +133,7 @@ void GcodeSuite::M109() { TERN_(AUTOTEMP, planner.autotemp_M104_M109()); - if (got_temp) + if (isM109 && got_temp) (void)thermalManager.wait_for_hotend(target_extruder, no_wait_for_cooling); } diff --git a/Marlin/src/gcode/temp/M140_M190.cpp b/Marlin/src/gcode/temp/M140_M190.cpp index 3aed878a03..ddab003973 100644 --- a/Marlin/src/gcode/temp/M140_M190.cpp +++ b/Marlin/src/gcode/temp/M140_M190.cpp @@ -35,62 +35,28 @@ #include "../../lcd/marlinui.h" /** - * M140: Set bed temperature + * M140 - Set Bed Temperature target and return immediately + * M190 - Set Bed Temperature target and wait * * I : Preset index (if material presets are defined) * S : The target temperature in current units - */ -void GcodeSuite::M140() { - if (DEBUGGING(DRYRUN)) return; - - bool got_temp = false; - celsius_t temp = 0; - - // Accept 'I' if temperature presets are defined - #if PREHEAT_COUNT - got_temp = parser.seenval('I'); - if (got_temp) { - const uint8_t index = parser.value_byte(); - temp = ui.material_preset[_MIN(index, PREHEAT_COUNT - 1)].bed_temp; - } - #endif - - // If no 'I' get the temperature from 'S' - if (!got_temp) { - got_temp = parser.seenval('S'); - if (got_temp) temp = parser.value_celsius(); - } - - if (got_temp) { - thermalManager.setTargetBed(temp); - - #if ENABLED(PRINTJOB_TIMER_AUTOSTART) - /** - * Stop the timer at the end of print. Hotend, bed target, and chamber - * temperatures need to be set below mintemp. Order of M140, M104, and M141 - * at the end of the print does not matter. - */ - thermalManager.auto_job_check_timer(false, true); - #endif - } -} - -/** - * M190 - Set Bed Temperature target and wait * - * Parameters: + * Parameters * I : Preset index (if material presets are defined) * S : The target temperature in current units. Wait for heating only. + * + * M190 Parameters * R : The target temperature in current units. Wait for heating and cooling. * - * Examples: - * M190 S60 : Set target to 60°. Wait until the bed is at or above 60°. + * Examples + * M140 S60 : Set target to 60° and return right away. * M190 R40 : Set target to 40°. Wait until the bed gets close to 40°. * * With PRINTJOB_TIMER_AUTOSTART turning on heaters will start the print job timer * (used by printingIsActive, etc.) and turning off heaters will stop the timer. */ -void GcodeSuite::M190() { +void GcodeSuite::M140_M190(const bool isM190) { + if (DEBUGGING(DRYRUN)) return; bool got_temp = false; @@ -109,7 +75,7 @@ void GcodeSuite::M190() { bool no_wait_for_cooling = false; if (!got_temp) { no_wait_for_cooling = parser.seenval('S'); - got_temp = no_wait_for_cooling || parser.seenval('R'); + got_temp = no_wait_for_cooling || (isM190 && parser.seenval('R')); if (got_temp) temp = parser.value_celsius(); } @@ -121,7 +87,8 @@ void GcodeSuite::M190() { ui.set_status_P(thermalManager.isHeatingBed() ? GET_TEXT(MSG_BED_HEATING) : GET_TEXT(MSG_BED_COOLING)); - thermalManager.wait_for_bed(no_wait_for_cooling); + if (isM190) + thermalManager.wait_for_bed(no_wait_for_cooling); } #endif // HAS_HEATED_BED diff --git a/Marlin/src/gcode/units/M82_M83.cpp b/Marlin/src/gcode/units/M82_M83.cpp index d93f0ea5ad..c1767e8057 100644 --- a/Marlin/src/gcode/units/M82_M83.cpp +++ b/Marlin/src/gcode/units/M82_M83.cpp @@ -20,6 +20,10 @@ * */ +#include "../../inc/MarlinConfigPre.h" + +#if HAS_EXTRUDERS + #include "../gcode.h" /** @@ -31,3 +35,5 @@ void GcodeSuite::M82() { set_e_absolute(); } * M83: Set E codes relative while in Absolute Coordinates (G90) mode */ void GcodeSuite::M83() { set_e_relative(); } + +#endif // HAS_EXTRUDERS diff --git a/Marlin/src/inc/Conditionals_LCD.h b/Marlin/src/inc/Conditionals_LCD.h index 000aa60347..8001674dc4 100644 --- a/Marlin/src/inc/Conditionals_LCD.h +++ b/Marlin/src/inc/Conditionals_LCD.h @@ -538,7 +538,12 @@ * E_MANUAL - Number of E steppers for LCD move options */ -#if EXTRUDERS == 0 +#if EXTRUDERS + #define HAS_EXTRUDERS 1 + #if EXTRUDERS > 1 + #define HAS_MULTI_EXTRUDER 1 + #endif +#else #undef EXTRUDERS #define EXTRUDERS 0 #undef SINGLENOZZLE @@ -546,8 +551,6 @@ #undef SWITCHING_NOZZLE #undef MIXING_EXTRUDER #undef HOTEND_IDLE_TIMEOUT -#elif EXTRUDERS > 1 - #define HAS_MULTI_EXTRUDER 1 #endif #if ENABLED(SWITCHING_EXTRUDER) // One stepper for every two EXTRUDERS @@ -651,22 +654,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 HAS_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 @@ -798,14 +817,31 @@ #endif #endif // FILAMENT_RUNOUT_SENSOR +// Homing to Min or Max +#if X_HOME_DIR > 0 + #define X_HOME_TO_MAX 1 +#elif X_HOME_DIR < 0 + #define X_HOME_TO_MIN 1 +#endif +#if Y_HOME_DIR > 0 + #define Y_HOME_TO_MAX 1 +#elif Y_HOME_DIR < 0 + #define Y_HOME_TO_MIN 1 +#endif +#if Z_HOME_DIR > 0 + #define Z_HOME_TO_MAX 1 +#elif Z_HOME_DIR < 0 + #define Z_HOME_TO_MIN 1 +#endif + #if HAS_BED_PROBE #if DISABLED(NOZZLE_AS_PROBE) #define HAS_PROBE_XY_OFFSET 1 #endif - #if DISABLED(Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN) + #if DISABLED(Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN) && !BOTH(DELTA, SENSORLESS_PROBING) #define HAS_CUSTOM_PROBE_PIN 1 #endif - #if Z_HOME_DIR < 0 && (!HAS_CUSTOM_PROBE_PIN || ENABLED(USE_PROBE_FOR_Z_HOMING)) + #if Z_HOME_TO_MIN && (!HAS_CUSTOM_PROBE_PIN || ENABLED(USE_PROBE_FOR_Z_HOMING)) #define HOMING_Z_WITH_PROBE 1 #endif #ifndef Z_PROBE_LOW_POINT @@ -827,7 +863,7 @@ #undef USE_PROBE_FOR_Z_HOMING #endif -#if Z_HOME_DIR > 0 +#if Z_HOME_TO_MAX #define HOME_Z_FIRST // If homing away from BED do Z first #endif diff --git a/Marlin/src/inc/Conditionals_adv.h b/Marlin/src/inc/Conditionals_adv.h index 44ea34a490..1d3253b1cc 100644 --- a/Marlin/src/inc/Conditionals_adv.h +++ b/Marlin/src/inc/Conditionals_adv.h @@ -75,7 +75,7 @@ #define SERVO_DELAY { 50 } #endif -#if EXTRUDERS == 0 +#if !HAS_EXTRUDERS #define NO_VOLUMETRICS #undef TEMP_SENSOR_0 #undef TEMP_SENSOR_1 @@ -391,6 +391,12 @@ #define POLL_JOG #endif +#if X2_HOME_DIR > 0 + #define X2_HOME_TO_MAX 1 +#elif X2_HOME_DIR < 0 + #define X2_HOME_TO_MIN 1 +#endif + #ifndef HOMING_BUMP_MM #define HOMING_BUMP_MM { 0, 0, 0 } #endif diff --git a/Marlin/src/inc/Conditionals_post.h b/Marlin/src/inc/Conditionals_post.h index 6de9c40ac7..d86b02bdc2 100644 --- a/Marlin/src/inc/Conditionals_post.h +++ b/Marlin/src/inc/Conditionals_post.h @@ -125,7 +125,7 @@ #if EITHER(IS_CORE, MARKFORGED_XY) #define CAN_CALIBRATE(A,B) (_AXIS(A) == B) #else - #define CAN_CALIBRATE(A,B) 1 + #define CAN_CALIBRATE(A,B) true #endif #endif #define AXIS_CAN_CALIBRATE(A) CAN_CALIBRATE(A,NORMAL_AXIS) @@ -155,7 +155,7 @@ #ifdef MANUAL_X_HOME_POS #define X_HOME_POS MANUAL_X_HOME_POS #else - #define X_END_POS (X_HOME_DIR < 0 ? X_MIN_POS : X_MAX_POS) + #define X_END_POS TERN(X_HOME_TO_MIN, X_MIN_POS, X_MAX_POS) #if ENABLED(BED_CENTER_AT_0_0) #define X_HOME_POS TERN(DELTA, 0, X_END_POS) #else @@ -166,7 +166,7 @@ #ifdef MANUAL_Y_HOME_POS #define Y_HOME_POS MANUAL_Y_HOME_POS #else - #define Y_END_POS (Y_HOME_DIR < 0 ? Y_MIN_POS : Y_MAX_POS) + #define Y_END_POS TERN(Y_HOME_TO_MIN, Y_MIN_POS, Y_MAX_POS) #if ENABLED(BED_CENTER_AT_0_0) #define Y_HOME_POS TERN(DELTA, 0, Y_END_POS) #else @@ -177,7 +177,7 @@ #ifdef MANUAL_Z_HOME_POS #define Z_HOME_POS MANUAL_Z_HOME_POS #else - #define Z_HOME_POS (Z_HOME_DIR < 0 ? Z_MIN_POS : Z_MAX_POS) + #define Z_HOME_POS TERN(Z_HOME_TO_MIN, Z_MIN_POS, Z_MAX_POS) #endif /** @@ -798,7 +798,7 @@ * X_DUAL_ENDSTOPS endstop reassignment */ #if ENABLED(X_DUAL_ENDSTOPS) - #if X_HOME_DIR > 0 + #if X_HOME_TO_MAX #ifndef X2_MAX_ENDSTOP_INVERTING #if X2_USE_ENDSTOP == _XMIN_ #define X2_MAX_ENDSTOP_INVERTING X_MIN_ENDSTOP_INVERTING @@ -921,7 +921,7 @@ * Y_DUAL_ENDSTOPS endstop reassignment */ #if ENABLED(Y_DUAL_ENDSTOPS) - #if Y_HOME_DIR > 0 + #if Y_HOME_TO_MAX #ifndef Y2_MAX_ENDSTOP_INVERTING #if Y2_USE_ENDSTOP == _XMIN_ #define Y2_MAX_ENDSTOP_INVERTING X_MIN_ENDSTOP_INVERTING @@ -1045,7 +1045,7 @@ */ #if ENABLED(Z_MULTI_ENDSTOPS) - #if Z_HOME_DIR > 0 + #if Z_HOME_TO_MAX #ifndef Z2_MAX_ENDSTOP_INVERTING #if Z2_USE_ENDSTOP == _XMIN_ #define Z2_MAX_ENDSTOP_INVERTING X_MIN_ENDSTOP_INVERTING @@ -1164,7 +1164,7 @@ #endif #if NUM_Z_STEPPER_DRIVERS >= 3 - #if Z_HOME_DIR > 0 + #if Z_HOME_TO_MAX #ifndef Z3_MAX_ENDSTOP_INVERTING #if Z3_USE_ENDSTOP == _XMIN_ #define Z3_MAX_ENDSTOP_INVERTING X_MIN_ENDSTOP_INVERTING @@ -1284,7 +1284,7 @@ #endif #if NUM_Z_STEPPER_DRIVERS >= 4 - #if Z_HOME_DIR > 0 + #if Z_HOME_TO_MAX #ifndef Z4_MAX_ENDSTOP_INVERTING #if Z4_USE_ENDSTOP == _XMIN_ #define Z4_MAX_ENDSTOP_INVERTING X_MIN_ENDSTOP_INVERTING diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index 2131fcd678..897cb2824f 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -1555,7 +1555,7 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #endif #if ENABLED(G26_MESH_VALIDATION) - #if !EXTRUDERS + #if !HAS_EXTRUDERS #error "G26_MESH_VALIDATION requires at least one extruder." #elif !HAS_MESH #error "G26_MESH_VALIDATION requires MESH_BED_LEVELING, AUTO_BED_LEVELING_BILINEAR, or AUTO_BED_LEVELING_UBL." @@ -1682,7 +1682,7 @@ static_assert(hbm[Z_AXIS] >= 0, "HOMING_BUMP_MM.Z must be greater than or equal * Allen Key * Deploying the Allen Key probe uses big moves in z direction. Too dangerous for an unhomed z-axis. */ -#if BOTH(Z_PROBE_ALLEN_KEY, Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN) && Z_HOME_DIR < 0 +#if ALL(Z_HOME_TO_MIN, Z_PROBE_ALLEN_KEY, Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN) #error "You can't home to a Z min endstop with a Z_PROBE_ALLEN_KEY." #endif @@ -1700,7 +1700,7 @@ static_assert(hbm[Z_AXIS] >= 0, "HOMING_BUMP_MM.Z must be greater than or equal #error "DUAL_X_CARRIAGE requires USE_XMAX_PLUG and an X Max Endstop." #elif !defined(X2_HOME_POS) || !defined(X2_MIN_POS) || !defined(X2_MAX_POS) #error "DUAL_X_CARRIAGE requires X2_HOME_POS, X2_MIN_POS, and X2_MAX_POS." - #elif X_HOME_DIR != -1 || X2_HOME_DIR != 1 + #elif X_HOME_TO_MAX || X2_HOME_TO_MIN #error "DUAL_X_CARRIAGE requires X_HOME_DIR -1 and X2_HOME_DIR 1." #endif #endif @@ -2089,25 +2089,25 @@ static_assert(hbm[Z_AXIS] >= 0, "HOMING_BUMP_MM.Z must be greater than or equal // Delta and Cartesian use 3 homing endstops #if NONE(IS_SCARA, SPI_ENDSTOPS) - #if X_HOME_DIR < 0 && DISABLED(USE_XMIN_PLUG) + #if X_HOME_TO_MIN && DISABLED(USE_XMIN_PLUG) #error "Enable USE_XMIN_PLUG when homing X to MIN." - #elif X_HOME_DIR > 0 && DISABLED(USE_XMAX_PLUG) + #elif X_HOME_TO_MAX && DISABLED(USE_XMAX_PLUG) #error "Enable USE_XMAX_PLUG when homing X to MAX." - #elif Y_HOME_DIR < 0 && DISABLED(USE_YMIN_PLUG) + #elif Y_HOME_TO_MIN && DISABLED(USE_YMIN_PLUG) #error "Enable USE_YMIN_PLUG when homing Y to MIN." - #elif Y_HOME_DIR > 0 && DISABLED(USE_YMAX_PLUG) + #elif Y_HOME_TO_MAX && DISABLED(USE_YMAX_PLUG) #error "Enable USE_YMAX_PLUG when homing Y to MAX." #endif #endif // Z homing direction and plug usage flags - #if Z_HOME_DIR < 0 && NONE(USE_ZMIN_PLUG, HOMING_Z_WITH_PROBE) + #if Z_HOME_TO_MIN && NONE(USE_ZMIN_PLUG, HOMING_Z_WITH_PROBE) #error "Enable USE_ZMIN_PLUG when homing Z to MIN." - #elif Z_HOME_DIR > 0 && ENABLED(USE_PROBE_FOR_Z_HOMING) + #elif Z_HOME_TO_MAX && ENABLED(USE_PROBE_FOR_Z_HOMING) #error "Z_HOME_DIR must be -1 when homing Z with the probe." #elif BOTH(HOMING_Z_WITH_PROBE, Z_MULTI_ENDSTOPS) #error "Z_MULTI_ENDSTOPS is incompatible with USE_PROBE_FOR_Z_HOMING." - #elif Z_HOME_DIR > 0 && DISABLED(USE_ZMAX_PLUG) + #elif Z_HOME_TO_MAX && DISABLED(USE_ZMAX_PLUG) #error "Enable USE_ZMAX_PLUG when homing Z to MAX." #endif #endif @@ -2304,7 +2304,7 @@ static_assert(hbm[Z_AXIS] >= 0, "HOMING_BUMP_MM.Z must be greater than or equal + (DISABLED(IS_LEGACY_TFT) && ENABLED(TFT_GENERIC)) \ + (ENABLED(IS_LEGACY_TFT) && COUNT_ENABLED(TFT_320x240, TFT_320x240_SPI, TFT_480x320, TFT_480x320_SPI)) \ + COUNT_ENABLED(ANYCUBIC_LCD_I3MEGA, ANYCUBIC_LCD_CHIRON, ANYCUBIC_TFT35) \ - + COUNT_ENABLED(DGUS_LCD_UI_ORIGIN, DGUS_LCD_UI_FYSETC, DGUS_LCD_UI_HIPRECY,DGUS_LCD_UI_MKS) \ + + COUNT_ENABLED(DGUS_LCD_UI_ORIGIN, DGUS_LCD_UI_FYSETC, DGUS_LCD_UI_HIPRECY, DGUS_LCD_UI_MKS) \ + COUNT_ENABLED(ENDER2_STOCKDISPLAY, CR10_STOCKDISPLAY, DWIN_CREALITY_LCD) \ + COUNT_ENABLED(FYSETC_MINI_12864_X_X, FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0, FYSETC_MINI_12864_2_1, FYSETC_GENERIC_12864_1_1) \ + COUNT_ENABLED(LCD_SAINSMART_I2C_1602, LCD_SAINSMART_I2C_2004) \ @@ -2630,17 +2630,17 @@ static_assert(hbm[Z_AXIS] >= 0, "HOMING_BUMP_MM.Z must be greater than or equal #define Z_ENDSTOP_INVERTING !AXIS_DRIVER_TYPE(Z,TMC2209) #if NONE(SPI_ENDSTOPS, ONBOARD_ENDSTOPPULLUPS, ENDSTOPPULLUPS) - #if X_SENSORLESS && X_HOME_DIR < 0 && DISABLED(ENDSTOPPULLUP_XMIN) + #if X_SENSORLESS && X_HOME_TO_MIN && DISABLED(ENDSTOPPULLUP_XMIN) #error "SENSORLESS_HOMING requires ENDSTOPPULLUP_XMIN (or ENDSTOPPULLUPS) when homing to X_MIN." - #elif X_SENSORLESS && X_HOME_DIR > 0 && DISABLED(ENDSTOPPULLUP_XMAX) + #elif X_SENSORLESS && X_HOME_TO_MAX && DISABLED(ENDSTOPPULLUP_XMAX) #error "SENSORLESS_HOMING requires ENDSTOPPULLUP_XMAX (or ENDSTOPPULLUPS) when homing to X_MAX." - #elif Y_SENSORLESS && Y_HOME_DIR < 0 && DISABLED(ENDSTOPPULLUP_YMIN) + #elif Y_SENSORLESS && Y_HOME_TO_MIN && DISABLED(ENDSTOPPULLUP_YMIN) #error "SENSORLESS_HOMING requires ENDSTOPPULLUP_YMIN (or ENDSTOPPULLUPS) when homing to Y_MIN." - #elif Y_SENSORLESS && Y_HOME_DIR > 0 && DISABLED(ENDSTOPPULLUP_YMAX) + #elif Y_SENSORLESS && Y_HOME_TO_MAX && DISABLED(ENDSTOPPULLUP_YMAX) #error "SENSORLESS_HOMING requires ENDSTOPPULLUP_YMAX (or ENDSTOPPULLUPS) when homing to Y_MAX." - #elif Z_SENSORLESS && Z_HOME_DIR < 0 && DISABLED(ENDSTOPPULLUP_ZMIN) + #elif Z_SENSORLESS && Z_HOME_TO_MIN && DISABLED(ENDSTOPPULLUP_ZMIN) #error "SENSORLESS_HOMING requires ENDSTOPPULLUP_ZMIN (or ENDSTOPPULLUPS) when homing to Z_MIN." - #elif Z_SENSORLESS && Z_HOME_DIR > 0 && DISABLED(ENDSTOPPULLUP_ZMAX) + #elif Z_SENSORLESS && Z_HOME_TO_MAX && DISABLED(ENDSTOPPULLUP_ZMAX) #error "SENSORLESS_HOMING requires ENDSTOPPULLUP_ZMAX (or ENDSTOPPULLUPS) when homing to Z_MAX." #endif #endif @@ -2650,37 +2650,37 @@ static_assert(hbm[Z_AXIS] >= 0, "HOMING_BUMP_MM.Z must be greater than or equal #warning "SPI_ENDSTOPS may be unreliable with QUICK_HOME. Adjust back-offs for better results." #endif #else - #if X_SENSORLESS && X_HOME_DIR < 0 && X_MIN_ENDSTOP_INVERTING != X_ENDSTOP_INVERTING + #if X_SENSORLESS && X_HOME_TO_MIN && X_MIN_ENDSTOP_INVERTING != X_ENDSTOP_INVERTING #if X_ENDSTOP_INVERTING #error "SENSORLESS_HOMING requires X_MIN_ENDSTOP_INVERTING = true when homing to X_MIN." #else #error "SENSORLESS_HOMING requires X_MIN_ENDSTOP_INVERTING = false when homing TMC2209 to X_MIN." #endif - #elif X_SENSORLESS && X_HOME_DIR > 0 && X_MAX_ENDSTOP_INVERTING != X_ENDSTOP_INVERTING + #elif X_SENSORLESS && X_HOME_TO_MAX && X_MAX_ENDSTOP_INVERTING != X_ENDSTOP_INVERTING #if X_ENDSTOP_INVERTING #error "SENSORLESS_HOMING requires X_MAX_ENDSTOP_INVERTING = true when homing to X_MAX." #else #error "SENSORLESS_HOMING requires X_MAX_ENDSTOP_INVERTING = false when homing TMC2209 to X_MAX." #endif - #elif Y_SENSORLESS && Y_HOME_DIR < 0 && Y_MIN_ENDSTOP_INVERTING != Y_ENDSTOP_INVERTING + #elif Y_SENSORLESS && Y_HOME_TO_MIN && Y_MIN_ENDSTOP_INVERTING != Y_ENDSTOP_INVERTING #if Y_ENDSTOP_INVERTING #error "SENSORLESS_HOMING requires Y_MIN_ENDSTOP_INVERTING = true when homing to Y_MIN." #else #error "SENSORLESS_HOMING requires Y_MIN_ENDSTOP_INVERTING = false when homing TMC2209 to Y_MIN." #endif - #elif Y_SENSORLESS && Y_HOME_DIR > 0 && Y_MAX_ENDSTOP_INVERTING != Y_ENDSTOP_INVERTING + #elif Y_SENSORLESS && Y_HOME_TO_MAX && Y_MAX_ENDSTOP_INVERTING != Y_ENDSTOP_INVERTING #if Y_ENDSTOP_INVERTING #error "SENSORLESS_HOMING requires Y_MAX_ENDSTOP_INVERTING = true when homing to Y_MAX." #else #error "SENSORLESS_HOMING requires Y_MAX_ENDSTOP_INVERTING = false when homing TMC2209 to Y_MAX." #endif - #elif Z_SENSORLESS && Z_HOME_DIR < 0 && Z_MIN_ENDSTOP_INVERTING != Z_ENDSTOP_INVERTING + #elif Z_SENSORLESS && Z_HOME_TO_MIN && Z_MIN_ENDSTOP_INVERTING != Z_ENDSTOP_INVERTING #if Z_ENDSTOP_INVERTING #error "SENSORLESS_HOMING requires Z_MIN_ENDSTOP_INVERTING = true when homing to Z_MIN." #else #error "SENSORLESS_HOMING requires Z_MIN_ENDSTOP_INVERTING = false when homing TMC2209 to Z_MIN." #endif - #elif Z_SENSORLESS && Z_HOME_DIR > 0 && Z_MAX_ENDSTOP_INVERTING != Z_ENDSTOP_INVERTING + #elif Z_SENSORLESS && Z_HOME_TO_MAX && Z_MAX_ENDSTOP_INVERTING != Z_ENDSTOP_INVERTING #if Z_ENDSTOP_INVERTING #error "SENSORLESS_HOMING requires Z_MAX_ENDSTOP_INVERTING = true when homing to Z_MAX." #else @@ -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), @@ -2918,9 +2918,9 @@ static_assert( _ARR_TEST(3,0) && _ARR_TEST(3,1) && _ARR_TEST(3,2) #error "POWER_LOSS_RECOVER_ZHOME cannot be used with Z_SAFE_HOMING." #elif BOTH(POWER_LOSS_PULLUP, POWER_LOSS_PULLDOWN) #error "You can't enable POWER_LOSS_PULLUP and POWER_LOSS_PULLDOWN at the same time." - #elif ENABLED(POWER_LOSS_RECOVER_ZHOME) && Z_HOME_DIR > 0 + #elif ENABLED(POWER_LOSS_RECOVER_ZHOME) && Z_HOME_TO_MAX #error "POWER_LOSS_RECOVER_ZHOME is not needed on a machine that homes to ZMAX." - #elif BOTH(IS_CARTESIAN, POWER_LOSS_RECOVER_ZHOME) && Z_HOME_DIR < 0 && !defined(POWER_LOSS_ZHOME_POS) + #elif BOTH(IS_CARTESIAN, POWER_LOSS_RECOVER_ZHOME) && Z_HOME_TO_MIN && !defined(POWER_LOSS_ZHOME_POS) #error "POWER_LOSS_RECOVER_ZHOME requires POWER_LOSS_ZHOME_POS for a Cartesian that homes to ZMIN." #endif #endif @@ -3247,7 +3247,7 @@ static_assert( _ARR_TEST(3,0) && _ARR_TEST(3,1) && _ARR_TEST(3,2) /** * Sanity check for MIXING_EXTRUDER & DISTINCT_E_FACTORS these are not compatible */ -#if ENABLED(MIXING_EXTRUDER) && ENABLED(DISTINCT_E_FACTORS) +#if BOTH(MIXING_EXTRUDER, DISTINCT_E_FACTORS) #error "MIXING_EXTRUDER can't be used with DISTINCT_E_FACTORS. But you may use SINGLENOZZLE with DISTINCT_E_FACTORS." #endif diff --git a/Marlin/src/lcd/HD44780/marlinui_HD44780.cpp b/Marlin/src/lcd/HD44780/marlinui_HD44780.cpp index 85430c18b0..50c80c9fa0 100644 --- a/Marlin/src/lcd/HD44780/marlinui_HD44780.cpp +++ b/Marlin/src/lcd/HD44780/marlinui_HD44780.cpp @@ -954,7 +954,7 @@ void MarlinUI::draw_status_screen() { else #endif { - #if EXTRUDERS + #if HAS_EXTRUDERS c = 'E'; per = planner.flow_percentage[0]; #endif diff --git a/Marlin/src/lcd/extui/dgus/DGUSScreenHandler.cpp b/Marlin/src/lcd/extui/dgus/DGUSScreenHandler.cpp index 5b3bb9e0f3..a1de499f46 100644 --- a/Marlin/src/lcd/extui/dgus/DGUSScreenHandler.cpp +++ b/Marlin/src/lcd/extui/dgus/DGUSScreenHandler.cpp @@ -422,7 +422,7 @@ void DGUSScreenHandler::HandleTemperatureChanged(DGUS_VP_Variable &var, void *va } void DGUSScreenHandler::HandleFlowRateChanged(DGUS_VP_Variable &var, void *val_ptr) { - #if EXTRUDERS + #if HAS_EXTRUDERS uint16_t newvalue = swap16(*(uint16_t*)val_ptr); uint8_t target_extruder; switch (var.VP) { diff --git a/Marlin/src/lcd/extui/dgus/dgus_extui.cpp b/Marlin/src/lcd/extui/dgus/dgus_extui.cpp index b389294175..55546caaf1 100644 --- a/Marlin/src/lcd/extui/dgus/dgus_extui.cpp +++ b/Marlin/src/lcd/extui/dgus/dgus_extui.cpp @@ -147,6 +147,7 @@ namespace ExtUI { case PID_DONE: ScreenHandler.setstatusmessagePGM(GET_TEXT(MSG_PID_AUTOTUNE_DONE)); break; + case PID_STARTED: break; } ScreenHandler.GotoScreen(DGUSLCD_SCREEN_MAIN); } diff --git a/Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.cpp b/Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.cpp index 525b781599..3d68df7b7f 100644 --- a/Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.cpp +++ b/Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.cpp @@ -691,7 +691,10 @@ const struct DGUS_VP_Variable ListOfVP[] PROGMEM = { VPHELPER(VP_X_PARK_POS, &mks_park_pos.x, ScreenHandler.GetParkPos_MKS, ScreenHandler.DGUSLCD_SendWordValueToDisplay), VPHELPER(VP_Y_PARK_POS, &mks_park_pos.y, ScreenHandler.GetParkPos_MKS, ScreenHandler.DGUSLCD_SendWordValueToDisplay), VPHELPER(VP_Z_PARK_POS, &mks_park_pos.z, ScreenHandler.GetParkPos_MKS, ScreenHandler.DGUSLCD_SendWordValueToDisplay), - VPHELPER(VP_MIN_EX_T, &thermalManager.extrude_min_temp, ScreenHandler.HandleGetExMinTemp_MKS, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + + #if ENABLED(PREVENT_COLD_EXTRUSION) + VPHELPER(VP_MIN_EX_T, &thermalManager.extrude_min_temp, ScreenHandler.HandleGetExMinTemp_MKS, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + #endif #if ENABLED(SENSORLESS_HOMING) // TMC SENSORLESS Setting #if AXIS_HAS_STEALTHCHOP(X) @@ -743,7 +746,11 @@ const struct DGUS_VP_Variable ListOfVP[] PROGMEM = { VPHELPER(VP_ZOffset_Distance,nullptr ,ScreenHandler.GetZoffsetDistance, nullptr), VPHELPER(VP_MESH_LEVEL_ADJUST, nullptr, ScreenHandler.MeshLevelDistanceConfig, nullptr), VPHELPER(VP_MESH_LEVEL_POINT,nullptr, ScreenHandler.MeshLevel,nullptr), - VPHELPER(VP_Min_EX_T_E, &thermalManager.extrude_min_temp, &ScreenHandler.GetMinExtrudeTemp, &ScreenHandler.DGUSLCD_SendWordValueToDisplay), + + #if ENABLED(PREVENT_COLD_EXTRUSION) + VPHELPER(VP_Min_EX_T_E, &thermalManager.extrude_min_temp, &ScreenHandler.GetMinExtrudeTemp, &ScreenHandler.DGUSLCD_SendWordValueToDisplay), + #endif + VPHELPER(VP_AutoTurnOffSw, nullptr, &ScreenHandler.GetTurnOffCtrl, nullptr), #if HOTENDS >= 1 diff --git a/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.cpp b/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.cpp index c0b3b60a16..6d12d529a9 100644 --- a/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.cpp +++ b/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.cpp @@ -342,7 +342,7 @@ void DGUSScreenHandler::GetTurnOffCtrl(DGUS_VP_Variable &var, void *val_ptr) { void DGUSScreenHandler::GetMinExtrudeTemp(DGUS_VP_Variable &var, void *val_ptr) { DEBUG_ECHOLNPGM("GetMinExtrudeTemp"); const uint16_t value = swap16(*(uint16_t *)val_ptr); - thermalManager.extrude_min_temp = value; + TERN_(PREVENT_COLD_EXTRUSION, thermalManager.extrude_min_temp = value); mks_min_extrusion_temp = value; settings.save(); } @@ -1083,11 +1083,13 @@ void DGUSScreenHandler::HandleAccChange_MKS(DGUS_VP_Variable &var, void *val_ptr skipVP = var.VP; // don't overwrite value the next update time as the display might autoincrement in parallel } -void DGUSScreenHandler::HandleGetExMinTemp_MKS(DGUS_VP_Variable &var, void *val_ptr) { - const uint16_t value_ex_min_temp = swap16(*(uint16_t*)val_ptr); - thermalManager.extrude_min_temp = value_ex_min_temp; - skipVP = var.VP; // don't overwrite value the next update time as the display might autoincrement in parallel -} +#if ENABLED(PREVENT_COLD_EXTRUSION) + void DGUSScreenHandler::HandleGetExMinTemp_MKS(DGUS_VP_Variable &var, void *val_ptr) { + const uint16_t value_ex_min_temp = swap16(*(uint16_t*)val_ptr); + thermalManager.extrude_min_temp = value_ex_min_temp; + skipVP = var.VP; // don't overwrite value the next update time as the display might autoincrement in parallel + } +#endif #if HAS_PID_HEATING void DGUSScreenHandler::HandleTemperaturePIDChanged(DGUS_VP_Variable &var, void *val_ptr) { @@ -1231,7 +1233,7 @@ void DGUSScreenHandler::MKS_FilamentLoadUnload(DGUS_VP_Variable &var, void *val_ break; } - #if HAS_HOTEND + #if BOTH(HAS_HOTEND, PREVENT_COLD_EXTRUSION) if (hotend_too_cold) { if (thermalManager.targetTooColdToExtrude(hotend_too_cold - 1)) thermalManager.setTargetHotend(thermalManager.extrude_min_temp, hotend_too_cold - 1); sendinfoscreen(PSTR("NOTICE"), nullptr, PSTR("Please wait."), PSTR("Nozzle heating!"), true, true, true, true); @@ -1428,8 +1430,10 @@ bool DGUSScreenHandler::loop() { #endif #endif - if (mks_min_extrusion_temp != 0) - thermalManager.extrude_min_temp = mks_min_extrusion_temp; + #if ENABLED(PREVENT_COLD_EXTRUSION) + if (mks_min_extrusion_temp != 0) + thermalManager.extrude_min_temp = mks_min_extrusion_temp; + #endif DGUS_ExtrudeLoadInit(); diff --git a/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.h b/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.h index 6713debd83..4a67b4afda 100644 --- a/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.h +++ b/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.h @@ -82,7 +82,9 @@ public: static void GetZoffsetDistance(DGUS_VP_Variable &var, void *val_ptr); static void GetMinExtrudeTemp(DGUS_VP_Variable &var, void *val_ptr); static void GetParkPos_MKS(DGUS_VP_Variable &var, void *val_ptr); - static void HandleGetExMinTemp_MKS(DGUS_VP_Variable &var, void *val_ptr); + #if ENABLED(PREVENT_COLD_EXTRUSION) + static void HandleGetExMinTemp_MKS(DGUS_VP_Variable &var, void *val_ptr); + #endif static void DGUS_LanguageDisplay(uint8_t var); static void TMC_ChangeConfig(DGUS_VP_Variable &var, void *val_ptr); static void GetTurnOffCtrl(DGUS_VP_Variable &var, void *val_ptr); diff --git a/Marlin/src/lcd/extui/example/example.cpp b/Marlin/src/lcd/extui/example/example.cpp index 959d750872..0e7d71ff4d 100644 --- a/Marlin/src/lcd/extui/example/example.cpp +++ b/Marlin/src/lcd/extui/example/example.cpp @@ -119,6 +119,12 @@ namespace ExtUI { #if HAS_PID_HEATING void onPidTuning(const result_t rst) { // Called for temperature PID tuning result + switch (rst) { + case PID_BAD_EXTRUDER_NUM: break; + case PID_TEMP_TOO_HIGH: break; + case PID_TUNING_TIMEOUT: break; + case PID_DONE: break; + } } #endif diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/move_axis_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/move_axis_screen.cpp index 67ea002d34..9406572c33 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/move_axis_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/move_axis_screen.cpp @@ -66,7 +66,7 @@ void MoveAxisScreen::onRedraw(draw_mode_t what) { w.adjuster( 14, GET_TEXT_F(MSG_AXIS_E4), mydata.e_rel[3], canMove(E3)); #endif #endif - #if Z_HOME_DIR < 0 + #if Z_HOME_TO_MIN w.button(24, GET_TEXT_F(MSG_MOVE_Z_TO_TOP), !axis_should_home(Z_AXIS)); #endif w.increments(); diff --git a/Marlin/src/lcd/extui/mks_ui/wifi_module.cpp b/Marlin/src/lcd/extui/mks_ui/wifi_module.cpp index be693a748f..52a877031f 100644 --- a/Marlin/src/lcd/extui/mks_ui/wifi_module.cpp +++ b/Marlin/src/lcd/extui/mks_ui/wifi_module.cpp @@ -28,11 +28,12 @@ #include "wifi_upload.h" #include "SPI_TFT.h" +#include "../../marlinui.h" + #include "../../../MarlinCore.h" #include "../../../module/temperature.h" #include "../../../gcode/queue.h" #include "../../../gcode/gcode.h" -#include "../../../lcd/marlinui.h" #include "../../../sd/cardreader.h" #include "../../../module/planner.h" #include "../../../module/servo.h" @@ -621,9 +622,9 @@ static void wifi_gcode_exec(uint8_t *cmd_line) { if (tmpStr == 0) { gCfgItems.fileSysType = FILE_SYS_SD; - send_to_wifi((uint8_t *)"Begin file list\r\n", strlen("Begin file list\r\n")); + send_to_wifi((uint8_t *)(STR_BEGIN_FILE_LIST "\r\n"), strlen(STR_BEGIN_FILE_LIST "\r\n")); get_file_list((char *)"0:/"); - send_to_wifi((uint8_t *)"End file list\r\n", strlen("End file list\r\n")); + send_to_wifi((uint8_t *)(STR_END_FILE_LIST "\r\n"), strlen(STR_END_FILE_LIST "\r\n")); SEND_OK_TO_WIFI; break; } @@ -634,7 +635,7 @@ static void wifi_gcode_exec(uint8_t *cmd_line) { char *path = (char *)tempBuf; if (strlen((char *)&tmpStr[index]) < 80) { - send_to_wifi((uint8_t *)"Begin file list\r\n", strlen("Begin file list\r\n")); + send_to_wifi((uint8_t *)(STR_BEGIN_FILE_LIST "\r\n"), strlen(STR_BEGIN_FILE_LIST "\r\n")); if (strncmp((char *)&tmpStr[index], "1:", 2) == 0) gCfgItems.fileSysType = FILE_SYS_SD; @@ -643,7 +644,7 @@ static void wifi_gcode_exec(uint8_t *cmd_line) { strcpy((char *)path, (char *)&tmpStr[index]); get_file_list(path); - send_to_wifi((uint8_t *)"End file list\r\n", strlen("End file list\r\n")); + send_to_wifi((uint8_t *)(STR_END_FILE_LIST "\r\n"), strlen(STR_END_FILE_LIST "\r\n")); } SEND_OK_TO_WIFI; } diff --git a/Marlin/src/lcd/extui/ui_api.cpp b/Marlin/src/lcd/extui/ui_api.cpp index faa23665bb..fff31f099b 100644 --- a/Marlin/src/lcd/extui/ui_api.cpp +++ b/Marlin/src/lcd/extui/ui_api.cpp @@ -569,7 +569,7 @@ namespace ExtUI { } float getAxisSteps_per_mm(const extruder_t extruder) { - UNUSED_E(extruder); + UNUSED(extruder); return planner.settings.axis_steps_per_mm[E_AXIS_N(extruder - E0)]; } @@ -579,7 +579,7 @@ namespace ExtUI { } void setAxisSteps_per_mm(const_float_t value, const extruder_t extruder) { - UNUSED_E(extruder); + UNUSED(extruder); planner.settings.axis_steps_per_mm[E_AXIS_N(extruder - E0)] = value; planner.refresh_positioning(); } @@ -589,7 +589,7 @@ namespace ExtUI { } feedRate_t getAxisMaxFeedrate_mm_s(const extruder_t extruder) { - UNUSED_E(extruder); + UNUSED(extruder); return planner.settings.max_feedrate_mm_s[E_AXIS_N(extruder - E0)]; } @@ -598,7 +598,7 @@ namespace ExtUI { } void setAxisMaxFeedrate_mm_s(const feedRate_t value, const extruder_t extruder) { - UNUSED_E(extruder); + UNUSED(extruder); planner.set_max_feedrate(E_AXIS_N(extruder - E0), value); } @@ -607,7 +607,7 @@ namespace ExtUI { } float getAxisMaxAcceleration_mm_s2(const extruder_t extruder) { - UNUSED_E(extruder); + UNUSED(extruder); return planner.settings.max_acceleration_mm_per_s2[E_AXIS_N(extruder - E0)]; } @@ -616,7 +616,7 @@ namespace ExtUI { } void setAxisMaxAcceleration_mm_s2(const_float_t value, const extruder_t extruder) { - UNUSED_E(extruder); + UNUSED(extruder); planner.set_max_acceleration(E_AXIS_N(extruder - E0), value); } diff --git a/Marlin/src/lcd/marlinui.cpp b/Marlin/src/lcd/marlinui.cpp index 4c33b924c4..14959851fa 100644 --- a/Marlin/src/lcd/marlinui.cpp +++ b/Marlin/src/lcd/marlinui.cpp @@ -488,12 +488,12 @@ bool MarlinUI::get_blink() { if (RRK(EN_KEYPAD_MIDDLE)) goto_screen(menu_move); - #if DISABLED(DELTA) && Z_HOME_DIR < 0 + #if NONE(DELTA, Z_HOME_TO_MAX) if (RRK(EN_KEYPAD_F2)) _reprapworld_keypad_move(Z_AXIS, 1); #endif if (homed) { - #if ENABLED(DELTA) || Z_HOME_DIR != -1 + #if EITHER(DELTA, Z_HOME_TO_MAX) if (RRK(EN_KEYPAD_F2)) _reprapworld_keypad_move(Z_AXIS, 1); #endif if (RRK(EN_KEYPAD_F3)) _reprapworld_keypad_move(Z_AXIS, -1); @@ -681,10 +681,10 @@ void MarlinUI::quick_feedback(const bool clear_buttons/*=true*/) { xyze_pos_t ManualMove::all_axes_destination = { 0 }; bool ManualMove::processing = false; #endif - #if ENABLED(MULTI_MANUAL) + #if MULTI_E_MANUAL int8_t ManualMove::e_index = 0; #endif - AxisEnum ManualMove::axis = NO_AXIS; + AxisEnum ManualMove::axis = NO_AXIS_ENUM; /** * 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_ENUM 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_ENUM && 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_ENUM) 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_ENUM; // 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_ENUM; #endif } @@ -758,11 +758,11 @@ void MarlinUI::quick_feedback(const bool clear_buttons/*=true*/) { // Tell ui.update() to start a move to current_position after a short delay. // void ManualMove::soon(const AxisEnum move_axis - #if MULTI_MANUAL + #if MULTI_E_MANUAL , const int8_t eindex/*=-1*/ #endif ) { - #if MULTI_MANUAL + #if MULTI_E_MANUAL if (move_axis == E_AXIS) e_index = eindex >= 0 ? eindex : active_extruder; #endif start_time = millis() + (menu_scale < 0.99f ? 0UL : 250UL); // delay for bigger moves diff --git a/Marlin/src/lcd/marlinui.h b/Marlin/src/lcd/marlinui.h index 085e2e0b7e..ba0221713b 100644 --- a/Marlin/src/lcd/marlinui.h +++ b/Marlin/src/lcd/marlinui.h @@ -48,7 +48,7 @@ #endif #if E_MANUAL > 1 - #define MULTI_MANUAL 1 + #define MULTI_E_MANUAL 1 #endif #if HAS_DISPLAY @@ -129,7 +129,7 @@ class ManualMove { private: static AxisEnum axis; - #if MULTI_MANUAL + #if MULTI_E_MANUAL static int8_t e_index; #else static int8_t constexpr e_index = 0; @@ -183,7 +183,7 @@ #endif static void task(); static void soon(const AxisEnum axis - #if MULTI_MANUAL + #if MULTI_E_MANUAL , const int8_t eindex=-1 #endif ); diff --git a/Marlin/src/lcd/menu/menu_advanced.cpp b/Marlin/src/lcd/menu/menu_advanced.cpp index 044797b749..e751b53446 100644 --- a/Marlin/src/lcd/menu/menu_advanced.cpp +++ b/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); }) diff --git a/Marlin/src/lcd/menu/menu_bed_corners.cpp b/Marlin/src/lcd/menu/menu_bed_corners.cpp index d28ef1182e..0ab82a9b16 100644 --- a/Marlin/src/lcd/menu/menu_bed_corners.cpp +++ b/Marlin/src/lcd/menu/menu_bed_corners.cpp @@ -225,7 +225,7 @@ static void _lcd_level_bed_corners_get_next_position() { if (verify) do_blocking_move_to_z(current_position.z + LEVEL_CORNERS_Z_HOP); // do clearance if needed TERN_(BLTOUCH_SLOW_MODE, bltouch.deploy()); // Deploy in LOW SPEED MODE on every probe action do_blocking_move_to_z(last_z - LEVEL_CORNERS_PROBE_TOLERANCE, MMM_TO_MMS(Z_PROBE_FEEDRATE_SLOW)); // Move down to lower tolerance - if (TEST(endstops.trigger_state(), TERN(Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN, Z_MIN, Z_MIN_PROBE))) { // check if probe triggered + if (TEST(endstops.trigger_state(), Z_MIN_PROBE)) { // check if probe triggered endstops.hit_on_purpose(); set_current_from_steppers_for_axis(Z_AXIS); sync_plan_position(); diff --git a/Marlin/src/lcd/menu/menu_bed_leveling.cpp b/Marlin/src/lcd/menu/menu_bed_leveling.cpp index 8e9707de5b..62cf8cf1c1 100644 --- a/Marlin/src/lcd/menu/menu_bed_leveling.cpp +++ b/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_ENUM); sync_plan_position(); } diff --git a/Marlin/src/lcd/menu/menu_delta_calibrate.cpp b/Marlin/src/lcd/menu/menu_delta_calibrate.cpp index b857b62de5..195afecc1b 100644 --- a/Marlin/src/lcd/menu/menu_delta_calibrate.cpp +++ b/Marlin/src/lcd/menu/menu_delta_calibrate.cpp @@ -37,7 +37,7 @@ #endif #if ENABLED(EXTENSIBLE_UI) - #include "../../lcd/extui/ui_api.h" + #include "../extui/ui_api.h" #endif void _man_probe_pt(const xy_pos_t &xy) { diff --git a/Marlin/src/lcd/menu/menu_info.cpp b/Marlin/src/lcd/menu/menu_info.cpp index d00909c7b3..cecccd115d 100644 --- a/Marlin/src/lcd/menu/menu_info.cpp +++ b/Marlin/src/lcd/menu/menu_info.cpp @@ -100,7 +100,7 @@ void menu_info_thermistors() { START_SCREEN(); - #if EXTRUDERS + #if HAS_EXTRUDERS #define THERMISTOR_ID TEMP_SENSOR_0 #include "../thermistornames.h" STATIC_ITEM_P(PSTR(LCD_STR_E0 ": " THERMISTOR_NAME), SS_INVERT); @@ -171,7 +171,7 @@ void menu_info_thermistors() { PSTRING_ITEM(MSG_INFO_MAX_TEMP, STRINGIFY(HEATER_7_MAXTEMP), SS_LEFT); #endif - #if EXTRUDERS + #if HAS_EXTRUDERS STATIC_ITEM(TERN(WATCH_HOTENDS, MSG_INFO_RUNAWAY_ON, MSG_INFO_RUNAWAY_OFF), SS_LEFT); #endif @@ -278,7 +278,7 @@ void menu_info() { #else SUBMENU(MSG_INFO_PRINTER_MENU, menu_info_printer); // Printer Info > SUBMENU(MSG_INFO_BOARD_MENU, menu_info_board); // Board Info > - #if EXTRUDERS + #if HAS_EXTRUDERS SUBMENU(MSG_INFO_THERMISTOR_MENU, menu_info_thermistors); // Thermistors > #endif #endif diff --git a/Marlin/src/lcd/menu/menu_main.cpp b/Marlin/src/lcd/menu/menu_main.cpp index 34d1d6c6f4..aad9161b75 100644 --- a/Marlin/src/lcd/menu/menu_main.cpp +++ b/Marlin/src/lcd/menu/menu_main.cpp @@ -47,7 +47,7 @@ #endif #if ENABLED(MMU2_MENUS) - #include "../../lcd/menu/menu_mmu2.h" + #include "menu_mmu2.h" #endif #if ENABLED(PASSWORD_FEATURE) diff --git a/Marlin/src/lcd/menu/menu_mmu2.cpp b/Marlin/src/lcd/menu/menu_mmu2.cpp index af3d9232b2..425a8ca751 100644 --- a/Marlin/src/lcd/menu/menu_mmu2.cpp +++ b/Marlin/src/lcd/menu/menu_mmu2.cpp @@ -37,8 +37,7 @@ inline void action_mmu2_load_filament_to_nozzle(const uint8_t tool) { ui.reset_status(); ui.return_to_status(); ui.status_printf_P(0, GET_TEXT(MSG_MMU2_LOADING_FILAMENT), int(tool + 1)); - if (mmu2.load_filament_to_nozzle(tool)) - ui.reset_status(); + if (mmu2.load_filament_to_nozzle(tool)) ui.reset_status(); ui.return_to_status(); } diff --git a/Marlin/src/lcd/menu/menu_motion.cpp b/Marlin/src/lcd/menu/menu_motion.cpp index 6bf6df1897..06d635ffc8 100644 --- a/Marlin/src/lcd/menu/menu_motion.cpp +++ b/Marlin/src/lcd/menu/menu_motion.cpp @@ -94,14 +94,14 @@ void lcd_move_z() { _lcd_move_xyz(GET_TEXT(MSG_MOVE_Z), Z_AXIS); } #if E_MANUAL - static void lcd_move_e(TERN_(MULTI_MANUAL, const int8_t eindex=-1)) { + static void lcd_move_e(TERN_(MULTI_E_MANUAL, const int8_t eindex=-1)) { if (ui.use_click()) return ui.goto_previous_screen_no_defer(); if (ui.encoderPosition) { if (!ui.manual_move.processing) { const float diff = float(int32_t(ui.encoderPosition)) * ui.manual_move.menu_scale; TERN(IS_KINEMATIC, ui.manual_move.offset, current_position.e) += diff; ui.manual_move.soon(E_AXIS - #if MULTI_MANUAL + #if MULTI_E_MANUAL , eindex #endif ); @@ -110,9 +110,9 @@ void lcd_move_z() { _lcd_move_xyz(GET_TEXT(MSG_MOVE_Z), Z_AXIS); } ui.encoderPosition = 0; } if (ui.should_draw()) { - TERN_(MULTI_MANUAL, MenuItemBase::init(eindex)); + TERN_(MULTI_E_MANUAL, MenuItemBase::init(eindex)); MenuEditItemBase::draw_edit_screen( - GET_TEXT(TERN(MULTI_MANUAL, MSG_MOVE_EN, MSG_MOVE_E)), + GET_TEXT(TERN(MULTI_E_MANUAL, MSG_MOVE_EN, MSG_MOVE_E)), ftostr41sign(current_position.e PLUS_TERN0(IS_KINEMATIC, ui.manual_move.offset) MINUS_TERN0(MANUAL_E_MOVES_RELATIVE, manual_move_e_origin) @@ -188,7 +188,7 @@ void _menu_move_distance(const AxisEnum axis, const screenFunc_t func, const int #if E_MANUAL inline void _goto_menu_move_distance_e() { - ui.goto_screen([]{ _menu_move_distance(E_AXIS, []{ lcd_move_e(TERN_(MULTI_MANUAL, active_extruder)); }, -1); }); + ui.goto_screen([]{ _menu_move_distance(E_AXIS, []{ lcd_move_e(TERN_(MULTI_E_MANUAL, active_extruder)); }, -1); }); } inline void _menu_move_distance_e_maybe() { @@ -283,7 +283,7 @@ void menu_move() { SUBMENU_MOVE_E(E_MANUAL - 1); #endif - #elif MULTI_MANUAL + #elif MULTI_E_MANUAL // Independent extruders with one E-stepper per hotend LOOP_L_N(n, E_MANUAL) SUBMENU_MOVE_E(n); diff --git a/Marlin/src/lcd/menu/menu_tune.cpp b/Marlin/src/lcd/menu/menu_tune.cpp index 1a972f63f2..3a0d0c81ca 100644 --- a/Marlin/src/lcd/menu/menu_tune.cpp +++ b/Marlin/src/lcd/menu/menu_tune.cpp @@ -195,7 +195,7 @@ void menu_tune() { // // Flow: // - #if EXTRUDERS + #if HAS_EXTRUDERS EDIT_ITEM(int3, MSG_FLOW, &planner.flow_percentage[active_extruder], 10, 999, []{ planner.refresh_e_factor(active_extruder); }); // Flow En: #if HAS_MULTI_EXTRUDER diff --git a/Marlin/src/lcd/menu/menu_ubl.cpp b/Marlin/src/lcd/menu/menu_ubl.cpp index 1171837a57..880b76ff76 100644 --- a/Marlin/src/lcd/menu/menu_ubl.cpp +++ b/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_ENUM); } inline int32_t grid_index(const uint8_t x, const uint8_t y) { diff --git a/Marlin/src/lcd/tft/ui_1024x600.cpp b/Marlin/src/lcd/tft/ui_1024x600.cpp index 3b12ab2b60..87b016b1ec 100644 --- a/Marlin/src/lcd/tft/ui_1024x600.cpp +++ b/Marlin/src/lcd/tft/ui_1024x600.cpp @@ -725,7 +725,7 @@ static void moveAxis(const AxisEnum axis, const int8_t direction) { #endif ui.manual_move.soon(axis - #if MULTI_MANUAL + #if MULTI_E_MANUAL , motionAxisState.e_selection #endif ); diff --git a/Marlin/src/lcd/tft/ui_320x240.cpp b/Marlin/src/lcd/tft/ui_320x240.cpp index 31665fdc33..89a127b01e 100644 --- a/Marlin/src/lcd/tft/ui_320x240.cpp +++ b/Marlin/src/lcd/tft/ui_320x240.cpp @@ -710,7 +710,7 @@ static void moveAxis(const AxisEnum axis, const int8_t direction) { #endif ui.manual_move.soon(axis - #if MULTI_MANUAL + #if MULTI_E_MANUAL , motionAxisState.e_selection #endif ); diff --git a/Marlin/src/lcd/tft/ui_480x320.cpp b/Marlin/src/lcd/tft/ui_480x320.cpp index a5539990d5..6923bdd71c 100644 --- a/Marlin/src/lcd/tft/ui_480x320.cpp +++ b/Marlin/src/lcd/tft/ui_480x320.cpp @@ -712,7 +712,7 @@ static void moveAxis(const AxisEnum axis, const int8_t direction) { #endif ui.manual_move.soon(axis - #if MULTI_MANUAL + #if MULTI_E_MANUAL , motionAxisState.e_selection #endif ); diff --git a/Marlin/src/libs/L64XX/L64XX_Marlin.cpp b/Marlin/src/libs/L64XX/L64XX_Marlin.cpp index 8f71d52ec8..a6aed2ad24 100644 --- a/Marlin/src/libs/L64XX/L64XX_Marlin.cpp +++ b/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'); @@ -445,12 +445,7 @@ uint8_t L64XX_Marlin::get_user_input(uint8_t &driver_count, L64XX_axis_t axis_in position_min = X_center - displacement; position_max = X_center + displacement; echo_min_max('X', position_min, position_max); - if (false - #if HAS_ENDSTOPS - || position_min < (X_MIN_POS) - || position_max > (X_MAX_POS) - #endif - ) { + if (TERN0(HAS_ENDSTOPS, position_min < (X_MIN_POS) || position_max > (X_MAX_POS))) { err_out_of_bounds(); return true; } @@ -460,12 +455,7 @@ uint8_t L64XX_Marlin::get_user_input(uint8_t &driver_count, L64XX_axis_t axis_in position_min = Y_center - displacement; position_max = Y_center + displacement; echo_min_max('Y', position_min, position_max); - if (false - #if HAS_ENDSTOPS - || position_min < (Y_MIN_POS) - || position_max > (Y_MAX_POS) - #endif - ) { + if (TERN0(HAS_ENDSTOPS, position_min < (Y_MIN_POS) || position_max > (Y_MAX_POS))) { err_out_of_bounds(); return true; } @@ -475,12 +465,7 @@ uint8_t L64XX_Marlin::get_user_input(uint8_t &driver_count, L64XX_axis_t axis_in position_min = Z_center - displacement; position_max = Z_center + displacement; echo_min_max('Z', position_min, position_max); - if (false - #if HAS_ENDSTOPS - || position_min < (Z_MIN_POS) - || position_max > (Z_MAX_POS) - #endif - ) { + if (TERN0(HAS_ENDSTOPS, position_min < (Z_MIN_POS) || position_max > (Z_MAX_POS))) { err_out_of_bounds(); return true; } diff --git a/Marlin/src/module/endstops.cpp b/Marlin/src/module/endstops.cpp index d7f728ad4b..dff0b6832a 100644 --- a/Marlin/src/module/endstops.cpp +++ b/Marlin/src/module/endstops.cpp @@ -56,12 +56,12 @@ Endstops endstops; // private: bool Endstops::enabled, Endstops::enabled_globally; // Initialized by settings.load() -volatile uint8_t Endstops::hit_state; -Endstops::esbits_t Endstops::live_state = 0; +volatile Endstops::endstop_mask_t Endstops::hit_state; +Endstops::endstop_mask_t Endstops::live_state = 0; #if ENDSTOP_NOISE_THRESHOLD - Endstops::esbits_t Endstops::validated_live_state; + Endstops::endstop_mask_t Endstops::validated_live_state; uint8_t Endstops::endstop_poll_count; #endif @@ -356,7 +356,7 @@ void Endstops::resync() { #endif void Endstops::event_handler() { - static uint8_t prev_hit_state; // = 0 + static endstop_mask_t prev_hit_state; // = 0 if (hit_state == prev_hit_state) return; prev_hit_state = hit_state; if (hit_state) { @@ -364,15 +364,14 @@ void Endstops::event_handler() { char chrX = ' ', chrY = ' ', chrZ = ' ', chrP = ' '; #define _SET_STOP_CHAR(A,C) (chr## A = C) #else - #define _SET_STOP_CHAR(A,C) ; + #define _SET_STOP_CHAR(A,C) NOOP #endif #define _ENDSTOP_HIT_ECHO(A,C) do{ \ - SERIAL_ECHOPAIR(" " STRINGIFY(A) ":", planner.triggered_position_mm(_AXIS(A))); \ - _SET_STOP_CHAR(A,C); }while(0) + SERIAL_ECHOPAIR(" " STRINGIFY(A) ":", planner.triggered_position_mm(_AXIS(A))); _SET_STOP_CHAR(A,C); }while(0) #define _ENDSTOP_HIT_TEST(A,C) \ - if (TEST(hit_state, A ##_MIN) || TEST(hit_state, A ##_MAX)) \ + if (TERN0(HAS_##A##_MIN, TEST(hit_state, A##_MIN)) || TERN0(HAS_##A##_MAX, TEST(hit_state, A##_MAX))) \ _ENDSTOP_HIT_ECHO(A,C) #define ENDSTOP_HIT_TEST_X() _ENDSTOP_HIT_TEST(X,'X') @@ -404,12 +403,21 @@ void Endstops::event_handler() { } } +#if GCC_VERSION <= 50000 + #pragma GCC diagnostic push + #pragma GCC diagnostic ignored "-Wunused-function" +#endif + static void print_es_state(const bool is_hit, PGM_P const label=nullptr) { if (label) SERIAL_ECHOPGM_P(label); SERIAL_ECHOPGM(": "); SERIAL_ECHOLNPGM_P(is_hit ? PSTR(STR_ENDSTOP_HIT) : PSTR(STR_ENDSTOP_OPEN)); } +#if GCC_VERSION <= 50000 + #pragma GCC diagnostic pop +#endif + void _O2 Endstops::report_states() { TERN_(BLTOUCH, bltouch._set_SW_mode()); SERIAL_ECHOLNPGM(STR_M119_REPORT); @@ -508,20 +516,14 @@ void Endstops::update() { #define UPDATE_ENDSTOP_BIT(AXIS, MINMAX) SET_BIT_TO(live_state, _ENDSTOP(AXIS, MINMAX), (READ(_ENDSTOP_PIN(AXIS, MINMAX)) != _ENDSTOP_INVERTING(AXIS, MINMAX))) #define COPY_LIVE_STATE(SRC_BIT, DST_BIT) SET_BIT_TO(live_state, DST_BIT, TEST(live_state, SRC_BIT)) - #if ENABLED(G38_PROBE_TARGET) && PIN_EXISTS(Z_MIN_PROBE) && NONE(CORE_IS_XY, CORE_IS_XZ, MARKFORGED_XY) + #if BOTH(G38_PROBE_TARGET, HAS_Z_MIN_PROBE_PIN) && NONE(CORE_IS_XY, CORE_IS_XZ, MARKFORGED_XY) // If G38 command is active check Z_MIN_PROBE for ALL movement if (G38_move) UPDATE_ENDSTOP_BIT(Z, MIN_PROBE); #endif // With Dual X, endstops are only checked in the homing direction for the active extruder - #if ENABLED(DUAL_X_CARRIAGE) - #define E0_ACTIVE stepper.last_moved_extruder == 0 - #define X_MIN_TEST() ((X_HOME_DIR < 0 && E0_ACTIVE) || (X2_HOME_DIR < 0 && !E0_ACTIVE)) - #define X_MAX_TEST() ((X_HOME_DIR > 0 && E0_ACTIVE) || (X2_HOME_DIR > 0 && !E0_ACTIVE)) - #else - #define X_MIN_TEST() true - #define X_MAX_TEST() true - #endif + #define X_MIN_TEST() TERN1(DUAL_X_CARRIAGE, TERN0(X_HOME_TO_MIN, stepper.last_moved_extruder == 0) || TERN0(X2_HOME_TO_MIN, stepper.last_moved_extruder != 0)) + #define X_MAX_TEST() TERN1(DUAL_X_CARRIAGE, TERN0(X_HOME_TO_MAX, stepper.last_moved_extruder == 0) || TERN0(X2_HOME_TO_MAX, stepper.last_moved_extruder != 0)) // Use HEAD for core axes, AXIS for others #if ANY(CORE_IS_XY, CORE_IS_XZ, MARKFORGED_XY) @@ -659,7 +661,7 @@ void Endstops::update() { * still exist. The only way to reduce them further is to increase the number of samples. * To reduce the chance to 1% (1/128th) requires 7 samples (adding 7ms of delay). */ - static esbits_t old_live_state; + static endstop_mask_t old_live_state; if (old_live_state != live_state) { endstop_poll_count = ENDSTOP_NOISE_THRESHOLD; old_live_state = live_state; @@ -747,7 +749,7 @@ void Endstops::update() { #define PROCESS_ENDSTOP_Z(MINMAX) PROCESS_DUAL_ENDSTOP(Z, MINMAX) #endif - #if ENABLED(G38_PROBE_TARGET) && PIN_EXISTS(Z_MIN_PROBE) && NONE(CORE_IS_XY, CORE_IS_XZ, MARKFORGED_XY) + #if BOTH(G38_PROBE_TARGET, HAS_Z_MIN_PROBE_PIN) && NONE(CORE_IS_XY, CORE_IS_XZ, MARKFORGED_XY) #if ENABLED(G38_PROBE_AWAY) #define _G38_OPEN_STATE (G38_move >= 4) #else @@ -766,7 +768,7 @@ void Endstops::update() { if (stepper.axis_is_moving(X_AXIS)) { if (stepper.motor_direction(X_AXIS_HEAD)) { // -direction - #if HAS_X_MIN || (X_SPI_SENSORLESS && X_HOME_DIR < 0) + #if HAS_X_MIN || (X_SPI_SENSORLESS && X_HOME_TO_MIN) PROCESS_ENDSTOP_X(MIN); #if CORE_DIAG(XY, Y, MIN) PROCESS_CORE_ENDSTOP(Y,MIN,X,MIN); @@ -780,7 +782,7 @@ void Endstops::update() { #endif } else { // +direction - #if HAS_X_MAX || (X_SPI_SENSORLESS && X_HOME_DIR > 0) + #if HAS_X_MAX || (X_SPI_SENSORLESS && X_HOME_TO_MAX) PROCESS_ENDSTOP_X(MAX); #if CORE_DIAG(XY, Y, MIN) PROCESS_CORE_ENDSTOP(Y,MIN,X,MAX); @@ -797,7 +799,7 @@ void Endstops::update() { if (stepper.axis_is_moving(Y_AXIS)) { if (stepper.motor_direction(Y_AXIS_HEAD)) { // -direction - #if HAS_Y_MIN || (Y_SPI_SENSORLESS && Y_HOME_DIR < 0) + #if HAS_Y_MIN || (Y_SPI_SENSORLESS && Y_HOME_TO_MIN) PROCESS_ENDSTOP_Y(MIN); #if CORE_DIAG(XY, X, MIN) PROCESS_CORE_ENDSTOP(X,MIN,Y,MIN); @@ -811,7 +813,7 @@ void Endstops::update() { #endif } else { // +direction - #if HAS_Y_MAX || (Y_SPI_SENSORLESS && Y_HOME_DIR > 0) + #if HAS_Y_MAX || (Y_SPI_SENSORLESS && Y_HOME_TO_MAX) PROCESS_ENDSTOP_Y(MAX); #if CORE_DIAG(XY, X, MIN) PROCESS_CORE_ENDSTOP(X,MIN,Y,MAX); @@ -829,7 +831,7 @@ void Endstops::update() { if (stepper.axis_is_moving(Z_AXIS)) { if (stepper.motor_direction(Z_AXIS_HEAD)) { // Z -direction. Gantry down, bed up. - #if HAS_Z_MIN || (Z_SPI_SENSORLESS && Z_HOME_DIR < 0) + #if HAS_Z_MIN || (Z_SPI_SENSORLESS && Z_HOME_TO_MIN) if ( TERN1(Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN, z_probe_enabled) && TERN1(HAS_CUSTOM_PROBE_PIN, !z_probe_enabled) ) PROCESS_ENDSTOP_Z(MIN); @@ -850,7 +852,7 @@ void Endstops::update() { #endif } else { // Z +direction. Gantry up, bed down. - #if HAS_Z_MAX || (Z_SPI_SENSORLESS && Z_HOME_DIR > 0) + #if HAS_Z_MAX || (Z_SPI_SENSORLESS && Z_HOME_TO_MAX) #if ENABLED(Z_MULTI_ENDSTOPS) PROCESS_ENDSTOP_Z(MAX); #elif !HAS_CUSTOM_PROBE_PIN || Z_MAX_PIN != Z_MIN_PROBE_PIN // No probe or probe is Z_MIN || Probe is not Z_MAX diff --git a/Marlin/src/module/endstops.h b/Marlin/src/module/endstops.h index 13e814aa1f..5da09f41cf 100644 --- a/Marlin/src/module/endstops.h +++ b/Marlin/src/module/endstops.h @@ -28,50 +28,89 @@ #include "../inc/MarlinConfig.h" #include +#define __ES_ITEM(N) N, +#define _ES_ITEM(K,N) TERN_(K,DEFER4(__ES_ITEM)(N)) + enum EndstopEnum : char { - X_MIN, Y_MIN, Z_MIN, Z_MIN_PROBE, - X_MAX, Y_MAX, Z_MAX, - X2_MIN, X2_MAX, - Y2_MIN, Y2_MAX, - Z2_MIN, Z2_MAX, - Z3_MIN, Z3_MAX, - Z4_MIN, Z4_MAX + // Common XYZ (ABC) endstops. Defined according to USE_[XYZ](MIN|MAX)_PLUG settings. + _ES_ITEM(HAS_X_MIN, X_MIN) + _ES_ITEM(HAS_X_MAX, X_MAX) + _ES_ITEM(HAS_Y_MIN, Y_MIN) + _ES_ITEM(HAS_Y_MAX, Y_MAX) + _ES_ITEM(HAS_Z_MIN, Z_MIN) + _ES_ITEM(HAS_Z_MAX, Z_MAX) + + // Extra Endstops for XYZ + #if ENABLED(X_DUAL_ENDSTOPS) + _ES_ITEM(HAS_X_MIN, X2_MIN) + _ES_ITEM(HAS_X_MAX, X2_MAX) + #endif + #if ENABLED(Y_DUAL_ENDSTOPS) + _ES_ITEM(HAS_Y_MIN, Y2_MIN) + _ES_ITEM(HAS_Y_MAX, Y2_MAX) + #endif + #if ENABLED(Z_MULTI_ENDSTOPS) + _ES_ITEM(HAS_Z_MIN, Z2_MIN) + _ES_ITEM(HAS_Z_MAX, Z2_MAX) + #if NUM_Z_STEPPER_DRIVERS >= 3 + _ES_ITEM(HAS_Z_MIN, Z3_MIN) + _ES_ITEM(HAS_Z_MAX, Z3_MAX) + #endif + #if NUM_Z_STEPPER_DRIVERS >= 4 + _ES_ITEM(HAS_Z_MIN, Z4_MIN) + _ES_ITEM(HAS_Z_MAX, Z4_MAX) + #endif + #endif + + // Bed Probe state is distinct or shared with Z_MIN (i.e., when the probe is the only Z endstop) + _ES_ITEM(HAS_BED_PROBE, Z_MIN_PROBE IF_DISABLED(HAS_CUSTOM_PROBE_PIN, = Z_MIN)) + + // The total number of states + NUM_ENDSTOP_STATES + + // Endstops can be either MIN or MAX but not both + #if HAS_X_MIN || HAS_X_MAX + , X_ENDSTOP = TERN(X_HOME_TO_MAX, X_MAX, X_MIN) + #endif + #if HAS_Y_MIN || HAS_Y_MAX + , Y_ENDSTOP = TERN(Y_HOME_TO_MAX, Y_MAX, Y_MIN) + #endif + #if HAS_Z_MIN || HAS_Z_MAX + , Z_ENDSTOP = TERN(Z_HOME_TO_MAX, Z_MAX, TERN(HOMING_Z_WITH_PROBE, Z_MIN_PROBE, Z_MIN)) + #endif }; -#define X_ENDSTOP (x_home_dir(active_extruder) < 0 ? X_MIN : X_MAX) -#define Y_ENDSTOP (Y_HOME_DIR < 0 ? Y_MIN : Y_MAX) -#define Z_ENDSTOP (Z_HOME_DIR < 0 ? TERN(HOMING_Z_WITH_PROBE, Z_MIN, Z_MIN_PROBE) : Z_MAX) +#undef __ES_ITEM +#undef _ES_ITEM class Endstops { public: - #if HAS_EXTRA_ENDSTOPS - typedef uint16_t esbits_t; - #if ENABLED(X_DUAL_ENDSTOPS) - static float x2_endstop_adj; - #endif - #if ENABLED(Y_DUAL_ENDSTOPS) - static float y2_endstop_adj; - #endif - #if ENABLED(Z_MULTI_ENDSTOPS) - static float z2_endstop_adj; - #endif - #if ENABLED(Z_MULTI_ENDSTOPS) && NUM_Z_STEPPER_DRIVERS >= 3 - static float z3_endstop_adj; - #endif - #if ENABLED(Z_MULTI_ENDSTOPS) && NUM_Z_STEPPER_DRIVERS >= 4 - static float z4_endstop_adj; - #endif - #else - typedef uint8_t esbits_t; + + typedef IF<(NUM_ENDSTOP_STATES > 8), uint16_t, uint8_t>::type endstop_mask_t; + + #if ENABLED(X_DUAL_ENDSTOPS) + static float x2_endstop_adj; + #endif + #if ENABLED(Y_DUAL_ENDSTOPS) + static float y2_endstop_adj; + #endif + #if ENABLED(Z_MULTI_ENDSTOPS) + static float z2_endstop_adj; + #endif + #if ENABLED(Z_MULTI_ENDSTOPS) && NUM_Z_STEPPER_DRIVERS >= 3 + static float z3_endstop_adj; + #endif + #if ENABLED(Z_MULTI_ENDSTOPS) && NUM_Z_STEPPER_DRIVERS >= 4 + static float z4_endstop_adj; #endif private: static bool enabled, enabled_globally; - static esbits_t live_state; - static volatile uint8_t hit_state; // Use X_MIN, Y_MIN, Z_MIN and Z_MIN_PROBE as BIT index + static endstop_mask_t live_state; + static volatile endstop_mask_t hit_state; // Use X_MIN, Y_MIN, Z_MIN and Z_MIN_PROBE as BIT index #if ENDSTOP_NOISE_THRESHOLD - static esbits_t validated_live_state; + static endstop_mask_t validated_live_state; static uint8_t endstop_poll_count; // Countdown from threshold for polling #endif @@ -107,12 +146,12 @@ class Endstops { /** * Get Endstop hit state. */ - FORCE_INLINE static uint8_t trigger_state() { return hit_state; } + FORCE_INLINE static endstop_mask_t trigger_state() { return hit_state; } /** * Get current endstops state */ - FORCE_INLINE static esbits_t state() { + FORCE_INLINE static endstop_mask_t state() { return #if ENDSTOP_NOISE_THRESHOLD validated_live_state diff --git a/Marlin/src/module/motion.cpp b/Marlin/src/module/motion.cpp index 171d9520cb..235a969f66 100644 --- a/Marlin/src/module/motion.cpp +++ b/Marlin/src/module/motion.cpp @@ -83,13 +83,13 @@ bool relative_mode; // = false; * Used by 'line_to_current_position' to do a move after changing it. * Used by 'sync_plan_position' to update 'planner.position'. */ -xyze_pos_t current_position = { X_HOME_POS, Y_HOME_POS, - #ifdef Z_IDLE_HEIGHT - Z_IDLE_HEIGHT - #else - Z_HOME_POS - #endif -}; +#ifdef Z_IDLE_HEIGHT + #define Z_INIT_POS Z_IDLE_HEIGHT +#else + #define Z_INIT_POS Z_HOME_POS +#endif + +xyze_pos_t current_position = { X_HOME_POS, Y_HOME_POS, Z_INIT_POS }; /** * Cartesian Destination @@ -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 @@ -204,11 +204,7 @@ void report_real_position() { get_cartesian_from_steppers(); xyze_pos_t npos = cartes; npos.e = planner.get_axis_position_mm(E_AXIS); - - #if HAS_POSITION_MODIFIERS - planner.unapply_modifiers(npos, true); - #endif - + TERN_(HAS_POSITION_MODIFIERS, planner.unapply_modifiers(npos, true)); report_logical_position(npos); report_more_positions(); } @@ -286,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_ENUM); sync_plan_position(); } @@ -364,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_ENUM) current_position = pos; else current_position[axis] = pos[axis]; @@ -378,7 +374,7 @@ void line_to_current_position(const_feedRate_t fr_mm_s/*=feedrate_mm_s*/) { planner.buffer_line(current_position, fr_mm_s, active_extruder); } -#if EXTRUDERS +#if HAS_EXTRUDERS void unscaled_e_move(const_float_t length, const_feedRate_t fr_mm_s) { TERN_(HAS_FILAMENT_SENSOR, runout.reset()); current_position.e += length / planner.e_factor[active_extruder]; @@ -425,7 +421,7 @@ void _internal_move_to_destination(const_feedRate_t fr_mm_s/*=0.0f*/ const uint16_t old_pct = feedrate_percentage; feedrate_percentage = 100; - #if EXTRUDERS + #if HAS_EXTRUDERS const float old_fac = planner.e_factor[active_extruder]; planner.e_factor[active_extruder] = 1.0f; #endif @@ -437,7 +433,7 @@ void _internal_move_to_destination(const_feedRate_t fr_mm_s/*=0.0f*/ feedrate_mm_s = old_feedrate; feedrate_percentage = old_pct; - #if EXTRUDERS + #if HAS_EXTRUDERS planner.e_factor[active_extruder] = old_fac; #endif } @@ -685,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]); } /** @@ -1185,18 +1181,20 @@ void prepare_line_to_destination() { #if HAS_ENDSTOPS - uint8_t axis_homed, axis_trusted; // = 0 + linear_axis_bits_t axis_homed, axis_trusted; // = 0 - uint8_t axes_should_home(uint8_t axis_bits/*=0x07*/) { - #define SHOULD_HOME(A) TERN(HOME_AFTER_DEACTIVATE, axis_is_trusted, axis_was_homed)(A) - // Clear test bits that are trusted - if (TEST(axis_bits, X_AXIS) && SHOULD_HOME(X_AXIS)) CBI(axis_bits, X_AXIS); - if (TEST(axis_bits, Y_AXIS) && SHOULD_HOME(Y_AXIS)) CBI(axis_bits, Y_AXIS); - if (TEST(axis_bits, Z_AXIS) && SHOULD_HOME(Z_AXIS)) CBI(axis_bits, Z_AXIS); + linear_axis_bits_t axes_should_home(linear_axis_bits_t axis_bits/*=linear_bits*/) { + auto set_should = [](linear_axis_bits_t &b, AxisEnum a) { + if (TEST(b, a) && TERN(HOME_AFTER_DEACTIVATE, axis_is_trusted, axis_was_homed)(a)) + CBI(b, a); + }; + set_should(axis_bits, X_AXIS); // Clear test bits that are trusted + set_should(axis_bits, Y_AXIS); + set_should(axis_bits, Z_AXIS); return axis_bits; } - bool homing_needed_error(uint8_t axis_bits/*=0x07*/) { + bool homing_needed_error(linear_axis_bits_t axis_bits/*=linear_bits*/) { if ((axis_bits = axes_should_home(axis_bits))) { PGM_P home_first = GET_TEXT(MSG_HOME_FIRST); char msg[strlen_P(home_first)+1]; @@ -1380,7 +1378,7 @@ void prepare_line_to_destination() { // Only do some things when moving towards an endstop const int8_t axis_home_dir = TERN0(DUAL_X_CARRIAGE, axis == X_AXIS) - ? x_home_dir(active_extruder) : home_dir(axis); + ? TOOL_X_HOME_DIR(active_extruder) : home_dir(axis); const bool is_home_dir = (axis_home_dir > 0) == (distance > 0); #if ENABLED(SENSORLESS_HOMING) @@ -1564,8 +1562,8 @@ void prepare_line_to_destination() { #define _CAN_HOME(A) (axis == _AXIS(A) && ( \ ENABLED(A##_SPI_SENSORLESS) \ || (_AXIS(A) == Z_AXIS && ENABLED(HOMING_Z_WITH_PROBE)) \ - || (A##_MIN_PIN > -1 && A##_HOME_DIR < 0) \ - || (A##_MAX_PIN > -1 && A##_HOME_DIR > 0) \ + || TERN0(A##_HOME_TO_MIN, A##_MIN_PIN > -1) \ + || TERN0(A##_HOME_TO_MAX, A##_MAX_PIN > -1) \ )) if (!_CAN_HOME(X) && !_CAN_HOME(Y) && !_CAN_HOME(Z)) return; #endif @@ -1573,7 +1571,7 @@ void prepare_line_to_destination() { if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR(">>> homeaxis(", AS_CHAR(axis_codes[axis]), ")"); const int axis_home_dir = TERN0(DUAL_X_CARRIAGE, axis == X_AXIS) - ? x_home_dir(active_extruder) : home_dir(axis); + ? TOOL_X_HOME_DIR(active_extruder) : home_dir(axis); // // Homing Z with a probe? Raise Z (maybe) and deploy the Z probe. @@ -1918,7 +1916,7 @@ void set_axis_is_at_home(const AxisEnum axis) { /** * Z Probe Z Homing? Account for the probe's Z offset. */ - #if HAS_BED_PROBE && Z_HOME_DIR < 0 + #if HAS_BED_PROBE && Z_HOME_TO_MIN if (axis == Z_AXIS) { #if HOMING_Z_WITH_PROBE @@ -1955,7 +1953,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 diff --git a/Marlin/src/module/motion.h b/Marlin/src/module/motion.h index e01978c852..a43af6446b 100644 --- a/Marlin/src/module/motion.h +++ b/Marlin/src/module/motion.h @@ -272,7 +272,7 @@ void sync_plan_position_e(); */ void line_to_current_position(const_feedRate_t fr_mm_s=feedrate_mm_s); -#if EXTRUDERS +#if HAS_EXTRUDERS void unscaled_e_move(const_float_t length, const_feedRate_t fr_mm_s); #endif @@ -326,7 +326,8 @@ void do_z_clearance(const_float_t zclear, const bool lower_allowed=false); /** * Homing and Trusted Axes */ -constexpr uint8_t xyz_bits = _BV(X_AXIS) | _BV(Y_AXIS) | _BV(Z_AXIS); +typedef IF<(LINEAR_AXES>8), uint16_t, uint8_t>::type linear_axis_bits_t; +constexpr linear_axis_bits_t linear_bits = _BV(LINEAR_AXES) - 1; void set_axis_is_at_home(const AxisEnum axis); @@ -340,23 +341,23 @@ void set_axis_is_at_home(const AxisEnum axis); * Flags that the position is trusted in each linear axis. Set when homed. * Cleared whenever a stepper powers off, potentially losing its position. */ - extern uint8_t axis_homed, axis_trusted; + extern linear_axis_bits_t axis_homed, axis_trusted; void homeaxis(const AxisEnum axis); void set_axis_never_homed(const AxisEnum axis); - uint8_t axes_should_home(uint8_t axis_bits=0x07); - bool homing_needed_error(uint8_t axis_bits=0x07); + linear_axis_bits_t axes_should_home(linear_axis_bits_t axis_bits=linear_bits); + bool homing_needed_error(linear_axis_bits_t axis_bits=linear_bits); FORCE_INLINE void set_axis_unhomed(const AxisEnum axis) { CBI(axis_homed, axis); } FORCE_INLINE void set_axis_untrusted(const AxisEnum axis) { CBI(axis_trusted, axis); } FORCE_INLINE void set_all_unhomed() { axis_homed = axis_trusted = 0; } FORCE_INLINE void set_axis_homed(const AxisEnum axis) { SBI(axis_homed, axis); } FORCE_INLINE void set_axis_trusted(const AxisEnum axis) { SBI(axis_trusted, axis); } - FORCE_INLINE void set_all_homed() { axis_homed = axis_trusted = xyz_bits; } + FORCE_INLINE void set_all_homed() { axis_homed = axis_trusted = linear_bits; } #else - constexpr uint8_t axis_homed = xyz_bits, axis_trusted = xyz_bits; // Zero-endstop machines are always homed and trusted + constexpr linear_axis_bits_t axis_homed = linear_bits, axis_trusted = linear_bits; // Zero-endstop machines are always homed and trusted FORCE_INLINE void homeaxis(const AxisEnum axis) {} FORCE_INLINE void set_axis_never_homed(const AxisEnum) {} - FORCE_INLINE uint8_t axes_should_home(uint8_t=0x07) { return false; } - FORCE_INLINE bool homing_needed_error(uint8_t=0x07) { return false; } + FORCE_INLINE linear_axis_bits_t axes_should_home(linear_axis_bits_t=linear_bits) { return false; } + FORCE_INLINE bool homing_needed_error(linear_axis_bits_t=linear_bits) { return false; } FORCE_INLINE void set_axis_unhomed(const AxisEnum axis) {} FORCE_INLINE void set_axis_untrusted(const AxisEnum axis) {} FORCE_INLINE void set_all_unhomed() {} @@ -369,9 +370,9 @@ FORCE_INLINE bool axis_was_homed(const AxisEnum axis) { return TEST(axis_h FORCE_INLINE bool axis_is_trusted(const AxisEnum axis) { return TEST(axis_trusted, axis); } FORCE_INLINE bool axis_should_home(const AxisEnum axis) { return (axes_should_home() & _BV(axis)) != 0; } FORCE_INLINE bool no_axes_homed() { return !axis_homed; } -FORCE_INLINE bool all_axes_homed() { return xyz_bits == (axis_homed & xyz_bits); } +FORCE_INLINE bool all_axes_homed() { return linear_bits == (axis_homed & linear_bits); } FORCE_INLINE bool homing_needed() { return !all_axes_homed(); } -FORCE_INLINE bool all_axes_trusted() { return xyz_bits == (axis_trusted & xyz_bits); } +FORCE_INLINE bool all_axes_trusted() { return linear_bits == (axis_trusted & linear_bits); } #if ENABLED(NO_MOTION_BEFORE_HOMING) #define MOTION_CONDITIONS (IsRunning() && !homing_needed_error()) @@ -516,7 +517,7 @@ FORCE_INLINE bool all_axes_trusted() { return xyz_bits == float x_home_pos(const uint8_t extruder); - FORCE_INLINE int x_home_dir(const uint8_t extruder) { return extruder ? X2_HOME_DIR : X_HOME_DIR; } + #define TOOL_X_HOME_DIR(T) ((T) ? X2_HOME_DIR : X_HOME_DIR) void set_duplication_enabled(const bool dupe, const int8_t tool_index=-1); void idex_set_mirrored_mode(const bool mirr); @@ -530,7 +531,7 @@ FORCE_INLINE bool all_axes_trusted() { return xyz_bits == FORCE_INLINE void set_duplication_enabled(const bool dupe) { extruder_duplication_enabled = dupe; } #endif - FORCE_INLINE int x_home_dir(const uint8_t) { return X_HOME_DIR; } + #define TOOL_X_HOME_DIR(T) X_HOME_DIR #endif diff --git a/Marlin/src/module/planner.cpp b/Marlin/src/module/planner.cpp index f11f273867..714be8019e 100644 --- a/Marlin/src/module/planner.cpp +++ b/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 @@ -164,7 +164,7 @@ float Planner::steps_to_mm[XYZE_N]; // (mm) Millimeters per step xyze_bool_t Planner::last_page_dir{0}; #endif -#if EXTRUDERS +#if HAS_EXTRUDERS int16_t Planner::flow_percentage[EXTRUDERS] = ARRAY_BY_EXTRUDERS1(100); // Extrusion factor for each extruder float Planner::e_factor[EXTRUDERS] = ARRAY_BY_EXTRUDERS1(1.0f); // The flow percentage and volumetric multiplier combine to scale E movement #endif @@ -1836,7 +1836,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move, db = target.b - position.b, dc = target.c - position.c; - #if EXTRUDERS + #if HAS_EXTRUDERS int32_t de = target.e - position.e; #else constexpr int32_t de = 0; @@ -1848,7 +1848,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move, " A:", target.a, " (", da, " steps)" " B:", target.b, " (", db, " steps)" " C:", target.c, " (", dc, " steps)" - #if EXTRUDERS + #if HAS_EXTRUDERS " E:", target.e, " (", de, " steps)" #endif ); @@ -1921,7 +1921,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move, #endif if (de < 0) SBI(dm, E_AXIS); - #if EXTRUDERS + #if HAS_EXTRUDERS const float esteps_float = de * e_factor[extruder]; const uint32_t esteps = ABS(esteps_float) + 0.5f; #else @@ -2003,7 +2003,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move, steps_dist_mm.c = dc * steps_to_mm[C_AXIS]; #endif - #if EXTRUDERS + #if HAS_EXTRUDERS steps_dist_mm.e = esteps_float * steps_to_mm[E_AXIS_N(extruder)]; #else steps_dist_mm.e = 0.0f; @@ -2013,7 +2013,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move, if (block->steps.a < MIN_STEPS_PER_SEGMENT && block->steps.b < MIN_STEPS_PER_SEGMENT && block->steps.c < MIN_STEPS_PER_SEGMENT) { block->millimeters = (0 - #if EXTRUDERS + #if HAS_EXTRUDERS + ABS(steps_dist_mm.e) #endif ); @@ -2046,7 +2046,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move, TERN_(BACKLASH_COMPENSATION, backlash.add_correction_steps(da, db, dc, dm, block)); } - #if EXTRUDERS + #if HAS_EXTRUDERS block->steps.e = esteps; #endif @@ -2107,7 +2107,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move, #endif // Enable extruder(s) - #if EXTRUDERS + #if HAS_EXTRUDERS if (esteps) { TERN_(AUTO_POWER_CONTROL, powerManager.power_on()); @@ -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]; @@ -2209,7 +2209,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move, } // Limit speed on extruders, if any - #if EXTRUDERS + #if HAS_EXTRUDERS { current_speed.e = steps_dist_mm.e * inverse_secs; #if HAS_MIXER_SYNC_CHANNEL @@ -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(); } diff --git a/Marlin/src/module/planner.h b/Marlin/src/module/planner.h index 30eeb758a4..66e98f4a57 100644 --- a/Marlin/src/module/planner.h +++ b/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. @@ -337,7 +337,7 @@ class Planner { static xyze_bool_t last_page_dir; // Last page direction given #endif - #if EXTRUDERS + #if HAS_EXTRUDERS static int16_t flow_percentage[EXTRUDERS]; // Extrusion factor for each extruder static float e_factor[EXTRUDERS]; // The flow percentage and volumetric multiplier combine to scale E movement #endif @@ -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 @@ -491,10 +491,10 @@ class Planner { #if HAS_CLASSIC_JERK static void set_max_jerk(const AxisEnum axis, float inMaxJerkMMS); #else - static inline void set_max_jerk(const AxisEnum, const_float_t ) {} + static inline void set_max_jerk(const AxisEnum, const_float_t) {} #endif - #if EXTRUDERS + #if HAS_EXTRUDERS FORCE_INLINE static void refresh_e_factor(const uint8_t e) { e_factor[e] = flow_percentage[e] * 0.01f * TERN(NO_VOLUMETRICS, 1.0f, volumetric_multiplier[e]); } @@ -592,9 +592,9 @@ class Planner { #else - FORCE_INLINE static float fade_scaling_factor_for_z(const_float_t ) { return 1; } + FORCE_INLINE static float fade_scaling_factor_for_z(const_float_t) { return 1; } - FORCE_INLINE static bool leveling_active_at_z(const_float_t ) { return true; } + FORCE_INLINE static bool leveling_active_at_z(const_float_t) { return true; } #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]); diff --git a/Marlin/src/module/probe.cpp b/Marlin/src/module/probe.cpp index be991c1d52..0042302fc7 100644 --- a/Marlin/src/module/probe.cpp +++ b/Marlin/src/module/probe.cpp @@ -243,7 +243,7 @@ xyz_pos_t Probe::offset; // Initialized by settings.load() #endif void Probe::set_probing_paused(const bool dopause) { - TERN_(PROBING_HEATERS_OFF, thermalManager.pause(dopause)); + TERN_(PROBING_HEATERS_OFF, thermalManager.pause_heaters(dopause)); TERN_(PROBING_FANS_OFF, thermalManager.set_fans_paused(dopause)); #if ENABLED(PROBING_STEPPERS_OFF) IF_DISABLED(DELTA, static uint8_t old_trusted); @@ -507,9 +507,9 @@ bool Probe::probe_down_to_z(const_float_t z, const_feedRate_t fr_mm_s) { // Check to see if the probe was triggered const bool probe_triggered = #if BOTH(DELTA, SENSORLESS_PROBING) - endstops.trigger_state() & (_BV(X_MIN) | _BV(Y_MIN) | _BV(Z_MIN)) + endstops.trigger_state() & (_BV(X_MAX) | _BV(Y_MAX) | _BV(Z_MAX)) #else - TEST(endstops.trigger_state(), TERN(Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN, Z_MIN, Z_MIN_PROBE)) + TEST(endstops.trigger_state(), Z_MIN_PROBE) #endif ; diff --git a/Marlin/src/module/scara.cpp b/Marlin/src/module/scara.cpp index e058804c90..07f714a997 100644 --- a/Marlin/src/module/scara.cpp +++ b/Marlin/src/module/scara.cpp @@ -221,10 +221,10 @@ float segments_per_second = TERN(AXEL_TPARA, TPARA_SEGMENTS_PER_SECOND, SCARA_SE TERN_(Z_SENSORLESS, sensorless_t stealth_states_z = start_sensorless_homing_per_axis(Z_AXIS)); #endif - // const int x_axis_home_dir = x_home_dir(active_extruder); + //const int x_axis_home_dir = TOOL_X_HOME_DIR(active_extruder); - // const xy_pos_t pos { max_length(X_AXIS) , max_length(Y_AXIS) }; - // const float mlz = max_length(X_AXIS), + //const xy_pos_t pos { max_length(X_AXIS) , max_length(Y_AXIS) }; + //const float mlz = max_length(X_AXIS), // Move all carriages together linearly until an endstop is hit. //do_blocking_move_to_xy_z(pos, mlz, homing_feedrate(Z_AXIS)); @@ -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(); } diff --git a/Marlin/src/module/settings.cpp b/Marlin/src/module/settings.cpp index 9d65bbb744..eae4728793 100644 --- a/Marlin/src/module/settings.cpp +++ b/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 @@ -402,7 +402,7 @@ typedef struct SettingsDataStruct { // // ADVANCED_PAUSE_FEATURE // - #if EXTRUDERS + #if HAS_EXTRUDERS fil_change_settings_t fc_settings[EXTRUDERS]; // M603 T U L #endif @@ -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); } @@ -584,7 +584,11 @@ void MarlinSettings::postprocess() { "ARCHIM2_SPI_FLASH_EEPROM_BACKUP_SIZE is insufficient to capture all EEPROM data."); #endif -#define DEBUG_OUT ENABLED(DEBUG_LEVELING_FEATURE) +// +// This file simply uses the DEBUG_ECHO macros to implement EEPROM_CHITCHAT. +// For deeper debugging of EEPROM issues enable DEBUG_EEPROM_READWRITE. +// +#define DEBUG_OUT EITHER(EEPROM_CHITCHAT, DEBUG_LEVELING_FEATURE) #include "../core/debug_out.h" #if ENABLED(EEPROM_SETTINGS) @@ -633,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); // @@ -1318,7 +1321,7 @@ void MarlinSettings::postprocess() { // // Advanced Pause filament load & unload lengths // - #if EXTRUDERS + #if HAS_EXTRUDERS { #if DISABLED(ADVANCED_PAUSE_FEATURE) const fil_change_settings_t fc_settings[EXTRUDERS] = { 0, 0 }; @@ -1450,8 +1453,7 @@ void MarlinSettings::postprocess() { EEPROM_WRITE(final_crc); // Report storage size - DEBUG_ECHO_START(); - DEBUG_ECHOLNPAIR("Settings Stored (", eeprom_size, " bytes; crc ", (uint32_t)final_crc, ")"); + DEBUG_ECHO_MSG("Settings Stored (", eeprom_size, " bytes; crc ", (uint32_t)final_crc, ")"); eeprom_error |= size_error(eeprom_size); } @@ -1490,8 +1492,7 @@ void MarlinSettings::postprocess() { stored_ver[0] = '?'; stored_ver[1] = '\0'; } - DEBUG_ECHO_START(); - DEBUG_ECHOLNPAIR("EEPROM version mismatch (EEPROM=", stored_ver, " Marlin=" EEPROM_VERSION ")"); + DEBUG_ECHO_MSG("EEPROM version mismatch (EEPROM=", stored_ver, " Marlin=" EEPROM_VERSION ")"); IF_DISABLED(EEPROM_AUTO_INIT, ui.eeprom_alert_version()); eeprom_error = true; } @@ -1511,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)]); @@ -1538,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)); @@ -2186,9 +2187,13 @@ void MarlinSettings::postprocess() { = DIGIPOT_MOTOR_CURRENT #endif ; - DEBUG_ECHOLNPGM("DIGIPOTS Loading"); + #if HAS_MOTOR_CURRENT_SPI + DEBUG_ECHO_MSG("DIGIPOTS Loading"); + #endif EEPROM_READ(motor_current_setting); - DEBUG_ECHOLNPGM("DIGIPOTS Loaded"); + #if HAS_MOTOR_CURRENT_SPI + DEBUG_ECHO_MSG("DIGIPOTS Loaded"); + #endif #if HAS_MOTOR_CURRENT_SPI || HAS_MOTOR_CURRENT_PWM if (!validating) COPY(stepper.motor_current_setting, motor_current_setting); @@ -2230,7 +2235,7 @@ void MarlinSettings::postprocess() { // // Advanced Pause filament load & unload lengths // - #if EXTRUDERS + #if HAS_EXTRUDERS { #if DISABLED(ADVANCED_PAUSE_FEATURE) fil_change_settings_t fc_settings[EXTRUDERS]; @@ -2357,14 +2362,12 @@ void MarlinSettings::postprocess() { // eeprom_error = size_error(eeprom_index - (EEPROM_OFFSET)); if (eeprom_error) { - DEBUG_ECHO_START(); - DEBUG_ECHOLNPAIR("Index: ", eeprom_index - (EEPROM_OFFSET), " Size: ", datasize()); + DEBUG_ECHO_MSG("Index: ", eeprom_index - (EEPROM_OFFSET), " Size: ", datasize()); IF_DISABLED(EEPROM_AUTO_INIT, ui.eeprom_alert_index()); } else if (working_crc != stored_crc) { eeprom_error = true; - DEBUG_ERROR_START(); - DEBUG_ECHOLNPAIR("EEPROM CRC mismatch - (stored) ", stored_crc, " != ", working_crc, " (calculated)!"); + DEBUG_ERROR_MSG("EEPROM CRC mismatch - (stored) ", stored_crc, " != ", working_crc, " (calculated)!"); IF_DISABLED(EEPROM_AUTO_INIT, ui.eeprom_alert_crc()); } else if (!validating) { @@ -2454,13 +2457,8 @@ void MarlinSettings::postprocess() { #if ENABLED(AUTO_BED_LEVELING_UBL) inline void ubl_invalid_slot(const int s) { - #if BOTH(EEPROM_CHITCHAT, DEBUG_OUT) - DEBUG_ECHOLNPGM("?Invalid slot."); - DEBUG_ECHO(s); - DEBUG_ECHOLNPGM(" mesh slots available."); - #else - UNUSED(s); - #endif + DEBUG_ECHOLNPAIR("?Invalid slot.\n", s, " mesh slots available."); + UNUSED(s); } const uint16_t MarlinSettings::meshes_end = persistentStore.capacity() - 129; // 128 (+1 because of the change to capacity rather than last valid address) @@ -2583,10 +2581,10 @@ 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)]); + 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)]); } planner.settings.min_segment_time_us = DEFAULT_MINSEGMENTTIME; @@ -2707,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 @@ -3857,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]); } diff --git a/Marlin/src/module/stepper.cpp b/Marlin/src/module/stepper.cpp index ff2be0c356..2e2afaeb90 100644 --- a/Marlin/src/module/stepper.cpp +++ b/Marlin/src/module/stepper.cpp @@ -259,13 +259,13 @@ xyze_int8_t Stepper::count_direction{0}; #define DUAL_ENDSTOP_APPLY_STEP(A,V) \ if (separate_multi_axis) { \ - if (A##_HOME_DIR < 0) { \ - if (!(TEST(endstops.state(), A##_MIN) && count_direction[_AXIS(A)] < 0) && !locked_##A##_motor) A##_STEP_WRITE(V); \ - if (!(TEST(endstops.state(), A##2_MIN) && count_direction[_AXIS(A)] < 0) && !locked_##A##2_motor) A##2_STEP_WRITE(V); \ + if (A##_HOME_TO_MIN) { \ + if (TERN0(HAS_##A##_MIN, !(TEST(endstops.state(), A##_MIN) && count_direction[_AXIS(A)] < 0) && !locked_##A##_motor)) A##_STEP_WRITE(V); \ + if (TERN0(HAS_##A##2_MIN, !(TEST(endstops.state(), A##2_MIN) && count_direction[_AXIS(A)] < 0) && !locked_##A##2_motor)) A##2_STEP_WRITE(V); \ } \ else { \ - if (!(TEST(endstops.state(), A##_MAX) && count_direction[_AXIS(A)] > 0) && !locked_##A##_motor) A##_STEP_WRITE(V); \ - if (!(TEST(endstops.state(), A##2_MAX) && count_direction[_AXIS(A)] > 0) && !locked_##A##2_motor) A##2_STEP_WRITE(V); \ + if (TERN0(HAS_##A##_MAX, !(TEST(endstops.state(), A##_MAX) && count_direction[_AXIS(A)] > 0) && !locked_##A##_motor)) A##_STEP_WRITE(V); \ + if (TERN0(HAS_##A##2_MAX, !(TEST(endstops.state(), A##2_MAX) && count_direction[_AXIS(A)] > 0) && !locked_##A##2_motor)) A##2_STEP_WRITE(V); \ } \ } \ else { \ @@ -285,7 +285,7 @@ xyze_int8_t Stepper::count_direction{0}; #define TRIPLE_ENDSTOP_APPLY_STEP(A,V) \ if (separate_multi_axis) { \ - if (A##_HOME_DIR < 0) { \ + if (A##_HOME_TO_MIN) { \ if (!(TEST(endstops.state(), A##_MIN) && count_direction[_AXIS(A)] < 0) && !locked_##A##_motor) A##_STEP_WRITE(V); \ if (!(TEST(endstops.state(), A##2_MIN) && count_direction[_AXIS(A)] < 0) && !locked_##A##2_motor) A##2_STEP_WRITE(V); \ if (!(TEST(endstops.state(), A##3_MIN) && count_direction[_AXIS(A)] < 0) && !locked_##A##3_motor) A##3_STEP_WRITE(V); \ @@ -316,7 +316,7 @@ xyze_int8_t Stepper::count_direction{0}; #define QUAD_ENDSTOP_APPLY_STEP(A,V) \ if (separate_multi_axis) { \ - if (A##_HOME_DIR < 0) { \ + if (A##_HOME_TO_MIN) { \ if (!(TEST(endstops.state(), A##_MIN) && count_direction[_AXIS(A)] < 0) && !locked_##A##_motor) A##_STEP_WRITE(V); \ if (!(TEST(endstops.state(), A##2_MIN) && count_direction[_AXIS(A)] < 0) && !locked_##A##2_motor) A##2_STEP_WRITE(V); \ if (!(TEST(endstops.state(), A##3_MIN) && count_direction[_AXIS(A)] < 0) && !locked_##A##3_motor) A##3_STEP_WRITE(V); \ diff --git a/Marlin/src/module/stepper.h b/Marlin/src/module/stepper.h index 5ddd762aa9..020f72e9e6 100644 --- a/Marlin/src/module/stepper.h +++ b/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) diff --git a/Marlin/src/module/stepper/trinamic.cpp b/Marlin/src/module/stepper/trinamic.cpp index de3d45e4b6..8c943048ba 100644 --- a/Marlin/src/module/stepper/trinamic.cpp +++ b/Marlin/src/module/stepper/trinamic.cpp @@ -62,7 +62,7 @@ enum StealthIndex : uint8_t { STEALTH_AXIS_XY, STEALTH_AXIS_Z, STEALTH_AXIS_E }; #define _TMC_UART_DEFINE(SWHW, IC, ST, AI) TMC_UART_##SWHW##_DEFINE(IC, ST, TMC_##ST##_LABEL, AI) #define TMC_UART_DEFINE(SWHW, ST, AI) _TMC_UART_DEFINE(SWHW, ST##_DRIVER_TYPE, ST, AI##_AXIS) -#if DISTINCT_E > 1 +#if ENABLED(DISTINCT_E_FACTORS) #define TMC_SPI_DEFINE_E(AI) TMC_SPI_DEFINE(E##AI, E##AI) #define TMC_UART_DEFINE_E(SWHW, AI) TMC_UART_DEFINE(SWHW, E##AI, E##AI) #else diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index 03c0195085..1f32e6b118 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -2439,7 +2439,7 @@ void Temperature::disable_all_heaters() { TERN_(AUTOTEMP, planner.autotemp_enabled = false); // Unpause and reset everything - TERN_(PROBING_HEATERS_OFF, pause(false)); + TERN_(PROBING_HEATERS_OFF, pause_heaters(false)); #if HAS_HOTEND HOTEND_LOOP() { @@ -2498,7 +2498,7 @@ void Temperature::disable_all_heaters() { #if ENABLED(PROBING_HEATERS_OFF) - void Temperature::pause(const bool p) { + void Temperature::pause_heaters(const bool p) { if (p != paused_for_probing) { paused_for_probing = p; if (p) { diff --git a/Marlin/src/module/temperature.h b/Marlin/src/module/temperature.h index 83fbc8fd46..7ad58e9ab8 100644 --- a/Marlin/src/module/temperature.h +++ b/Marlin/src/module/temperature.h @@ -838,7 +838,7 @@ class Temperature { #endif #if ENABLED(PROBING_HEATERS_OFF) - static void pause(const bool p); + static void pause_heaters(const bool p); #endif #if HEATER_IDLE_HANDLER diff --git a/Marlin/src/module/tool_change.cpp b/Marlin/src/module/tool_change.cpp index 559caa7f98..cc34acc14f 100644 --- a/Marlin/src/module/tool_change.cpp +++ b/Marlin/src/module/tool_change.cpp @@ -822,7 +822,7 @@ void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_axis, 0. #endif // ELECTROMAGNETIC_SWITCHING_TOOLHEAD -#if EXTRUDERS +#if HAS_EXTRUDERS inline void invalid_extruder_error(const uint8_t e) { SERIAL_ECHO_START(); SERIAL_CHAR('T'); SERIAL_ECHO(e); @@ -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; diff --git a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h index 625de05996..b262212b7e 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h @@ -38,7 +38,7 @@ // #ifdef X_STALL_SENSITIVITY #define X_STOP_PIN X_DIAG_PIN - #if X_HOME_DIR < 0 + #if X_HOME_TO_MIN #define X_MAX_PIN P1_28 // X+ #else #define X_MIN_PIN P1_28 // X+ @@ -50,7 +50,7 @@ #ifdef Y_STALL_SENSITIVITY #define Y_STOP_PIN Y_DIAG_PIN - #if Y_HOME_DIR < 0 + #if Y_HOME_TO_MIN #define Y_MAX_PIN P1_26 // Y+ #else #define Y_MIN_PIN P1_26 // Y+ @@ -62,7 +62,7 @@ #ifdef Z_STALL_SENSITIVITY #define Z_STOP_PIN Z_DIAG_PIN - #if Z_HOME_DIR < 0 + #if Z_HOME_TO_MIN #define Z_MAX_PIN P1_24 // Z+ #else #define Z_MIN_PIN P1_24 // Z+ diff --git a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h index ba60db472e..0508c5b5a9 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h @@ -50,7 +50,7 @@ // #ifdef X_STALL_SENSITIVITY #define X_STOP_PIN X_DIAG_PIN - #if X_HOME_DIR < 0 + #if X_HOME_TO_MIN #define X_MAX_PIN P1_26 // E0DET #else #define X_MIN_PIN P1_26 // E0DET @@ -68,7 +68,7 @@ #ifdef Y_STALL_SENSITIVITY #define Y_STOP_PIN Y_DIAG_PIN - #if Y_HOME_DIR < 0 + #if Y_HOME_TO_MIN #define Y_MAX_PIN P1_25 // E1DET #else #define Y_MIN_PIN P1_25 // E1DET @@ -86,7 +86,7 @@ #ifdef Z_STALL_SENSITIVITY #define Z_STOP_PIN Z_DIAG_PIN - #if Z_HOME_DIR < 0 + #if Z_HOME_TO_MIN #define Z_MAX_PIN P1_00 // PWRDET #else #define Z_MIN_PIN P1_00 // PWRDET diff --git a/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h b/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h index 40fac4e7fa..f998ecde4e 100644 --- a/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h +++ b/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h @@ -50,7 +50,7 @@ // #ifdef X_STALL_SENSITIVITY #define X_STOP_PIN X_DIAG_PIN - #if X_HOME_DIR < 0 + #if X_HOME_TO_MIN #define X_MAX_PIN P1_28 // X+ #else #define X_MIN_PIN P1_28 // X+ @@ -62,7 +62,7 @@ #ifdef Y_STALL_SENSITIVITY #define Y_STOP_PIN Y_DIAG_PIN - #if Y_HOME_DIR < 0 + #if Y_HOME_TO_MIN #define Y_MAX_PIN P1_26 // Y+ #else #define Y_MIN_PIN P1_26 // Y+ @@ -74,7 +74,7 @@ #ifdef Z_STALL_SENSITIVITY #define Z_STOP_PIN Z_DIAG_PIN - #if Z_HOME_DIR < 0 + #if Z_HOME_TO_MIN #define Z_MAX_PIN P1_24 // Z+ #else #define Z_MIN_PIN P1_24 // Z+ diff --git a/Marlin/src/pins/lpc1769/pins_MKS_SGEN_L_V2.h b/Marlin/src/pins/lpc1769/pins_MKS_SGEN_L_V2.h index a616079403..1057147498 100644 --- a/Marlin/src/pins/lpc1769/pins_MKS_SGEN_L_V2.h +++ b/Marlin/src/pins/lpc1769/pins_MKS_SGEN_L_V2.h @@ -60,7 +60,7 @@ // #if X_STALL_SENSITIVITY #define X_STOP_PIN X_DIAG_PIN - #if X_HOME_DIR < 0 + #if X_HOME_TO_MIN #define X_MAX_PIN P1_28 // X+ #else #define X_MIN_PIN P1_28 // X+ @@ -72,7 +72,7 @@ #if Y_STALL_SENSITIVITY #define Y_STOP_PIN Y_DIAG_PIN - #if Y_HOME_DIR < 0 + #if Y_HOME_TO_MIN #define Y_MAX_PIN P1_26 // Y+ #else #define Y_MIN_PIN P1_26 // Y+ @@ -84,7 +84,7 @@ #if Z_STALL_SENSITIVITY #define Z_STOP_PIN Z_DIAG_PIN - #if Z_HOME_DIR < 0 + #if Z_HOME_TO_MIN #define Z_MAX_PIN P1_24 // Z+ #else #define Z_MIN_PIN P1_24 // Z+ diff --git a/Marlin/src/pins/pins_postprocess.h b/Marlin/src/pins/pins_postprocess.h index d71b79ca95..37ebbd47ad 100644 --- a/Marlin/src/pins/pins_postprocess.h +++ b/Marlin/src/pins/pins_postprocess.h @@ -385,7 +385,7 @@ // Assign endstop pins for boards with only 3 connectors // #ifdef X_STOP_PIN - #if X_HOME_DIR < 0 + #if X_HOME_TO_MIN #define X_MIN_PIN X_STOP_PIN #ifndef X_MAX_PIN #define X_MAX_PIN -1 @@ -396,14 +396,14 @@ #define X_MIN_PIN -1 #endif #endif -#elif X_HOME_DIR < 0 +#elif X_HOME_TO_MIN #define X_STOP_PIN X_MIN_PIN #else #define X_STOP_PIN X_MAX_PIN #endif #ifdef Y_STOP_PIN - #if Y_HOME_DIR < 0 + #if Y_HOME_TO_MIN #define Y_MIN_PIN Y_STOP_PIN #ifndef Y_MAX_PIN #define Y_MAX_PIN -1 @@ -414,14 +414,14 @@ #define Y_MIN_PIN -1 #endif #endif -#elif Y_HOME_DIR < 0 +#elif Y_HOME_TO_MIN #define Y_STOP_PIN Y_MIN_PIN #else #define Y_STOP_PIN Y_MAX_PIN #endif #ifdef Z_STOP_PIN - #if Z_HOME_DIR < 0 + #if Z_HOME_TO_MIN #define Z_MIN_PIN Z_STOP_PIN #ifndef Z_MAX_PIN #define Z_MAX_PIN -1 @@ -432,7 +432,7 @@ #define Z_MIN_PIN -1 #endif #endif -#elif Z_HOME_DIR < 0 +#elif Z_HOME_TO_MIN #define Z_STOP_PIN Z_MIN_PIN #else #define Z_STOP_PIN Z_MAX_PIN @@ -489,34 +489,34 @@ #undef Z_MIN_PIN #define Z_MIN_PIN -1 #endif -#if DISABLED(X_DUAL_ENDSTOPS) || X_HOME_DIR > 0 +#if DISABLED(X_DUAL_ENDSTOPS) || X_HOME_TO_MAX #undef X2_MIN_PIN #endif -#if DISABLED(X_DUAL_ENDSTOPS) || X_HOME_DIR < 0 +#if DISABLED(X_DUAL_ENDSTOPS) || X_HOME_TO_MIN #undef X2_MAX_PIN #endif -#if DISABLED(Y_DUAL_ENDSTOPS) || Y_HOME_DIR > 0 +#if DISABLED(Y_DUAL_ENDSTOPS) || Y_HOME_TO_MAX #undef Y2_MIN_PIN #endif -#if DISABLED(Y_DUAL_ENDSTOPS) || Y_HOME_DIR < 0 +#if DISABLED(Y_DUAL_ENDSTOPS) || Y_HOME_TO_MIN #undef Y2_MAX_PIN #endif -#if DISABLED(Z_MULTI_ENDSTOPS) || Z_HOME_DIR > 0 +#if DISABLED(Z_MULTI_ENDSTOPS) || Z_HOME_TO_MAX #undef Z2_MIN_PIN #endif -#if DISABLED(Z_MULTI_ENDSTOPS) || Z_HOME_DIR < 0 +#if DISABLED(Z_MULTI_ENDSTOPS) || Z_HOME_TO_MIN #undef Z2_MAX_PIN #endif -#if DISABLED(Z_MULTI_ENDSTOPS) || NUM_Z_STEPPER_DRIVERS < 3 || Z_HOME_DIR > 0 +#if DISABLED(Z_MULTI_ENDSTOPS) || NUM_Z_STEPPER_DRIVERS < 3 || Z_HOME_TO_MAX #undef Z3_MIN_PIN #endif -#if DISABLED(Z_MULTI_ENDSTOPS) || NUM_Z_STEPPER_DRIVERS < 3 || Z_HOME_DIR < 0 +#if DISABLED(Z_MULTI_ENDSTOPS) || NUM_Z_STEPPER_DRIVERS < 3 || Z_HOME_TO_MIN #undef Z3_MAX_PIN #endif -#if DISABLED(Z_MULTI_ENDSTOPS) || NUM_Z_STEPPER_DRIVERS < 4 || Z_HOME_DIR > 0 +#if DISABLED(Z_MULTI_ENDSTOPS) || NUM_Z_STEPPER_DRIVERS < 4 || Z_HOME_TO_MAX #undef Z4_MIN_PIN #endif -#if DISABLED(Z_MULTI_ENDSTOPS) || NUM_Z_STEPPER_DRIVERS < 4 || Z_HOME_DIR < 0 +#if DISABLED(Z_MULTI_ENDSTOPS) || NUM_Z_STEPPER_DRIVERS < 4 || Z_HOME_TO_MIN #undef Z4_MAX_PIN #endif diff --git a/Marlin/src/pins/rambo/pins_EINSY_RETRO.h b/Marlin/src/pins/rambo/pins_EINSY_RETRO.h index ee537495ea..0c072745d5 100644 --- a/Marlin/src/pins/rambo/pins_EINSY_RETRO.h +++ b/Marlin/src/pins/rambo/pins_EINSY_RETRO.h @@ -61,7 +61,7 @@ #else - #if X_HOME_DIR < 0 + #if X_HOME_TO_MIN #define X_MIN_PIN X_DIAG_PIN #define X_MAX_PIN 81 // X+ #else @@ -69,7 +69,7 @@ #define X_MAX_PIN X_DIAG_PIN #endif - #if Y_HOME_DIR < 0 + #if Y_HOME_TO_MIN #define Y_MIN_PIN Y_DIAG_PIN #define Y_MAX_PIN 57 // Y+ #else diff --git a/Marlin/src/pins/ramps/pins_3DRAG.h b/Marlin/src/pins/ramps/pins_3DRAG.h index 6c7f7f4db6..08354ce2ff 100644 --- a/Marlin/src/pins/ramps/pins_3DRAG.h +++ b/Marlin/src/pins/ramps/pins_3DRAG.h @@ -144,7 +144,7 @@ #undef SPINDLE_DIR_PIN #if HAS_CUTTER - #if !EXTRUDERS + #if !HAS_EXTRUDERS #undef E0_DIR_PIN #undef E0_ENABLE_PIN #undef E0_STEP_PIN diff --git a/Marlin/src/pins/sam/pins_ARCHIM2.h b/Marlin/src/pins/sam/pins_ARCHIM2.h index 3776cf8bb5..ecff888ff0 100644 --- a/Marlin/src/pins/sam/pins_ARCHIM2.h +++ b/Marlin/src/pins/sam/pins_ARCHIM2.h @@ -71,7 +71,7 @@ #define E0_DIAG_PIN 78 // PB23 #define E1_DIAG_PIN 25 // PD0 - #if X_HOME_DIR < 0 + #if X_HOME_TO_MIN #define X_MIN_PIN X_DIAG_PIN #define X_MAX_PIN 32 #else @@ -79,7 +79,7 @@ #define X_MAX_PIN X_DIAG_PIN #endif - #if Y_HOME_DIR < 0 + #if Y_HOME_TO_MIN #define Y_MIN_PIN Y_DIAG_PIN #define Y_MAX_PIN 15 #else diff --git a/Marlin/src/pins/sensitive_pins.h b/Marlin/src/pins/sensitive_pins.h index 1c811601ca..21ba87e8f6 100644 --- a/Marlin/src/pins/sensitive_pins.h +++ b/Marlin/src/pins/sensitive_pins.h @@ -353,7 +353,7 @@ #define _E6_PINS #define _E7_PINS -#if EXTRUDERS +#if HAS_EXTRUDERS #undef _E0_PINS #define _E0_PINS E0_STEP_PIN, E0_DIR_PIN, E0_ENABLE_PIN, _E0_CS _E0_MS1 _E0_MS2 _E0_MS3 #endif diff --git a/Marlin/src/pins/stm32f4/pins_BTT_E3_RRF.h b/Marlin/src/pins/stm32f4/pins_BTT_E3_RRF.h index f808278510..621b136e17 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_E3_RRF.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_E3_RRF.h @@ -55,7 +55,7 @@ #define X2_DIR_PIN FPC10_PIN // X2DIR #define X2_SERIAL_TX_PIN FPC12_PIN // X2UART #define X2_SERIAL_RX_PIN FPC12_PIN // X2UART - #if X_HOME_DIR < 0 + #if X_HOME_TO_MIN #define X_MAX_PIN FPC2_PIN // X2-STOP #else #define X_MIN_PIN FPC2_PIN // X2-STOP diff --git a/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h b/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h index 70d502f68a..70ac9a13c3 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h @@ -69,7 +69,7 @@ // #ifdef X_STALL_SENSITIVITY #define X_STOP_PIN X_DIAG_PIN - #if X_HOME_DIR < 0 + #if X_HOME_TO_MIN #define X_MAX_PIN E0_DIAG_PIN // X+ #else #define X_MIN_PIN E0_DIAG_PIN // X+ @@ -81,7 +81,7 @@ #ifdef Y_STALL_SENSITIVITY #define Y_STOP_PIN Y_DIAG_PIN - #if Y_HOME_DIR < 0 + #if Y_HOME_TO_MIN #define Y_MAX_PIN E1_DIAG_PIN // Y+ #else #define Y_MIN_PIN E1_DIAG_PIN // Y+ @@ -93,7 +93,7 @@ #ifdef Z_STALL_SENSITIVITY #define Z_STOP_PIN Z_DIAG_PIN - #if Z_HOME_DIR < 0 + #if Z_HOME_TO_MIN #define Z_MAX_PIN E2_DIAG_PIN // Z+ #else #define Z_MIN_PIN E2_DIAG_PIN // Z+ diff --git a/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_0.h b/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_0.h index 6de3c544d3..34fe1a824b 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_0.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_0.h @@ -71,7 +71,7 @@ // #ifdef X_STALL_SENSITIVITY #define X_STOP_PIN X_DIAG_PIN - #if X_HOME_DIR < 0 + #if X_HOME_TO_MIN #define X_MAX_PIN E0_DIAG_PIN // E0DET #else #define X_MIN_PIN E0_DIAG_PIN // E0DET @@ -89,7 +89,7 @@ #ifdef Y_STALL_SENSITIVITY #define Y_STOP_PIN Y_DIAG_PIN - #if Y_HOME_DIR < 0 + #if Y_HOME_TO_MIN #define Y_MAX_PIN E1_DIAG_PIN // E1DET #else #define Y_MIN_PIN E1_DIAG_PIN // E1DET @@ -107,7 +107,7 @@ #ifdef Z_STALL_SENSITIVITY #define Z_STOP_PIN Z_DIAG_PIN - #if Z_HOME_DIR < 0 + #if Z_HOME_TO_MIN #define Z_MAX_PIN E2_DIAG_PIN // PWRDET #else #define Z_MIN_PIN E2_DIAG_PIN // PWRDET diff --git a/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_common.h b/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_common.h index 67907affa7..fe6d8740bd 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_common.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_common.h @@ -71,7 +71,7 @@ // #ifdef X_STALL_SENSITIVITY #define X_STOP_PIN X_DIAG_PIN - #if X_HOME_DIR < 0 + #if X_HOME_TO_MIN #define X_MAX_PIN PE15 // E0 #else #define X_MIN_PIN PE15 // E0 @@ -83,7 +83,7 @@ #ifdef Y_STALL_SENSITIVITY #define Y_STOP_PIN Y_DIAG_PIN - #if Y_HOME_DIR < 0 + #if Y_HOME_TO_MIN #define Y_MAX_PIN PE10 // E1 #else #define Y_MIN_PIN PE10 // E1 @@ -95,7 +95,7 @@ #ifdef Z_STALL_SENSITIVITY #define Z_STOP_PIN Z_DIAG_PIN - #if Z_HOME_DIR < 0 + #if Z_HOME_TO_MIN #define Z_MAX_PIN PG5 // E2 #else #define Z_MIN_PIN PG5 // E2 diff --git a/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h b/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h index a69041e2d4..5e2f88190d 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h @@ -72,7 +72,7 @@ // #ifdef X_STALL_SENSITIVITY #define X_STOP_PIN X_DIAG_PIN - #if X_HOME_DIR < 0 + #if X_HOME_TO_MIN #define X_MAX_PIN PC2 // E0DET #else #define X_MIN_PIN PC2 // E0DET @@ -90,7 +90,7 @@ #ifdef Y_STALL_SENSITIVITY #define Y_STOP_PIN Y_DIAG_PIN - #if Y_HOME_DIR < 0 + #if Y_HOME_TO_MIN #define Y_MAX_PIN PA0 // E1DET #else #define Y_MIN_PIN PA0 // E1DET @@ -108,7 +108,7 @@ #ifdef Z_STALL_SENSITIVITY #define Z_STOP_PIN Z_DIAG_PIN - #if Z_HOME_DIR < 0 + #if Z_HOME_TO_MIN #define Z_MAX_PIN PC15 // PWRDET #else #define Z_MIN_PIN PC15 // PWRDET diff --git a/Marlin/src/sd/Sd2Card.cpp b/Marlin/src/sd/Sd2Card.cpp index 3e714fe9fe..a81932d494 100644 --- a/Marlin/src/sd/Sd2Card.cpp +++ b/Marlin/src/sd/Sd2Card.cpp @@ -89,6 +89,11 @@ // Send command and return error code. Return zero for OK uint8_t DiskIODriver_SPI_SD::cardCommand(const uint8_t cmd, const uint32_t arg) { + + #if ENABLED(SDCARD_COMMANDS_SPLIT) + if (cmd != CMD12) chipDeselect(); + #endif + // Select card chipSelect(); diff --git a/Marlin/src/sd/cardreader.cpp b/Marlin/src/sd/cardreader.cpp index cca5c52e02..0d26be9616 100644 --- a/Marlin/src/sd/cardreader.cpp +++ b/Marlin/src/sd/cardreader.cpp @@ -261,7 +261,14 @@ void CardReader::selectByName(SdFile dir, const char * const match) { } // -// Recursive method to list all files within a folder +// Recursive method to print all files within a folder in flat +// DOS 8.3 format. This style of listing is the most compatible +// with legacy hosts. +// +// This method recurses to unlimited depth and lists every +// G-code file within the given parent. If the hierarchy is +// very deep this can blow up the stack, so a 'depth' parameter +// (as with printListingJSON) would be a good addition. // void CardReader::printListing(SdFile parent, const char * const prepend/*=nullptr*/) { #if ENABLED(MKS_WIFI) @@ -291,31 +298,29 @@ void CardReader::printListing(SdFile parent, const char * const prepend/*=nullpt // Get a new directory object using the full path // and dive recursively into it. - SdFile child; - if (!child.open(&parent, dosFilename, O_READ)) + SdFile child; // child.close() in destructor + if (child.open(&parent, dosFilename, O_READ)) + printListing(child, path); + else { SERIAL_ECHO_MSG(STR_SD_CANT_OPEN_SUBDIR, dosFilename); - - printListing(child, path); - // close() is done automatically by destructor of SdFile + return; + } } else if (is_dir_or_gcode(p)) { - createFilename(filename, p); if (prepend) SERIAL_ECHO(prepend); - #if ENABLED(MKS_WIFI) if (port.index == MKS_WIFI_SERIAL_NUM){ - printLongPath(filename); + printLongPath(createFilename(filename, p)); }else{ - SERIAL_ECHO(filename); + SERIAL_ECHO(createFilename(filename, p)); SERIAL_CHAR(' '); SERIAL_ECHOLN(p.fileSize); } #else - SERIAL_ECHO(filename); + SERIAL_ECHO(createFilename(filename, p)); SERIAL_CHAR(' '); SERIAL_ECHOLN(p.fileSize); #endif - } } } @@ -360,7 +365,7 @@ void CardReader::ls() { // Go to the next segment while (path[++i]) { } - // SERIAL_ECHOPGM("Looking for segment: "); SERIAL_ECHOLN(segment); + //SERIAL_ECHOLNPAIR("Looking for segment: ", segment); // Find the item, setting the long filename diveDir.rewind(); @@ -749,14 +754,14 @@ void CardReader::removeFile(const char * const name) { //abortFilePrintNow(); - SdFile *curDir; - const char * const fname = diveToFile(false, curDir, name); + SdFile *itsDirPtr; + const char * const fname = diveToFile(false, itsDirPtr, name); if (!fname) return; #if ENABLED(SDCARD_READONLY) SERIAL_ECHOLNPAIR("Deletion failed (read-only), File: ", fname, "."); #else - if (file.remove(curDir, fname)) { + if (file.remove(itsDirPtr, fname)) { SERIAL_ECHOLNPAIR("File deleted:", fname); sdpos = 0; TERN_(SDCARD_SORT_ALPHA, presort()); @@ -899,98 +904,101 @@ uint16_t CardReader::countFilesInWorkDir() { * - If update_cwd was 'true' the workDir now points to the file's directory. * * Returns a pointer to the last segment (filename) of the given DOS 8.3 path. + * On exit, inDirPtr contains an SdFile reference to the file's directory. * * A nullptr result indicates an unrecoverable error. + * + * NOTE: End the path with a slash to dive to a folder. In this case the + * returned filename will be blank (points to the end of the path). */ -const char* CardReader::diveToFile(const bool update_cwd, SdFile* &diveDir, const char * const path, const bool echo/*=false*/) { +const char* CardReader::diveToFile(const bool update_cwd, SdFile* &inDirPtr, const char * const path, const bool echo/*=false*/) { DEBUG_SECTION(est, "diveToFile", true); // Track both parent and subfolder static SdFile newDir1, newDir2; - SdFile *sub = &newDir1, *startDir; + SdFile *sub = &newDir1, *startDirPtr; // Parsing the path string - const char *item_name_adr = path; + const char *atom_ptr = path; DEBUG_ECHOLNPAIR(" path = '", path, "'"); if (path[0] == '/') { // Starting at the root directory? - diveDir = &root; - item_name_adr++; - DEBUG_ECHOLNPAIR(" CWD to root: ", hex_address((void*)diveDir)); + inDirPtr = &root; + atom_ptr++; + DEBUG_ECHOLNPAIR(" CWD to root: ", hex_address((void*)inDirPtr)); if (update_cwd) workDirDepth = 0; // The cwd can be updated for the benefit of sub-programs } else - diveDir = &workDir; // Dive from workDir (as set by the UI) + inDirPtr = &workDir; // Dive from workDir (as set by the UI) - startDir = diveDir; + startDirPtr = inDirPtr; - DEBUG_ECHOLNPAIR(" startDir = ", hex_address((void*)startDir)); + DEBUG_ECHOLNPAIR(" startDirPtr = ", hex_address((void*)startDirPtr)); - while (item_name_adr) { + while (atom_ptr) { // Find next subdirectory delimiter - char * const name_end = strchr(item_name_adr, '/'); + char * const name_end = strchr(atom_ptr, '/'); // Last atom in the path? Item found. - if (name_end <= item_name_adr) break; + if (name_end <= atom_ptr) break; - // Set subDirName - const uint8_t len = name_end - item_name_adr; + // Isolate the next subitem name + const uint8_t len = name_end - atom_ptr; char dosSubdirname[len + 1]; - strncpy(dosSubdirname, item_name_adr, len); + strncpy(dosSubdirname, atom_ptr, len); dosSubdirname[len] = 0; if (echo) SERIAL_ECHOLN(dosSubdirname); DEBUG_ECHOLNPAIR(" sub = ", hex_address((void*)sub)); - // Open diveDir (closing first) + // Open inDirPtr (closing first) sub->close(); - if (!sub->open(diveDir, dosSubdirname, O_READ)) { + if (!sub->open(inDirPtr, dosSubdirname, O_READ)) { openFailed(dosSubdirname); - item_name_adr = nullptr; + atom_ptr = nullptr; break; } - // Close diveDir if not at starting-point - if (diveDir != startDir) { - DEBUG_ECHOLNPAIR(" closing diveDir: ", hex_address((void*)diveDir)); - diveDir->close(); + // Close inDirPtr if not at starting-point + if (inDirPtr != startDirPtr) { + DEBUG_ECHOLNPAIR(" closing inDirPtr: ", hex_address((void*)inDirPtr)); + inDirPtr->close(); } - // diveDir now subDir - diveDir = sub; - DEBUG_ECHOLNPAIR(" diveDir = sub: ", hex_address((void*)diveDir)); + // inDirPtr now subDir + inDirPtr = sub; + DEBUG_ECHOLNPAIR(" inDirPtr = sub: ", hex_address((void*)inDirPtr)); // Update workDirParents and workDirDepth if (update_cwd) { DEBUG_ECHOLNPAIR(" update_cwd"); if (workDirDepth < MAX_DIR_DEPTH) - workDirParents[workDirDepth++] = *diveDir; + workDirParents[workDirDepth++] = *inDirPtr; } // Point sub at the other scratch object - sub = (diveDir != &newDir1) ? &newDir1 : &newDir2; + sub = (inDirPtr != &newDir1) ? &newDir1 : &newDir2; DEBUG_ECHOLNPAIR(" swapping sub = ", hex_address((void*)sub)); // Next path atom address - item_name_adr = name_end + 1; + atom_ptr = name_end + 1; } if (update_cwd) { - workDir = *diveDir; - DEBUG_ECHOLNPAIR(" final workDir = ", hex_address((void*)diveDir)); + workDir = *inDirPtr; + DEBUG_ECHOLNPAIR(" final workDir = ", hex_address((void*)inDirPtr)); flag.workDirIsRoot = (workDirDepth == 0); TERN_(SDCARD_SORT_ALPHA, presort()); } - DEBUG_ECHOLNPAIR(" returning string ", item_name_adr ?: "nullptr"); - return item_name_adr; + DEBUG_ECHOLNPAIR(" returning string ", atom_ptr ?: "nullptr"); + return atom_ptr; } void CardReader::cd(const char * relpath) { - SdFile newDir; - SdFile *parent = workDir.isOpen() ? &workDir : &root; + SdFile newDir, *parent = &getWorkDir(); if (newDir.open(parent, relpath, O_READ)) { workDir = newDir; diff --git a/Marlin/src/sd/cardreader.h b/Marlin/src/sd/cardreader.h index 6f1633d30e..35d7627421 100644 --- a/Marlin/src/sd/cardreader.h +++ b/Marlin/src/sd/cardreader.h @@ -111,7 +111,6 @@ public: static void mount(); static void release(); static inline bool isMounted() { return flag.mounted; } - static void ls(); // Handle media insert/remove static void manage_media(); @@ -176,21 +175,32 @@ public: return 0; } - // Helper for open and remove - static const char* diveToFile(const bool update_cwd, SdFile* &curDir, const char * const path, const bool echo=false); + /** + * Dive down to a relative or absolute path. + * Relative paths apply to the workDir. + * + * update_cwd: Pass 'true' to update the workDir on success. + * inDirPtr: On exit your pointer points to the target SdFile. + * A nullptr indicates failure. + * path: Start with '/' for abs path. End with '/' to get a folder ref. + * echo: Set 'true' to print the path throughout the loop. + */ + static const char* diveToFile(const bool update_cwd, SdFile* &inDirPtr, const char * const path, const bool echo=false); #if ENABLED(SDCARD_SORT_ALPHA) static void presort(); static void getfilename_sorted(const uint16_t nr); #if ENABLED(SDSORT_GCODE) - FORCE_INLINE static void setSortOn(bool b) { sort_alpha = b; presort(); } - FORCE_INLINE static void setSortFolders(int i) { sort_folders = i; presort(); } + FORCE_INLINE static void setSortOn(bool b) { sort_alpha = b; presort(); } + FORCE_INLINE static void setSortFolders(int i) { sort_folders = i; presort(); } //FORCE_INLINE static void setSortReverse(bool b) { sort_reverse = b; } #endif #else FORCE_INLINE static void getfilename_sorted(const uint16_t nr) { selectFileByIndex(nr); } #endif + static void ls(); + #if ENABLED(POWER_LOSS_RECOVERY) static bool jobRecoverFileExists(); static void openJobRecoveryFile(const bool read); @@ -199,6 +209,7 @@ public: // Current Working Dir - Set by cd, cdup, cdroot, and diveToFile(true, ...) static inline char* getWorkDirName() { workDir.getDosName(filename); return filename; } + static inline SdFile& getWorkDir() { return workDir.isOpen() ? workDir : root; } // Print File stats static inline uint32_t getFileSize() { return filesize; } diff --git a/buildroot/share/PlatformIO/scripts/common-dependencies.h b/buildroot/share/PlatformIO/scripts/common-dependencies.h index 18a7303be6..a88e708467 100644 --- a/buildroot/share/PlatformIO/scripts/common-dependencies.h +++ b/buildroot/share/PlatformIO/scripts/common-dependencies.h @@ -49,10 +49,6 @@ #define HAS_GCODE_M876 #endif -#if EXTRUDERS - #define HAS_EXTRUDERS -#endif - #if ENABLED(DUET_SMART_EFFECTOR) && PIN_EXISTS(SMART_EFFECTOR_MOD) #define HAS_SMART_EFF_MOD #endif diff --git a/buildroot/share/PlatformIO/scripts/mks_encrypt.py b/buildroot/share/PlatformIO/scripts/mks_encrypt.py index 78d7cf349d..0c622704e7 100644 --- a/buildroot/share/PlatformIO/scripts/mks_encrypt.py +++ b/buildroot/share/PlatformIO/scripts/mks_encrypt.py @@ -17,7 +17,7 @@ if 'firmware' in board.get("build").keys(): # Encrypt ${PROGNAME}.bin and save it as build.firmware def encrypt(source, target, env): - marlin.encrypt_mks(source, target, env, "build.firmware") + marlin.encrypt_mks(source, target, env, board.get("build.firmware")) marlin.add_post_action(encrypt); diff --git a/buildroot/share/PlatformIO/scripts/mks_robin_nano35.py b/buildroot/share/PlatformIO/scripts/mks_robin_nano35.py index 310c3d6606..938210e579 100644 --- a/buildroot/share/PlatformIO/scripts/mks_robin_nano35.py +++ b/buildroot/share/PlatformIO/scripts/mks_robin_nano35.py @@ -1,5 +1,11 @@ # # buildroot/share/PlatformIO/scripts/mks_robin_nano35.py # +Import("env") import marlin marlin.prepare_robin("0x08007000", "mks_robin_nano.ld", "Robin_nano35.bin") + +env.Replace( + UPLOADER="curl", + UPLOADCMD="$UPLOADER -v -H 'Content-Type:application/octet-stream' http://$UPLOADERFLAGS/upload?X-Filename=Robin_Nano35.bin --data-binary @$BUILD_DIR/Robin_nano35.bin" +) \ No newline at end of file diff --git a/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1_0/PeripheralPins.c b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1_0/PeripheralPins.c index 75bbd1cf20..333bef3db2 100644 --- a/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1_0/PeripheralPins.c +++ b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1_0/PeripheralPins.c @@ -132,70 +132,96 @@ const PinMap PinMap_I2C_SCL[] = { #ifdef HAL_TIM_MODULE_ENABLED const PinMap PinMap_PWM[] = { - {PA_0, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 1, 0)}, // TIM2_CH1 - // {PA_0, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 1, 0)}, // TIM5_CH1 - // {PA_1, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 2, 0)}, // TIM2_CH2 - {PA_1, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 2, 0)}, // TIM5_CH2 - // {PA_2, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 3, 0)}, // TIM2_CH3 - STLink Tx - // {PA_2, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 3, 0)}, // TIM5_CH3 - STLink Tx - // {PA_2, TIM9, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM9, 1, 0)}, // TIM9_CH1 - STLink Tx - // {PA_3, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 4, 0)}, // TIM2_CH4 - STLink Rx - // {PA_3, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 4, 0)}, // TIM5_CH4 - STLink Rx - // {PA_3, TIM9, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM9, 2, 0)}, // TIM9_CH2 - STLink Rx - {PA_5, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 1, 0)}, // TIM2_CH1 - // {PA_5, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 1)}, // TIM8_CH1N - {PA_6, TIM13, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM13, 1, 0)}, // TIM13_CH1 - // {PA_6, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 1, 0)}, // TIM3_CH1 - //{PA_7, TIM14, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM14, 1, 0)}, // TIM14_CH1 - // {PA_7, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 1)}, // TIM1_CH1N - // {PA_7, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2 - // {PA_7, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 1)}, // TIM8_CH1N - {PA_8, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 0)}, // TIM1_CH1 - {PA_9, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 0)}, // TIM1_CH2 - {PA_10, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 0)}, // TIM1_CH3 - {PA_11, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 4, 0)}, // TIM1_CH4 - {PA_15, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 1, 0)}, // TIM2_CH1 - // {PB_0, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N - // {PB_0, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 3, 0)}, // TIM3_CH3 - {PB_0, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 1)}, // Fan0, TIM8_CH2N - // {PB_1, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 1)}, // TIM1_CH3N - // {PB_1, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 4, 0)}, // TIM3_CH4 - {PB_1, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 3, 1)}, // Fan1, TIM8_CH3N - {PB_2, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 4, 0)}, // Fan2, TIM2_CH4 - {PB_3, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 2, 0)}, // E0 Heater, TIM2_CH2 - {PB_4, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 1, 0)}, // E1 Heater, TIM3_CH1 - {PB_5, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // LED G, TIM3_CH2 - {PB_6, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 1, 0)}, // LED R, TIM4_CH1 - {PB_7, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 2, 0)}, // LED B, TIM4_CH2 - // {PB_8, TIM10, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM10, 1, 0)}, // TIM10_CH1 - // {PB_8, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 1, 0)}, // TIM2_CH1 - {PB_8, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 3, 0)}, // TIM4_CH3 - {PB_9, TIM11, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM11, 1, 0)}, // TIM11_CH1 - // {PB_9, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 2, 0)}, // TIM2_CH2 - // {PB_9, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 4, 0)}, // TIM4_CH4 - {PB_10, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 3, 0)}, // TIM2_CH3 - {PB_13, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 1)}, // TIM1_CH1N - {PB_14, TIM12, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM12, 1, 0)}, // TIM12_CH1 - // {PB_14, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N - // {PB_14, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 1)}, // TIM8_CH2N - {PB_15, TIM12, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM12, 2, 0)}, // TIM12_CH2 - // {PB_15, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 1)}, // TIM1_CH3N - // {PB_15, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 3, 1)}, // TIM8_CH3N - {PC_6, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 1, 0)}, // TIM3_CH1 - // {PC_6, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 0)}, // TIM8_CH1 - // {PC_7, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2 - {PC_7, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 0)}, // TIM8_CH2 - {PC_8, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 3, 0)}, // TIM3_CH3 - // {PC_8, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 3, 0)}, // TIM8_CH3 - // {PC_9, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 4, 0)}, // TIM3_CH4 - {PC_9, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 4, 0)}, // TIM8_CH4 - {PD_12, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 1, 0)}, // TIM4_CH1 BED - {PD_13, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 2, 0)}, // TIM4_CH2 - {PD_14, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 3, 0)}, // TIM4_CH3 HEATER1 - {PD_15, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 4, 0)}, // TIM4_CH4 - {PE_5, TIM9, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM9, 1, 0)}, // TIM9_CH1 FAN1 - {PE_9, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 0)}, // TIM1_CH1 - {PE_10, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N + {PA_1, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 2, 0)}, // TIM5_CH2 BED + {PA_2, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 3, 0)}, // TIM2_CH3 HEATER0 + {PA_3, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 4, 0)}, // TIM2_CH4 HEATER1 + {PB_10, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 3, 0)}, // TIM2_CH3 HEATER2 + {PB_11, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 4, 0)}, // TIM2_CH4 HEATER3 + {PA_8, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 0)}, // TIM1_CH1 FAN0 + {PE_5, TIM9, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM9, 1, 0)}, // TIM9_CH1 FAN1 + {PD_12, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 1, 0)}, // TIM4_CH1 FAN2 + {PD_13, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 2, 0)}, // TIM4_CH2 FAN3 + {PD_14, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 3, 0)}, // TIM4_CH3 FAN4 + {PD_15, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 4, 0)}, // TIM4_CH4 FAN5 + + /** + * Unused by specifications on Octopus. + * Uncomment the corresponding line if you want to have HardwarePWM on some pins. + * WARNING: check timers' usage first to avoid conflicts. + * If you don't know what you're doing leave things as they are or you WILL break something (including hardware) + * If you alter this section DO NOT report bugs to Marlin team since they are most likely caused by you. Thank you. + */ + //{PA_0, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 1, 0)}, // TIM2_CH1 + //{PA_0, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 1, 0)}, // TIM5_CH1 + //{PA_1, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 2, 0)}, // TIM2_CH2 BLTOUCH is a "servo" + //{PA_2, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 3, 0)}, // TIM2_CH3 BLTOUCH is a "servo" + //{PA_1, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 2, 0)}, // TIM5_CH2 + //{PA_2, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 3, 0)}, // TIM5_CH3 + //{PA_2, TIM9, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM9, 1, 0)}, // TIM9_CH1 + //{PA_3, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 4, 0)}, // TIM2_CH4 + //{PA_3, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 4, 0)}, // TIM5_CH4 + //{PA_3, TIM9, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM9, 2, 0)}, // TIM9_CH2 + //{PA_5, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 1, 0)}, // TIM2_CH1 + //{PA_5, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 1)}, // TIM8_CH1N + //{PA_6, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 1, 0)}, // TIM3_CH1 + //{PA_6, TIM13, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM13, 1, 0)}, // TIM13_CH1 + //{PA_7, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 1)}, // TIM1_CH1N + //{PA_7, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2 + //{PA_7, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 1)}, // TIM8_CH1N + //{PA_7, TIM14, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM14, 1, 0)}, // TIM14_CH1 + //{PA_8, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 0)}, // TIM1_CH1 + //{PA_9, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 0)}, // TIM1_CH2 + //{PA_10, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 0)}, // TIM1_CH3 + //{PA_11, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 4, 0)}, // TIM1_CH4 + //{PA_15, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 1, 0)}, // TIM2_CH1 + //{PB_0, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N + //{PB_0, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 1)}, // TIM8_CH2N + //{PB_1, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 1)}, // TIM1_CH3N + //{PB_1, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 3, 1)}, // TIM8_CH3N + //{PB_3, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 2, 0)}, // TIM2_CH2 + //{PB_4, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 1, 0)}, // TIM3_CH1 + //{PB_5, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2 + //{PB_6, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 1, 0)}, // TIM4_CH1 + //{PB_8, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 3, 0)}, // TIM4_CH3 + //{PB_8, TIM10, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM10, 1, 0)}, // TIM10_CH1 + //{PB_9, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 4, 0)}, // TIM4_CH4 + //{PB_9, TIM11, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM11, 1, 0)}, // TIM11_CH1 + //{PB_10, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 3, 0)}, // TIM2_CH3 + //{PB_11, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 4, 0)}, // TIM2_CH4 + //{PB_13, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 1)}, // TIM1_CH1N + //{PB_14, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N + //{PB_14, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 1)}, // TIM8_CH2N + //{PB_14, TIM12, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM12, 1, 0)}, // TIM12_CH1 + //{PB_15, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 1)}, // TIM1_CH3N + //{PB_15, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 3, 1)}, // TIM8_CH3N + //{PB_15, TIM12, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM12, 2, 0)}, // TIM12_CH2 + //{PC_6, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 0)}, // TIM8_CH1 + //{PC_7, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2 + //{PC_7, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 0)}, // TIM8_CH2 + //{PC_8, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 3, 0)}, // TIM3_CH3 + //{PC_9, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 4, 0)}, // TIM3_CH4 + //{PD_13, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 2, 0)}, // TIM4_CH2 + //{PD_15, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 4, 0)}, // TIM4_CH4 + //{PE_8, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 1)}, // TIM1_CH1N + //{PE_9, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 0)}, // TIM1_CH1 + //{PE_10, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N + //{PE_11, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 0)}, // TIM1_CH2 + //{PE_12, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 1)}, // TIM1_CH3N + //{PE_13, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 0)}, // TIM1_CH3 + //{PE_14, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 4, 0)}, // TIM1_CH4 + //144 pins mcu, 114 gpio + //{PF_6, TIM10, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM10, 1, 0)}, // TIM10_CH1 + //{PF_7, TIM11, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM11, 1, 0)}, // TIM11_CH1 + //{PF_8, TIM13, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM13, 1, 0)}, // TIM13_CH1 + //{PF_9, TIM14, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM14, 1, 0)}, // TIM14_CH1 + + //176 pins mcu, 140 gpio + //{PH_10, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 1, 0)}, // TIM5_CH1 + //{PH_6, TIM12, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM12, 1, 0)}, // TIM12_CH1 + //{PH_11, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 2, 0)}, // TIM5_CH2 + //{PI_5, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 0)}, // TIM8_CH1 + //{PI_6, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 0)}, // TIM8_CH2 + {NC, NP, 0} }; #endif @@ -367,7 +393,24 @@ const PinMap PinMap_USB_OTG_FS[] = { #endif #ifdef HAL_PCD_MODULE_ENABLED -const PinMap PinMap_USB_OTG_HS[] = { +const PinMap PinMap_USB_OTG_HS[] = { + //{PB_12, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_PULLUP, GPIO_AF12_OTG_HS_FS)}, // USB_OTG_HS_ID + //{PB_13, USB_OTG_HS, STM_PIN_DATA(STM_MODE_INPUT, GPIO_NOPULL, GPIO_AF_NONE)}, // USB_OTG_HS_VBUS + {PB_14, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_OTG_HS_FS)}, // USB_OTG_HS_DM + {PB_15, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_OTG_HS_FS)}, // USB_OTG_HS_DP + + /*#error "USB in HS mode isn't supported by the board" + {PA_3, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D0 + {PB_0, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D1 + {PB_1, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D2 + {PB_5, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D7 + {PB_10, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D3 + {PB_12, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D5 + {PB_13, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D6 + {PC_0, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_STP + {PC_2, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_DIR + {PC_3, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_NXT + */ {NC, NP, 0} }; diff --git a/buildroot/tests/mega2560 b/buildroot/tests/mega2560 index 7bbf29e630..22832920ee 100755 --- a/buildroot/tests/mega2560 +++ b/buildroot/tests/mega2560 @@ -16,7 +16,7 @@ set -e # Test a probeless build of AUTO_BED_LEVELING_UBL, with lots of extruders # use_example_configs AnimationExample -opt_set MOTHERBOARD BOARD_AZTEEG_X3_PRO LCD_LANGUAGE fr \ +opt_set MOTHERBOARD BOARD_AZTEEG_X3_PRO LCD_LANGUAGE fr SAVED_POSITIONS 4 \ EXTRUDERS 5 TEMP_SENSOR_1 1 TEMP_SENSOR_2 5 TEMP_SENSOR_3 20 TEMP_SENSOR_4 1000 TEMP_SENSOR_BED 1 opt_enable AUTO_BED_LEVELING_UBL RESTORE_LEVELING_AFTER_G28 DEBUG_LEVELING_FEATURE G26_MESH_VALIDATION ENABLE_LEVELING_FADE_HEIGHT SKEW_CORRECTION \ REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER LIGHTWEIGHT_UI STATUS_MESSAGE_SCROLLING SHOW_CUSTOM_BOOTSCREEN BOOT_MARLIN_LOGO_SMALL \ @@ -171,7 +171,10 @@ exec_test $1 $2 "Azteeg X3 | Mixing Extruder (x5) | Gradient Mix | Greek" "$3" # Test Laser features with 12864 LCD # restore_configs -opt_set MOTHERBOARD BOARD_RAMPS_14_EFB LCD_LANGUAGE en TEMP_SENSOR_COOLER 1 EXTRUDERS 0 TEMP_SENSOR_1 0 SERIAL_PORT_2 2 +opt_set MOTHERBOARD BOARD_RAMPS_14_EFB LCD_LANGUAGE en TEMP_SENSOR_COOLER 1 EXTRUDERS 0 TEMP_SENSOR_1 0 SERIAL_PORT_2 2 \ + DEFAULT_AXIS_STEPS_PER_UNIT '{ 80, 80, 400 }' \ + DEFAULT_MAX_FEEDRATE '{ 300, 300, 5 }' \ + DEFAULT_MAX_ACCELERATION '{ 3000, 3000, 100 }' opt_enable REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER SDSUPPORT EEPROM_SETTINGS EEPROM_BOOT_SILENT EEPROM_AUTO_INIT \ LASER_FEATURE AIR_EVACUATION AIR_EVACUATION_PIN AIR_ASSIST AIR_ASSIST_PIN LASER_COOLANT_FLOW_METER MEATPACK_ON_SERIAL_PORT_1 @@ -181,7 +184,10 @@ exec_test $1 $2 "REPRAP MEGA2560 RAMPS | Laser Feature | Air Evacuation | Air As # Test Laser features with 44780 LCD # restore_configs -opt_set MOTHERBOARD BOARD_RAMPS_14_EFB LCD_LANGUAGE en TEMP_SENSOR_COOLER 1 EXTRUDERS 0 TEMP_SENSOR_1 0 +opt_set MOTHERBOARD BOARD_RAMPS_14_EFB LCD_LANGUAGE en TEMP_SENSOR_COOLER 1 EXTRUDERS 0 TEMP_SENSOR_1 0 \ + DEFAULT_AXIS_STEPS_PER_UNIT '{ 80, 80, 400 }' \ + DEFAULT_MAX_FEEDRATE '{ 300, 300, 5 }' \ + DEFAULT_MAX_ACCELERATION '{ 3000, 3000, 100 }' opt_enable REPRAP_DISCOUNT_SMART_CONTROLLER SDSUPPORT EEPROM_SETTINGS EEPROM_BOOT_SILENT EEPROM_AUTO_INIT \ LASER_FEATURE AIR_EVACUATION AIR_EVACUATION_PIN AIR_ASSIST AIR_ASSIST_PIN LASER_COOLANT_FLOW_METER diff --git a/buildroot/tests/rambo b/buildroot/tests/rambo index 87772a988b..9869b96b34 100755 --- a/buildroot/tests/rambo +++ b/buildroot/tests/rambo @@ -45,6 +45,10 @@ restore_configs opt_set MOTHERBOARD BOARD_RAMBO \ EXTRUDERS 0 TEMP_SENSOR_0 999 DUMMY_THERMISTOR_999_VALUE 170 Z_HOME_DIR 1 \ DIGIPOT_MOTOR_CURRENT '{ 120, 120, 120, 120, 120 }' \ + DEFAULT_AXIS_STEPS_PER_UNIT '{ 80, 80, 4000 }' \ + DEFAULT_MAX_FEEDRATE '{ 300, 300, 5 }' \ + DEFAULT_MAX_ACCELERATION '{ 3000, 3000, 100 }' \ + AXIS_RELATIVE_MODES '{ false, false, false }' \ LEVEL_CORNERS_LEVELING_ORDER '{ LF, RF }' opt_enable USE_XMAX_PLUG USE_YMAX_PLUG USE_ZMAX_PLUG \ REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER REVERSE_ENCODER_DIRECTION SDSUPPORT EEPROM_SETTINGS \ @@ -58,7 +62,11 @@ exec_test $1 $2 "Rambo CNC Configuration" "$3" # Rambo heated bed only # restore_configs -opt_set MOTHERBOARD BOARD_RAMBO EXTRUDERS 0 TEMP_SENSOR_BED 1 +opt_set MOTHERBOARD BOARD_RAMBO EXTRUDERS 0 TEMP_SENSOR_BED 1 \ + DEFAULT_AXIS_STEPS_PER_UNIT '{ 80, 80, 4000 }' \ + DEFAULT_MAX_FEEDRATE '{ 300, 300, 5 }' \ + DEFAULT_MAX_ACCELERATION '{ 3000, 3000, 100 }' \ + AXIS_RELATIVE_MODES '{ false, false, false }' opt_enable REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER exec_test $1 $2 "Rambo heated bed only" "$3" diff --git a/config/README.md b/config/README.md index 84a8f847f2..940604b921 100644 --- a/config/README.md +++ b/config/README.md @@ -1,3 +1,3 @@ # Where have all the configurations gone? -## https://github.com/MarlinFirmware/Configurations/archive/release-2.0.8.zip +## https://github.com/MarlinFirmware/Configurations/archive/release-2.0.8.1.zip diff --git a/ini/features.ini b/ini/features.ini index 6a2ccbedac..2b69daa88a 100644 --- a/ini/features.ini +++ b/ini/features.ini @@ -198,7 +198,7 @@ MAGNETIC_PARKING_EXTRUDER = src_filter=+ SDSUPPORT = src_filter=+ + + + + + + HAS_MEDIA_SUBCALLS = src_filter=+ GCODE_REPEAT_MARKERS = src_filter=+ + -HAS_EXTRUDERS = src_filter=+ + +HAS_EXTRUDERS = src_filter=+ + + HAS_COOLER = src_filter=+ + AUTO_REPORT_TEMPERATURES = src_filter=+ INCH_MODE_SUPPORT = src_filter=+ diff --git a/ini/stm32f1.ini b/ini/stm32f1.ini index 6a234bdc97..7c450cb266 100644 --- a/ini/stm32f1.ini +++ b/ini/stm32f1.ini @@ -279,7 +279,9 @@ extra_scripts = ${common_stm32f1.extra_scripts} build_flags = ${common_stm32f1.build_flags} -DMCU_STM32F103VE -DSS_TIMER=4 debug_tool = jlink -upload_protocol = jlink +upload_protocol = custom +upload_flags = + 192.168.0.107 # # MKS Robin (STM32F103ZET6)