diff --git a/.github/workflows/test-builds.yml b/.github/workflows/test-builds.yml index 59722e3ca5..b92b015287 100644 --- a/.github/workflows/test-builds.yml +++ b/.github/workflows/test-builds.yml @@ -29,7 +29,7 @@ jobs: - DUE - esp32 - linux_native - - megaatmega2560 + - mega2560 - teensy31 - teensy35 - SAMD51_grandcentral_m4 @@ -37,22 +37,23 @@ jobs: # Extended AVR Environments - FYSETC_F6_13 - - megaatmega1280 + - mega1280 - rambo - - sanguino_atmega1284p - - sanguino_atmega644p + - sanguino1284p + - sanguino644p # Extended STM32 Environments - - STM32F103RC_bigtree - - STM32F103RC_bigtree_USB - - STM32F103RE_bigtree - - STM32F103RE_bigtree_USB + - STM32F103RC_btt + - STM32F103RC_btt_USB + - STM32F103RE_btt + - STM32F103RE_btt_USB - STM32F103RC_fysetc - jgaurora_a5s_a1 - STM32F103VE_longer - STM32F407VE_black - BIGTREE_SKR_PRO + - BIGTREE_GTR_V1_0 - mks_robin - ARMED - FYSETC_S6 diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index 5679aa3093..a92557977f 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -36,7 +36,7 @@ * Advanced settings can be found in Configuration_adv.h * */ -#define CONFIGURATION_H_VERSION 020004 +#define CONFIGURATION_H_VERSION 020005 //=========================================================================== //============================= Getting Started ============================= @@ -925,6 +925,14 @@ #define SMART_EFFECTOR_MOD_PIN -1 // Connect a GPIO pin to the Smart Effector MOD pin #endif +/** + * Use StallGuard2 to probe the bed with the nozzle. + * Requires stallGuard-capable Trinamic stepper drivers. + * CAUTION: This can damage machines with Z lead screws. + * Take extreme care when setting up this feature. + */ +//#define SENSORLESS_PROBING + // // For Z_PROBE_ALLEN_KEY see the Delta example configurations. // diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index ede35a561e..f5d80a3eb3 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -31,7 +31,7 @@ * Basic settings can be found in Configuration.h * */ -#define CONFIGURATION_ADV_H_VERSION 020004 +#define CONFIGURATION_ADV_H_VERSION 020005 // @section temperature @@ -276,8 +276,10 @@ #define AUTOTEMP_OLDWEIGHT 0.98 #endif -// Show extra position information with 'M114 D' -//#define M114_DETAIL +// Extra options for the M114 "Current Position" report +//#define M114_DETAIL // Use 'M114` for details to check planner calculations +//#define M114_REALTIME // Real current position based on forward kinematics +//#define M114_LEGACY // M114 used to synchronize on every call. Enable if needed. // Show Temperature ADC value // Enable for M105 to include ADC values read from temperature sensors. @@ -716,6 +718,9 @@ #define Z_STEPPER_ALIGN_ITERATIONS 5 // Number of iterations to apply during alignment #define Z_STEPPER_ALIGN_ACC 0.02 // Stop iterating early if the accuracy is better than this #define RESTORE_LEVELING_AFTER_G34 // Restore leveling after G34 is done? + // After G34, re-home Z (G28 Z) or just calculate it from the last probe heights? + // Re-homing might be more precise in reproducing the actual 'G28 Z' homing height, especially on an uneven bed. + #define HOME_AFTER_G34 #endif // @section motion @@ -990,6 +995,10 @@ // Show the E position (filament used) during printing //#define LCD_SHOW_E_TOTAL +#if ENABLED(SHOW_BOOTSCREEN) + #define BOOTSCREEN_TIMEOUT 4000 // (ms) Total Duration to display the boot screen(s) +#endif + #if HAS_GRAPHICAL_LCD && HAS_PRINT_PROGRESS //#define PRINT_PROGRESS_SHOW_DECIMALS // Show progress with decimal digits //#define SHOW_REMAINING_TIME // Display estimated time to completion @@ -1012,12 +1021,9 @@ #if ENABLED(SDSUPPORT) - // Some RAMPS and other boards don't detect when an SD card is inserted. You can work - // around this by connecting a push button or single throw switch to the pin defined - // as SD_DETECT_PIN in your board's pins definitions. - // This setting should be disabled unless you are using a push button, pulling the pin to ground. - // Note: This is always disabled for ULTIPANEL (except ELB_FULL_GRAPHIC_CONTROLLER). - #define SD_DETECT_INVERTED + // The standard SD detect circuit reads LOW when media is inserted and HIGH when empty. + // Enable this option and set to HIGH if your SD cards are incorrectly detected. + //#define SD_DETECT_STATE HIGH #define SD_FINISHED_STEPPERRELEASE true // Disable steppers when SD Print is finished #define SD_FINISHED_RELEASECOMMAND "M84 X Y Z E" // You might want to keep the Z enabled so your bed stays in place. @@ -1039,9 +1045,13 @@ * during SD printing. If the recovery file is found at boot time, present * an option on the LCD screen to continue the print from the last-known * point in the file. + * + * If the machine reboots when resuming a print you may need to replace or + * reformat the SD card. (Bad sectors delay startup triggering the watchdog.) */ //#define POWER_LOSS_RECOVERY #if ENABLED(POWER_LOSS_RECOVERY) + #define PLR_ENABLED_DEFAULT false // Power Loss Recovery enabled by default. (Set with 'M413 Sn' & M500) //#define BACKUP_POWER_SUPPLY // Backup power / UPS to move the steppers on power loss //#define POWER_LOSS_ZRAISE 2 // (mm) Z axis raise on resume (on power loss with UPS) //#define POWER_LOSS_PIN 44 // Pin to detect power loss. Set to -1 to disable default pin on boards without module. @@ -1221,10 +1231,6 @@ // Western only. Not available for Cyrillic, Kana, Turkish, Greek, or Chinese. //#define USE_SMALL_INFOFONT - // Enable this option and reduce the value to optimize screen updates. - // The normal delay is 10µs. Use the lowest value that still gives a reliable display. - //#define DOGM_SPI_DELAY_US 5 - // Swap the CW/CCW indicators in the graphics overlay //#define OVERLAY_GFX_REVERSE @@ -1241,6 +1247,10 @@ * This will prevent position updates from being displayed. */ #if ENABLED(U8GLIB_ST7920) + // Enable this option and reduce the value to optimize screen updates. + // The normal delay is 10µs. Use the lowest value that still gives a reliable display. + //#define DOGM_SPI_DELAY_US 5 + //#define LIGHTWEIGHT_UI #if ENABLED(LIGHTWEIGHT_UI) #define STATUS_EXPIRE_SECONDS 20 @@ -1278,7 +1288,7 @@ // Additional options for DGUS / DWIN displays // #if HAS_DGUS_LCD - #define DGUS_SERIAL_PORT 2 + #define DGUS_SERIAL_PORT 3 #define DGUS_BAUDRATE 115200 #define DGUS_RX_BUFFER_SIZE 128 @@ -1286,16 +1296,15 @@ //#define DGUS_SERIAL_STATS_RX_BUFFER_OVERRUNS // Fix Rx overrun situation (Currently only for AVR) #define DGUS_UPDATE_INTERVAL_MS 500 // (ms) Interval between automatic screen updates - #define BOOTSCREEN_TIMEOUT 3000 // (ms) Duration to display the boot screen #if EITHER(DGUS_LCD_UI_FYSETC, DGUS_LCD_UI_HIPRECY) #define DGUS_PRINT_FILENAME // Display the filename during printing #define DGUS_PREHEAT_UI // Display a preheat screen during heatup #if ENABLED(DGUS_LCD_UI_FYSETC) - //#define DUGS_UI_MOVE_DIS_OPTION // Disabled by default for UI_FYSETC + //#define DGUS_UI_MOVE_DIS_OPTION // Disabled by default for UI_FYSETC #else - #define DUGS_UI_MOVE_DIS_OPTION // Enabled by default for UI_HIPRECY + #define DGUS_UI_MOVE_DIS_OPTION // Enabled by default for UI_HIPRECY #endif #define DGUS_FILAMENT_LOADUNLOAD @@ -1578,7 +1587,7 @@ #if ENABLED(PROBE_TEMP_COMPENSATION) // Max temperature that can be reached by heated bed. // This is required only for the calibration process. - #define PTC_MAX_BED_TEMP 110 + #define PTC_MAX_BED_TEMP BED_MAXTEMP // Park position to wait for probe cooldown #define PTC_PARK_POS_X 0.0F @@ -2015,7 +2024,7 @@ * TMCStepper library is required to use TMC stepper drivers. * https://github.com/teemuatlut/TMCStepper */ -#if HAS_TRINAMIC +#if HAS_TRINAMIC_CONFIG #define HOLD_MULTIPLIER 0.5 // Scales down the holding current from run current #define INTERPOLATE true // Interpolate X/Y/Z_MICROSTEPS to 256 @@ -2302,14 +2311,6 @@ */ //#define SENSORLESS_HOMING // StallGuard capable drivers only - /** - * Use StallGuard2 to probe the bed with the nozzle. - * - * CAUTION: This could cause damage to machines that use a lead screw or threaded rod - * to move the Z axis. Take extreme care when attempting to enable this feature. - */ - //#define SENSORLESS_PROBING // StallGuard capable drivers only - #if EITHER(SENSORLESS_HOMING, SENSORLESS_PROBING) // TMC2209: 0...255. TMC2130: -64...63 #define X_STALL_SENSITIVITY 8 @@ -2345,7 +2346,7 @@ */ #define TMC_ADV() { } -#endif // HAS_TRINAMIC +#endif // HAS_TRINAMIC_CONFIG // @section L64XX @@ -2991,7 +2992,7 @@ #define MAX7219_LOAD_PIN 44 //#define MAX7219_GCODE // Add the M7219 G-code to control the LED matrix - #define MAX7219_INIT_TEST 2 // Do a test pattern at initialization (Set to 2 for spiral) + #define MAX7219_INIT_TEST 2 // Test pattern at startup: 0=none, 1=sweep, 2=spiral #define MAX7219_NUMBER_UNITS 1 // Number of Max7219 units in chain. #define MAX7219_ROTATE 0 // Rotate the display clockwise (in multiples of +/- 90°) // connector at: right=0 bottom=-90 top=90 left=180 diff --git a/Marlin/src/HAL/HAL_AVR/HAL.cpp b/Marlin/src/HAL/AVR/HAL.cpp similarity index 100% rename from Marlin/src/HAL/HAL_AVR/HAL.cpp rename to Marlin/src/HAL/AVR/HAL.cpp diff --git a/Marlin/src/HAL/HAL_AVR/HAL.h b/Marlin/src/HAL/AVR/HAL.h similarity index 100% rename from Marlin/src/HAL/HAL_AVR/HAL.h rename to Marlin/src/HAL/AVR/HAL.h diff --git a/Marlin/src/HAL/HAL_AVR/HAL_SPI.cpp b/Marlin/src/HAL/AVR/HAL_SPI.cpp similarity index 98% rename from Marlin/src/HAL/HAL_AVR/HAL_SPI.cpp rename to Marlin/src/HAL/AVR/HAL_SPI.cpp index 29d5e38700..f1f9654c4e 100644 --- a/Marlin/src/HAL/HAL_AVR/HAL_SPI.cpp +++ b/Marlin/src/HAL/AVR/HAL_SPI.cpp @@ -197,7 +197,7 @@ void spiBegin() { // output pin high - like sending 0xFF WRITE(MOSI_PIN, HIGH); - for (uint8_t i = 0; i < 8; i++) { + LOOP_L_N(i, 8) { WRITE(SCK_PIN, HIGH); nop; // adjust so SCK is nice @@ -224,7 +224,7 @@ void spiBegin() { void spiSend(uint8_t data) { // no interrupts during byte send - about 8µs cli(); - for (uint8_t i = 0; i < 8; i++) { + LOOP_L_N(i, 8) { WRITE(SCK_PIN, LOW); WRITE(MOSI_PIN, data & 0x80); data <<= 1; diff --git a/Marlin/src/HAL/HAL_AVR/MarlinSerial.cpp b/Marlin/src/HAL/AVR/MarlinSerial.cpp similarity index 99% rename from Marlin/src/HAL/HAL_AVR/MarlinSerial.cpp rename to Marlin/src/HAL/AVR/MarlinSerial.cpp index a0c636a9f9..350d0f302d 100644 --- a/Marlin/src/HAL/HAL_AVR/MarlinSerial.cpp +++ b/Marlin/src/HAL/AVR/MarlinSerial.cpp @@ -55,7 +55,7 @@ // A SW memory barrier, to ensure GCC does not overoptimize loops #define sw_barrier() asm volatile("": : :"memory"); - #include "../../feature/emergency_parser.h" + #include "../../feature/e_parser.h" // "Atomically" read the RX head index value without disabling interrupts: // This MUST be called with RX interrupts enabled, and CAN'T be called @@ -682,7 +682,7 @@ // Round correctly so that print(1.999, 2) prints as "2.00" double rounding = 0.5; - for (uint8_t i = 0; i < digits; ++i) rounding *= 0.1; + LOOP_L_N(i, digits) rounding *= 0.1; number += rounding; // Extract the integer part of the number and print it diff --git a/Marlin/src/HAL/HAL_AVR/MarlinSerial.h b/Marlin/src/HAL/AVR/MarlinSerial.h similarity index 94% rename from Marlin/src/HAL/HAL_AVR/MarlinSerial.h rename to Marlin/src/HAL/AVR/MarlinSerial.h index 33870e2ca6..cd7aad90a9 100644 --- a/Marlin/src/HAL/HAL_AVR/MarlinSerial.h +++ b/Marlin/src/HAL/AVR/MarlinSerial.h @@ -31,10 +31,10 @@ * Templatized 01 October 2018 by Eduardo José Tagle to allow multiple instances */ -#include "../shared/MarlinSerial.h" - #include +#include "../../inc/MarlinConfigPre.h" + #ifndef SERIAL_PORT #define SERIAL_PORT 0 #endif @@ -261,12 +261,12 @@ static constexpr int PORT = serial; static constexpr unsigned int RX_SIZE = RX_BUFFER_SIZE; static constexpr unsigned int TX_SIZE = TX_BUFFER_SIZE; - static constexpr bool XONOFF = bSERIAL_XON_XOFF; - static constexpr bool EMERGENCYPARSER = bEMERGENCY_PARSER; - static constexpr bool DROPPED_RX = bSERIAL_STATS_DROPPED_RX; - static constexpr bool RX_OVERRUNS = bSERIAL_STATS_RX_BUFFER_OVERRUNS; - static constexpr bool RX_FRAMING_ERRORS = bSERIAL_STATS_RX_FRAMING_ERRORS; - static constexpr bool MAX_RX_QUEUED = bSERIAL_STATS_MAX_RX_QUEUED; + static constexpr bool XONOFF = ENABLED(SERIAL_XON_XOFF); + static constexpr bool EMERGENCYPARSER = ENABLED(EMERGENCY_PARSER); + static constexpr bool DROPPED_RX = ENABLED(SERIAL_STATS_DROPPED_RX); + static constexpr bool RX_OVERRUNS = ENABLED(SERIAL_STATS_RX_BUFFER_OVERRUNS); + static constexpr bool RX_FRAMING_ERRORS = ENABLED(SERIAL_STATS_RX_FRAMING_ERRORS); + static constexpr bool MAX_RX_QUEUED = ENABLED(SERIAL_STATS_MAX_RX_QUEUED); }; extern MarlinSerial> customizedSerial1; @@ -304,7 +304,7 @@ static constexpr bool XONOFF = false; static constexpr bool EMERGENCYPARSER = false; static constexpr bool DROPPED_RX = false; - static constexpr bool RX_OVERRUNS = bDGUS_SERIAL_STATS_RX_BUFFER_OVERRUNS; + static constexpr bool RX_OVERRUNS = HAS_DGUS_LCD && ENABLED(DGUS_SERIAL_STATS_RX_BUFFER_OVERRUNS); static constexpr bool RX_FRAMING_ERRORS = false; static constexpr bool MAX_RX_QUEUED = false; }; diff --git a/Marlin/src/HAL/HAL_AVR/Servo.cpp b/Marlin/src/HAL/AVR/Servo.cpp similarity index 100% rename from Marlin/src/HAL/HAL_AVR/Servo.cpp rename to Marlin/src/HAL/AVR/Servo.cpp diff --git a/Marlin/src/HAL/HAL_AVR/ServoTimers.h b/Marlin/src/HAL/AVR/ServoTimers.h similarity index 100% rename from Marlin/src/HAL/HAL_AVR/ServoTimers.h rename to Marlin/src/HAL/AVR/ServoTimers.h diff --git a/Marlin/src/HAL/HAL_AVR/endstop_interrupts.h b/Marlin/src/HAL/AVR/endstop_interrupts.h similarity index 100% rename from Marlin/src/HAL/HAL_AVR/endstop_interrupts.h rename to Marlin/src/HAL/AVR/endstop_interrupts.h diff --git a/Marlin/src/HAL/HAL_AVR/fast_pwm.cpp b/Marlin/src/HAL/AVR/fast_pwm.cpp similarity index 99% rename from Marlin/src/HAL/HAL_AVR/fast_pwm.cpp rename to Marlin/src/HAL/AVR/fast_pwm.cpp index 78a7ad883b..42e7cc3f10 100644 --- a/Marlin/src/HAL/HAL_AVR/fast_pwm.cpp +++ b/Marlin/src/HAL/AVR/fast_pwm.cpp @@ -167,7 +167,7 @@ void set_pwm_frequency(const pin_t pin, int f_desired) { uint16_t prescaler[] = { 0, 1, 8, /*TIMER2 ONLY*/32, 64, /*TIMER2 ONLY*/128, 256, 1024 }; // loop over prescaler values - for (uint8_t i = 1; i < 8; i++) { + LOOP_S_L_N(i, 1, 8) { uint16_t res_temp_fast = 255, res_temp_phase_correct = 255; if (timer.n == 2) { // No resolution calculation for TIMER2 unless enabled USE_OCR2A_AS_TOP diff --git a/Marlin/src/HAL/HAL_AVR/fastio.cpp b/Marlin/src/HAL/AVR/fastio.cpp similarity index 100% rename from Marlin/src/HAL/HAL_AVR/fastio.cpp rename to Marlin/src/HAL/AVR/fastio.cpp diff --git a/Marlin/src/HAL/HAL_AVR/fastio.h b/Marlin/src/HAL/AVR/fastio.h similarity index 100% rename from Marlin/src/HAL/HAL_AVR/fastio.h rename to Marlin/src/HAL/AVR/fastio.h diff --git a/Marlin/src/HAL/HAL_AVR/fastio/fastio_1280.h b/Marlin/src/HAL/AVR/fastio/fastio_1280.h similarity index 99% rename from Marlin/src/HAL/HAL_AVR/fastio/fastio_1280.h rename to Marlin/src/HAL/AVR/fastio/fastio_1280.h index f9f0d3ceee..b62156caa7 100644 --- a/Marlin/src/HAL/HAL_AVR/fastio/fastio_1280.h +++ b/Marlin/src/HAL/AVR/fastio/fastio_1280.h @@ -26,7 +26,7 @@ * * Hardware Pin : 02 03 06 07 01 05 15 16 17 18 23 24 25 26 64 63 13 12 46 45 44 43 78 77 76 75 74 73 72 71 60 59 58 57 56 55 54 53 50 70 52 51 42 41 40 39 38 37 36 35 22 21 20 19 97 96 95 94 93 92 91 90 89 88 87 86 85 84 83 82 | 04 08 09 10 11 14 27 28 29 30 31 32 33 34 47 48 49 61 62 65 66 67 68 69 79 80 81 98 99 100 * Port : E0 E1 E4 E5 G5 E3 H3 H4 H5 H6 B4 B5 B6 B7 J1 J0 H1 H0 D3 D2 D1 D0 A0 A1 A2 A3 A4 A5 A6 A7 C7 C6 C5 C4 C3 C2 C1 C0 D7 G2 G1 G0 L7 L6 L5 L4 L3 L2 L1 L0 B3 B2 B1 B0 F0 F1 F2 F3 F4 F5 F6 F7 K0 K1 K2 K3 K4 K5 K6 K7 | E2 E6 E7 xx xx H2 H7 G3 G4 xx xx xx xx xx D4 D5 D6 xx xx J2 J3 J4 J5 J6 J7 xx xx xx xx xx - * Logical Pin : 00 01 02 03 04 05 06 07 08 09 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 | 78 79 80 xx xx 84 85 71 70 xx xx xx xx xx 81 82 83 xx xx 72 72 75 76 77 74 xx xx xx xx xx + * Logical Pin : 00 01 02 03 04 05 06 07 08 09 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 | 78 79 80 xx xx 84 85 71 70 xx xx xx xx xx 81 82 83 xx xx 72 73 75 76 77 74 xx xx xx xx xx */ #include "../fastio.h" diff --git a/Marlin/src/HAL/HAL_AVR/fastio/fastio_1281.h b/Marlin/src/HAL/AVR/fastio/fastio_1281.h similarity index 100% rename from Marlin/src/HAL/HAL_AVR/fastio/fastio_1281.h rename to Marlin/src/HAL/AVR/fastio/fastio_1281.h diff --git a/Marlin/src/HAL/HAL_AVR/fastio/fastio_168.h b/Marlin/src/HAL/AVR/fastio/fastio_168.h similarity index 100% rename from Marlin/src/HAL/HAL_AVR/fastio/fastio_168.h rename to Marlin/src/HAL/AVR/fastio/fastio_168.h diff --git a/Marlin/src/HAL/HAL_AVR/fastio/fastio_644.h b/Marlin/src/HAL/AVR/fastio/fastio_644.h similarity index 100% rename from Marlin/src/HAL/HAL_AVR/fastio/fastio_644.h rename to Marlin/src/HAL/AVR/fastio/fastio_644.h diff --git a/Marlin/src/HAL/HAL_AVR/fastio/fastio_AT90USB.h b/Marlin/src/HAL/AVR/fastio/fastio_AT90USB.h similarity index 100% rename from Marlin/src/HAL/HAL_AVR/fastio/fastio_AT90USB.h rename to Marlin/src/HAL/AVR/fastio/fastio_AT90USB.h diff --git a/Marlin/src/HAL/HAL_AVR/inc/Conditionals_LCD.h b/Marlin/src/HAL/AVR/inc/Conditionals_LCD.h similarity index 100% rename from Marlin/src/HAL/HAL_AVR/inc/Conditionals_LCD.h rename to Marlin/src/HAL/AVR/inc/Conditionals_LCD.h diff --git a/Marlin/src/HAL/HAL_AVR/inc/Conditionals_adv.h b/Marlin/src/HAL/AVR/inc/Conditionals_adv.h similarity index 100% rename from Marlin/src/HAL/HAL_AVR/inc/Conditionals_adv.h rename to Marlin/src/HAL/AVR/inc/Conditionals_adv.h diff --git a/Marlin/src/HAL/HAL_AVR/inc/Conditionals_post.h b/Marlin/src/HAL/AVR/inc/Conditionals_post.h similarity index 100% rename from Marlin/src/HAL/HAL_AVR/inc/Conditionals_post.h rename to Marlin/src/HAL/AVR/inc/Conditionals_post.h diff --git a/Marlin/src/HAL/HAL_AVR/inc/SanityCheck.h b/Marlin/src/HAL/AVR/inc/SanityCheck.h similarity index 97% rename from Marlin/src/HAL/HAL_AVR/inc/SanityCheck.h rename to Marlin/src/HAL/AVR/inc/SanityCheck.h index 87864bcaf6..1c7c68f216 100644 --- a/Marlin/src/HAL/HAL_AVR/inc/SanityCheck.h +++ b/Marlin/src/HAL/AVR/inc/SanityCheck.h @@ -56,7 +56,7 @@ /** * The Trinamic library includes SoftwareSerial.h, leading to a compile error. */ -#if HAS_TRINAMIC && ENABLED(ENDSTOP_INTERRUPTS_FEATURE) +#if HAS_TRINAMIC_CONFIG && ENABLED(ENDSTOP_INTERRUPTS_FEATURE) #error "TMCStepper includes SoftwareSerial.h which is incompatible with ENDSTOP_INTERRUPTS_FEATURE. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif diff --git a/Marlin/src/HAL/HAL_AVR/math.h b/Marlin/src/HAL/AVR/math.h similarity index 100% rename from Marlin/src/HAL/HAL_AVR/math.h rename to Marlin/src/HAL/AVR/math.h diff --git a/Marlin/src/HAL/HAL_AVR/persistent_store_eeprom.cpp b/Marlin/src/HAL/AVR/persistent_store_eeprom.cpp similarity index 100% rename from Marlin/src/HAL/HAL_AVR/persistent_store_eeprom.cpp rename to Marlin/src/HAL/AVR/persistent_store_eeprom.cpp diff --git a/Marlin/src/HAL/HAL_AVR/pinsDebug.h b/Marlin/src/HAL/AVR/pinsDebug.h similarity index 99% rename from Marlin/src/HAL/HAL_AVR/pinsDebug.h rename to Marlin/src/HAL/AVR/pinsDebug.h index cea82ef3fa..fbd2e084fa 100644 --- a/Marlin/src/HAL/HAL_AVR/pinsDebug.h +++ b/Marlin/src/HAL/AVR/pinsDebug.h @@ -70,12 +70,12 @@ void PRINT_ARRAY_NAME(uint8_t x) { char *name_mem_pointer = (char*)pgm_read_ptr(&pin_array[x].name); - for (uint8_t y = 0; y < MAX_NAME_LENGTH; y++) { + LOOP_L_N(y, MAX_NAME_LENGTH) { char temp_char = pgm_read_byte(name_mem_pointer + y); if (temp_char != 0) SERIAL_CHAR(temp_char); else { - for (uint8_t i = 0; i < MAX_NAME_LENGTH - y; i++) SERIAL_CHAR(' '); + LOOP_L_N(i, MAX_NAME_LENGTH - y) SERIAL_CHAR(' '); break; } } diff --git a/Marlin/src/HAL/HAL_AVR/pinsDebug_Teensyduino.h b/Marlin/src/HAL/AVR/pinsDebug_Teensyduino.h similarity index 100% rename from Marlin/src/HAL/HAL_AVR/pinsDebug_Teensyduino.h rename to Marlin/src/HAL/AVR/pinsDebug_Teensyduino.h diff --git a/Marlin/src/HAL/HAL_AVR/pinsDebug_plus_70.h b/Marlin/src/HAL/AVR/pinsDebug_plus_70.h similarity index 100% rename from Marlin/src/HAL/HAL_AVR/pinsDebug_plus_70.h rename to Marlin/src/HAL/AVR/pinsDebug_plus_70.h diff --git a/Marlin/src/HAL/HAL_AVR/spi_pins.h b/Marlin/src/HAL/AVR/spi_pins.h similarity index 100% rename from Marlin/src/HAL/HAL_AVR/spi_pins.h rename to Marlin/src/HAL/AVR/spi_pins.h diff --git a/Marlin/src/HAL/HAL_AVR/u8g_com_HAL_AVR_sw_spi.cpp b/Marlin/src/HAL/AVR/u8g_com_HAL_AVR_sw_spi.cpp similarity index 98% rename from Marlin/src/HAL/HAL_AVR/u8g_com_HAL_AVR_sw_spi.cpp rename to Marlin/src/HAL/AVR/u8g_com_HAL_AVR_sw_spi.cpp index 60b4e83104..fab79646f0 100644 --- a/Marlin/src/HAL/HAL_AVR/u8g_com_HAL_AVR_sw_spi.cpp +++ b/Marlin/src/HAL/AVR/u8g_com_HAL_AVR_sw_spi.cpp @@ -88,7 +88,7 @@ void u8g_spiSend_sw_AVR_mode_0(uint8_t val) { volatile uint8_t *outData = u8g_outData, *outClock = u8g_outClock; U8G_ATOMIC_START(); - for (uint8_t i = 0; i < 8; i++) { + LOOP_L_N(i, 8) { if (val & 0x80) *outData |= bitData; else @@ -108,7 +108,7 @@ void u8g_spiSend_sw_AVR_mode_3(uint8_t val) { volatile uint8_t *outData = u8g_outData, *outClock = u8g_outClock; U8G_ATOMIC_START(); - for (uint8_t i = 0; i < 8; i++) { + LOOP_L_N(i, 8) { *outClock &= bitNotClock; if (val & 0x80) *outData |= bitData; diff --git a/Marlin/src/HAL/HAL_AVR/watchdog.cpp b/Marlin/src/HAL/AVR/watchdog.cpp similarity index 100% rename from Marlin/src/HAL/HAL_AVR/watchdog.cpp rename to Marlin/src/HAL/AVR/watchdog.cpp diff --git a/Marlin/src/HAL/HAL_AVR/watchdog.h b/Marlin/src/HAL/AVR/watchdog.h similarity index 100% rename from Marlin/src/HAL/HAL_AVR/watchdog.h rename to Marlin/src/HAL/AVR/watchdog.h diff --git a/Marlin/src/HAL/HAL_DUE/DebugMonitor.cpp b/Marlin/src/HAL/DUE/DebugMonitor.cpp similarity index 100% rename from Marlin/src/HAL/HAL_DUE/DebugMonitor.cpp rename to Marlin/src/HAL/DUE/DebugMonitor.cpp diff --git a/Marlin/src/HAL/HAL_DUE/EepromEmulation.cpp b/Marlin/src/HAL/DUE/EepromEmulation.cpp similarity index 99% rename from Marlin/src/HAL/HAL_DUE/EepromEmulation.cpp rename to Marlin/src/HAL/DUE/EepromEmulation.cpp index 9263079358..f1ae224bfc 100644 --- a/Marlin/src/HAL/HAL_DUE/EepromEmulation.cpp +++ b/Marlin/src/HAL/DUE/EepromEmulation.cpp @@ -54,7 +54,7 @@ #include "../../inc/MarlinConfig.h" -#if ENABLED(EEPROM_SETTINGS) && NONE(I2C_EEPROM, SPI_EEPROM) +#if ENABLED(FLASH_EEPROM_EMULATION) #include "../shared/Marduino.h" #include "../shared/persistent_store_api.h" @@ -1016,5 +1016,5 @@ void eeprom_flush() { ee_Flush(); } -#endif // EEPROM_SETTINGS && (!I2C_EEPROM && !SPI_EEPROM) +#endif // FLASH_EEPROM_EMULATION #endif // ARDUINO_ARCH_AVR diff --git a/Marlin/src/HAL/HAL_DUE/HAL.cpp b/Marlin/src/HAL/DUE/HAL.cpp similarity index 100% rename from Marlin/src/HAL/HAL_DUE/HAL.cpp rename to Marlin/src/HAL/DUE/HAL.cpp diff --git a/Marlin/src/HAL/HAL_DUE/HAL.h b/Marlin/src/HAL/DUE/HAL.h similarity index 100% rename from Marlin/src/HAL/HAL_DUE/HAL.h rename to Marlin/src/HAL/DUE/HAL.h diff --git a/Marlin/src/HAL/HAL_DUE/HAL_SPI.cpp b/Marlin/src/HAL/DUE/HAL_SPI.cpp similarity index 100% rename from Marlin/src/HAL/HAL_DUE/HAL_SPI.cpp rename to Marlin/src/HAL/DUE/HAL_SPI.cpp diff --git a/Marlin/src/HAL/HAL_DUE/InterruptVectors.cpp b/Marlin/src/HAL/DUE/InterruptVectors.cpp similarity index 100% rename from Marlin/src/HAL/HAL_DUE/InterruptVectors.cpp rename to Marlin/src/HAL/DUE/InterruptVectors.cpp diff --git a/Marlin/src/HAL/HAL_DUE/InterruptVectors.h b/Marlin/src/HAL/DUE/InterruptVectors.h similarity index 100% rename from Marlin/src/HAL/HAL_DUE/InterruptVectors.h rename to Marlin/src/HAL/DUE/InterruptVectors.h diff --git a/Marlin/src/HAL/HAL_DUE/MarlinSerial.cpp b/Marlin/src/HAL/DUE/MarlinSerial.cpp similarity index 99% rename from Marlin/src/HAL/HAL_DUE/MarlinSerial.cpp rename to Marlin/src/HAL/DUE/MarlinSerial.cpp index 3cd6f7d5ed..d827def422 100644 --- a/Marlin/src/HAL/HAL_DUE/MarlinSerial.cpp +++ b/Marlin/src/HAL/DUE/MarlinSerial.cpp @@ -45,7 +45,7 @@ template typename MarlinSerial::ring_buffer_pos_t MarlinSeria // A SW memory barrier, to ensure GCC does not overoptimize loops #define sw_barrier() asm volatile("": : :"memory"); -#include "../../feature/emergency_parser.h" +#include "../../feature/e_parser.h" // (called with RX interrupts disabled) template @@ -606,7 +606,7 @@ void MarlinSerial::printFloat(double number, uint8_t digits) { // Round correctly so that print(1.999, 2) prints as "2.00" double rounding = 0.5; - for (uint8_t i = 0; i < digits; ++i) rounding *= 0.1; + LOOP_L_N(i, digits) rounding *= 0.1; number += rounding; // Extract the integer part of the number and print it diff --git a/Marlin/src/HAL/HAL_DUE/MarlinSerial.h b/Marlin/src/HAL/DUE/MarlinSerial.h similarity index 92% rename from Marlin/src/HAL/HAL_DUE/MarlinSerial.h rename to Marlin/src/HAL/DUE/MarlinSerial.h index af7d2b7ade..eb26a5644d 100644 --- a/Marlin/src/HAL/HAL_DUE/MarlinSerial.h +++ b/Marlin/src/HAL/DUE/MarlinSerial.h @@ -27,10 +27,10 @@ * Based on MarlinSerial for AVR, copyright (c) 2006 Nicholas Zambetti. All right reserved. */ -#include "../shared/MarlinSerial.h" - #include +#include "../../inc/MarlinConfigPre.h" + #define DEC 10 #define HEX 16 #define OCT 8 @@ -163,12 +163,12 @@ struct MarlinSerialCfg { static constexpr int PORT = serial; static constexpr unsigned int RX_SIZE = RX_BUFFER_SIZE; static constexpr unsigned int TX_SIZE = TX_BUFFER_SIZE; - static constexpr bool XONOFF = bSERIAL_XON_XOFF; - static constexpr bool EMERGENCYPARSER = bEMERGENCY_PARSER; - static constexpr bool DROPPED_RX = bSERIAL_STATS_DROPPED_RX; - static constexpr bool RX_OVERRUNS = bSERIAL_STATS_RX_BUFFER_OVERRUNS; - static constexpr bool RX_FRAMING_ERRORS = bSERIAL_STATS_RX_FRAMING_ERRORS; - static constexpr bool MAX_RX_QUEUED = bSERIAL_STATS_MAX_RX_QUEUED; + static constexpr bool XONOFF = ENABLED(SERIAL_XON_XOFF); + static constexpr bool EMERGENCYPARSER = ENABLED(EMERGENCY_PARSER); + static constexpr bool DROPPED_RX = ENABLED(SERIAL_STATS_DROPPED_RX); + static constexpr bool RX_OVERRUNS = ENABLED(SERIAL_STATS_RX_BUFFER_OVERRUNS); + static constexpr bool RX_FRAMING_ERRORS = ENABLED(SERIAL_STATS_RX_FRAMING_ERRORS); + static constexpr bool MAX_RX_QUEUED = ENABLED(SERIAL_STATS_MAX_RX_QUEUED); }; #if SERIAL_PORT >= 0 diff --git a/Marlin/src/HAL/HAL_DUE/MarlinSerialUSB.cpp b/Marlin/src/HAL/DUE/MarlinSerialUSB.cpp similarity index 98% rename from Marlin/src/HAL/HAL_DUE/MarlinSerialUSB.cpp rename to Marlin/src/HAL/DUE/MarlinSerialUSB.cpp index 38cdd8f8a1..41ffb52ba1 100644 --- a/Marlin/src/HAL/HAL_DUE/MarlinSerialUSB.cpp +++ b/Marlin/src/HAL/DUE/MarlinSerialUSB.cpp @@ -34,7 +34,7 @@ #include "MarlinSerialUSB.h" #if ENABLED(EMERGENCY_PARSER) - #include "../../feature/emergency_parser.h" + #include "../../feature/e_parser.h" #endif // Imports from Atmel USB Stack/CDC implementation @@ -259,7 +259,7 @@ void MarlinSerialUSB::printFloat(double number, uint8_t digits) { // Round correctly so that print(1.999, 2) prints as "2.00" double rounding = 0.5; - for (uint8_t i = 0; i < digits; ++i) + LOOP_L_N(i, digits) rounding *= 0.1; number += rounding; diff --git a/Marlin/src/HAL/HAL_DUE/MarlinSerialUSB.h b/Marlin/src/HAL/DUE/MarlinSerialUSB.h similarity index 100% rename from Marlin/src/HAL/HAL_DUE/MarlinSerialUSB.h rename to Marlin/src/HAL/DUE/MarlinSerialUSB.h diff --git a/Marlin/src/HAL/HAL_DUE/Servo.cpp b/Marlin/src/HAL/DUE/Servo.cpp similarity index 100% rename from Marlin/src/HAL/HAL_DUE/Servo.cpp rename to Marlin/src/HAL/DUE/Servo.cpp diff --git a/Marlin/src/HAL/HAL_DUE/ServoTimers.h b/Marlin/src/HAL/DUE/ServoTimers.h similarity index 100% rename from Marlin/src/HAL/HAL_DUE/ServoTimers.h rename to Marlin/src/HAL/DUE/ServoTimers.h diff --git a/Marlin/src/HAL/HAL_DUE/Tone.cpp b/Marlin/src/HAL/DUE/Tone.cpp similarity index 100% rename from Marlin/src/HAL/HAL_DUE/Tone.cpp rename to Marlin/src/HAL/DUE/Tone.cpp diff --git a/Marlin/src/HAL/HAL_DUE/dogm/u8g_com_HAL_DUE_shared_hw_spi.cpp b/Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_shared_hw_spi.cpp similarity index 100% rename from Marlin/src/HAL/HAL_DUE/dogm/u8g_com_HAL_DUE_shared_hw_spi.cpp rename to Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_shared_hw_spi.cpp diff --git a/Marlin/src/HAL/HAL_DUE/dogm/u8g_com_HAL_DUE_st7920_sw_spi.cpp b/Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_st7920_sw_spi.cpp similarity index 100% rename from Marlin/src/HAL/HAL_DUE/dogm/u8g_com_HAL_DUE_st7920_sw_spi.cpp rename to Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_st7920_sw_spi.cpp diff --git a/Marlin/src/HAL/HAL_DUE/dogm/u8g_com_HAL_DUE_sw_spi.cpp b/Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_sw_spi.cpp similarity index 100% rename from Marlin/src/HAL/HAL_DUE/dogm/u8g_com_HAL_DUE_sw_spi.cpp rename to Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_sw_spi.cpp diff --git a/Marlin/src/HAL/HAL_DUE/dogm/u8g_com_HAL_DUE_sw_spi_shared.cpp b/Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_sw_spi_shared.cpp similarity index 98% rename from Marlin/src/HAL/HAL_DUE/dogm/u8g_com_HAL_DUE_sw_spi_shared.cpp rename to Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_sw_spi_shared.cpp index 2563cf110f..96b7a1f61e 100644 --- a/Marlin/src/HAL/HAL_DUE/dogm/u8g_com_HAL_DUE_sw_spi_shared.cpp +++ b/Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_sw_spi_shared.cpp @@ -80,7 +80,7 @@ Pio *SCK_pPio, *MOSI_pPio; uint32_t SCK_dwMask, MOSI_dwMask; void u8g_spiSend_sw_DUE_mode_0(uint8_t val) { // 3MHz - for (uint8_t i = 0; i < 8; i++) { + LOOP_L_N(i, 8) { if (val & 0x80) MOSI_pPio->PIO_SODR = MOSI_dwMask; else @@ -94,7 +94,7 @@ void u8g_spiSend_sw_DUE_mode_0(uint8_t val) { // 3MHz } void u8g_spiSend_sw_DUE_mode_3(uint8_t val) { // 3.5MHz - for (uint8_t i = 0; i < 8; i++) { + LOOP_L_N(i, 8) { SCK_pPio->PIO_CODR = SCK_dwMask; DELAY_NS(50); if (val & 0x80) diff --git a/Marlin/src/HAL/HAL_DUE/dogm/u8g_com_HAL_DUE_sw_spi_shared.h b/Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_sw_spi_shared.h similarity index 100% rename from Marlin/src/HAL/HAL_DUE/dogm/u8g_com_HAL_DUE_sw_spi_shared.h rename to Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_sw_spi_shared.h diff --git a/Marlin/src/HAL/HAL_DUE/endstop_interrupts.h b/Marlin/src/HAL/DUE/endstop_interrupts.h similarity index 100% rename from Marlin/src/HAL/HAL_DUE/endstop_interrupts.h rename to Marlin/src/HAL/DUE/endstop_interrupts.h diff --git a/Marlin/src/HAL/HAL_DUE/fastio.h b/Marlin/src/HAL/DUE/fastio.h similarity index 100% rename from Marlin/src/HAL/HAL_DUE/fastio.h rename to Marlin/src/HAL/DUE/fastio.h diff --git a/Marlin/src/HAL/HAL_DUE/fastio/G2_PWM.cpp b/Marlin/src/HAL/DUE/fastio/G2_PWM.cpp similarity index 100% rename from Marlin/src/HAL/HAL_DUE/fastio/G2_PWM.cpp rename to Marlin/src/HAL/DUE/fastio/G2_PWM.cpp diff --git a/Marlin/src/HAL/HAL_DUE/fastio/G2_PWM.h b/Marlin/src/HAL/DUE/fastio/G2_PWM.h similarity index 96% rename from Marlin/src/HAL/HAL_DUE/fastio/G2_PWM.h rename to Marlin/src/HAL/DUE/fastio/G2_PWM.h index 1a802ed0f3..a94c1c5276 100644 --- a/Marlin/src/HAL/HAL_DUE/fastio/G2_PWM.h +++ b/Marlin/src/HAL/DUE/fastio/G2_PWM.h @@ -63,7 +63,7 @@ extern PWM_map ISR_table[NUM_PWMS]; extern uint32_t motor_current_setting[3]; #define IR_BIT(p) (WITHIN(p, 0, 3) ? (p) : (p) + 4) -#define COPY_ACTIVE_TABLE() do{ for (uint8_t i = 0; i < 6 ; i++) work_table[i] = active_table[i]; }while(0) +#define COPY_ACTIVE_TABLE() do{ LOOP_L_N(i, 6) work_table[i] = active_table[i]; }while(0) #define PWM_MR0 19999 // base repetition rate minus one count - 20mS #define PWM_PR 24 // prescaler value - prescaler divide by 24 + 1 - 1 MHz output diff --git a/Marlin/src/HAL/HAL_DUE/fastio/G2_pins.h b/Marlin/src/HAL/DUE/fastio/G2_pins.h similarity index 100% rename from Marlin/src/HAL/HAL_DUE/fastio/G2_pins.h rename to Marlin/src/HAL/DUE/fastio/G2_pins.h diff --git a/Marlin/src/HAL/HAL_DUE/inc/Conditionals_LCD.h b/Marlin/src/HAL/DUE/inc/Conditionals_LCD.h similarity index 100% rename from Marlin/src/HAL/HAL_DUE/inc/Conditionals_LCD.h rename to Marlin/src/HAL/DUE/inc/Conditionals_LCD.h diff --git a/Marlin/src/HAL/HAL_DUE/inc/Conditionals_adv.h b/Marlin/src/HAL/DUE/inc/Conditionals_adv.h similarity index 100% rename from Marlin/src/HAL/HAL_DUE/inc/Conditionals_adv.h rename to Marlin/src/HAL/DUE/inc/Conditionals_adv.h diff --git a/Marlin/src/HAL/HAL_TEENSY31_32/inc/Conditionals_post.h b/Marlin/src/HAL/DUE/inc/Conditionals_post.h similarity index 86% rename from Marlin/src/HAL/HAL_TEENSY31_32/inc/Conditionals_post.h rename to Marlin/src/HAL/DUE/inc/Conditionals_post.h index 0285c52ee3..223890d790 100644 --- a/Marlin/src/HAL/HAL_TEENSY31_32/inc/Conditionals_post.h +++ b/Marlin/src/HAL/DUE/inc/Conditionals_post.h @@ -20,3 +20,9 @@ * */ #pragma once + +#if USE_EMULATED_EEPROM + #undef SRAM_EEPROM_EMULATION + #undef SDCARD_EEPROM_EMULATION + #define FLASH_EEPROM_EMULATION 1 +#endif diff --git a/Marlin/src/HAL/HAL_DUE/inc/SanityCheck.h b/Marlin/src/HAL/DUE/inc/SanityCheck.h similarity index 100% rename from Marlin/src/HAL/HAL_DUE/inc/SanityCheck.h rename to Marlin/src/HAL/DUE/inc/SanityCheck.h diff --git a/Marlin/src/HAL/HAL_DUE/persistent_store_eeprom.cpp b/Marlin/src/HAL/DUE/persistent_store_eeprom.cpp similarity index 96% rename from Marlin/src/HAL/HAL_DUE/persistent_store_eeprom.cpp rename to Marlin/src/HAL/DUE/persistent_store_eeprom.cpp index 9fdcca7850..fbdc760e45 100644 --- a/Marlin/src/HAL/HAL_DUE/persistent_store_eeprom.cpp +++ b/Marlin/src/HAL/DUE/persistent_store_eeprom.cpp @@ -29,7 +29,7 @@ #include "../../inc/MarlinConfig.h" #include "../shared/persistent_store_api.h" -#if !defined(E2END) && NONE(I2C_EEPROM, SPI_EEPROM) +#if !defined(E2END) && ENABLED(FLASH_EEPROM_EMULATION) #define E2END 0xFFF // Default to Flash emulated EEPROM size (EepromEmulation_Due.cpp) #endif @@ -38,7 +38,7 @@ extern void eeprom_flush(); bool PersistentStore::access_start() { return true; } bool PersistentStore::access_finish() { - #if NONE(I2C_EEPROM, SPI_EEPROM) + #if ENABLED(FLASH_EEPROM_EMULATION) eeprom_flush(); #endif return true; diff --git a/Marlin/src/HAL/HAL_DUE/pinsDebug.h b/Marlin/src/HAL/DUE/pinsDebug.h similarity index 100% rename from Marlin/src/HAL/HAL_DUE/pinsDebug.h rename to Marlin/src/HAL/DUE/pinsDebug.h diff --git a/Marlin/src/HAL/HAL_DUE/spi_pins.h b/Marlin/src/HAL/DUE/spi_pins.h similarity index 100% rename from Marlin/src/HAL/HAL_DUE/spi_pins.h rename to Marlin/src/HAL/DUE/spi_pins.h diff --git a/Marlin/src/HAL/HAL_DUE/timers.cpp b/Marlin/src/HAL/DUE/timers.cpp similarity index 100% rename from Marlin/src/HAL/HAL_DUE/timers.cpp rename to Marlin/src/HAL/DUE/timers.cpp diff --git a/Marlin/src/HAL/HAL_DUE/timers.h b/Marlin/src/HAL/DUE/timers.h similarity index 100% rename from Marlin/src/HAL/HAL_DUE/timers.h rename to Marlin/src/HAL/DUE/timers.h diff --git a/Marlin/src/HAL/HAL_DUE/usb/arduino_due_x.h b/Marlin/src/HAL/DUE/usb/arduino_due_x.h similarity index 100% rename from Marlin/src/HAL/HAL_DUE/usb/arduino_due_x.h rename to Marlin/src/HAL/DUE/usb/arduino_due_x.h diff --git a/Marlin/src/HAL/HAL_DUE/usb/compiler.h b/Marlin/src/HAL/DUE/usb/compiler.h similarity index 100% rename from Marlin/src/HAL/HAL_DUE/usb/compiler.h rename to Marlin/src/HAL/DUE/usb/compiler.h diff --git a/Marlin/src/HAL/HAL_DUE/usb/conf_access.h b/Marlin/src/HAL/DUE/usb/conf_access.h similarity index 100% rename from Marlin/src/HAL/HAL_DUE/usb/conf_access.h rename to Marlin/src/HAL/DUE/usb/conf_access.h diff --git a/Marlin/src/HAL/HAL_DUE/usb/conf_clock.h b/Marlin/src/HAL/DUE/usb/conf_clock.h similarity index 100% rename from Marlin/src/HAL/HAL_DUE/usb/conf_clock.h rename to Marlin/src/HAL/DUE/usb/conf_clock.h diff --git a/Marlin/src/HAL/HAL_DUE/usb/conf_usb.h b/Marlin/src/HAL/DUE/usb/conf_usb.h similarity index 100% rename from Marlin/src/HAL/HAL_DUE/usb/conf_usb.h rename to Marlin/src/HAL/DUE/usb/conf_usb.h diff --git a/Marlin/src/HAL/HAL_DUE/usb/ctrl_access.c b/Marlin/src/HAL/DUE/usb/ctrl_access.c similarity index 100% rename from Marlin/src/HAL/HAL_DUE/usb/ctrl_access.c rename to Marlin/src/HAL/DUE/usb/ctrl_access.c diff --git a/Marlin/src/HAL/HAL_DUE/usb/ctrl_access.h b/Marlin/src/HAL/DUE/usb/ctrl_access.h similarity index 100% rename from Marlin/src/HAL/HAL_DUE/usb/ctrl_access.h rename to Marlin/src/HAL/DUE/usb/ctrl_access.h diff --git a/Marlin/src/HAL/HAL_DUE/usb/genclk.h b/Marlin/src/HAL/DUE/usb/genclk.h similarity index 100% rename from Marlin/src/HAL/HAL_DUE/usb/genclk.h rename to Marlin/src/HAL/DUE/usb/genclk.h diff --git a/Marlin/src/HAL/HAL_DUE/usb/mrepeat.h b/Marlin/src/HAL/DUE/usb/mrepeat.h similarity index 100% rename from Marlin/src/HAL/HAL_DUE/usb/mrepeat.h rename to Marlin/src/HAL/DUE/usb/mrepeat.h diff --git a/Marlin/src/HAL/HAL_DUE/usb/osc.h b/Marlin/src/HAL/DUE/usb/osc.h similarity index 100% rename from Marlin/src/HAL/HAL_DUE/usb/osc.h rename to Marlin/src/HAL/DUE/usb/osc.h diff --git a/Marlin/src/HAL/HAL_DUE/usb/pll.h b/Marlin/src/HAL/DUE/usb/pll.h similarity index 100% rename from Marlin/src/HAL/HAL_DUE/usb/pll.h rename to Marlin/src/HAL/DUE/usb/pll.h diff --git a/Marlin/src/HAL/HAL_DUE/usb/preprocessor.h b/Marlin/src/HAL/DUE/usb/preprocessor.h similarity index 100% rename from Marlin/src/HAL/HAL_DUE/usb/preprocessor.h rename to Marlin/src/HAL/DUE/usb/preprocessor.h diff --git a/Marlin/src/HAL/HAL_DUE/usb/sbc_protocol.h b/Marlin/src/HAL/DUE/usb/sbc_protocol.h similarity index 100% rename from Marlin/src/HAL/HAL_DUE/usb/sbc_protocol.h rename to Marlin/src/HAL/DUE/usb/sbc_protocol.h diff --git a/Marlin/src/HAL/HAL_DUE/usb/sd_mmc_spi_mem.cpp b/Marlin/src/HAL/DUE/usb/sd_mmc_spi_mem.cpp similarity index 100% rename from Marlin/src/HAL/HAL_DUE/usb/sd_mmc_spi_mem.cpp rename to Marlin/src/HAL/DUE/usb/sd_mmc_spi_mem.cpp diff --git a/Marlin/src/HAL/HAL_DUE/usb/sd_mmc_spi_mem.h b/Marlin/src/HAL/DUE/usb/sd_mmc_spi_mem.h similarity index 100% rename from Marlin/src/HAL/HAL_DUE/usb/sd_mmc_spi_mem.h rename to Marlin/src/HAL/DUE/usb/sd_mmc_spi_mem.h diff --git a/Marlin/src/HAL/HAL_DUE/usb/spc_protocol.h b/Marlin/src/HAL/DUE/usb/spc_protocol.h similarity index 100% rename from Marlin/src/HAL/HAL_DUE/usb/spc_protocol.h rename to Marlin/src/HAL/DUE/usb/spc_protocol.h diff --git a/Marlin/src/HAL/HAL_DUE/usb/stringz.h b/Marlin/src/HAL/DUE/usb/stringz.h similarity index 100% rename from Marlin/src/HAL/HAL_DUE/usb/stringz.h rename to Marlin/src/HAL/DUE/usb/stringz.h diff --git a/Marlin/src/HAL/HAL_DUE/usb/sysclk.c b/Marlin/src/HAL/DUE/usb/sysclk.c similarity index 100% rename from Marlin/src/HAL/HAL_DUE/usb/sysclk.c rename to Marlin/src/HAL/DUE/usb/sysclk.c diff --git a/Marlin/src/HAL/HAL_DUE/usb/sysclk.h b/Marlin/src/HAL/DUE/usb/sysclk.h similarity index 100% rename from Marlin/src/HAL/HAL_DUE/usb/sysclk.h rename to Marlin/src/HAL/DUE/usb/sysclk.h diff --git a/Marlin/src/HAL/HAL_DUE/usb/tpaste.h b/Marlin/src/HAL/DUE/usb/tpaste.h similarity index 100% rename from Marlin/src/HAL/HAL_DUE/usb/tpaste.h rename to Marlin/src/HAL/DUE/usb/tpaste.h diff --git a/Marlin/src/HAL/HAL_DUE/usb/udc.c b/Marlin/src/HAL/DUE/usb/udc.c similarity index 100% rename from Marlin/src/HAL/HAL_DUE/usb/udc.c rename to Marlin/src/HAL/DUE/usb/udc.c diff --git a/Marlin/src/HAL/HAL_DUE/usb/udc.h b/Marlin/src/HAL/DUE/usb/udc.h similarity index 100% rename from Marlin/src/HAL/HAL_DUE/usb/udc.h rename to Marlin/src/HAL/DUE/usb/udc.h diff --git a/Marlin/src/HAL/HAL_DUE/usb/udc_desc.h b/Marlin/src/HAL/DUE/usb/udc_desc.h similarity index 100% rename from Marlin/src/HAL/HAL_DUE/usb/udc_desc.h rename to Marlin/src/HAL/DUE/usb/udc_desc.h diff --git a/Marlin/src/HAL/HAL_DUE/usb/udd.h b/Marlin/src/HAL/DUE/usb/udd.h similarity index 100% rename from Marlin/src/HAL/HAL_DUE/usb/udd.h rename to Marlin/src/HAL/DUE/usb/udd.h diff --git a/Marlin/src/HAL/HAL_DUE/usb/udi.h b/Marlin/src/HAL/DUE/usb/udi.h similarity index 100% rename from Marlin/src/HAL/HAL_DUE/usb/udi.h rename to Marlin/src/HAL/DUE/usb/udi.h diff --git a/Marlin/src/HAL/HAL_DUE/usb/udi_cdc.c b/Marlin/src/HAL/DUE/usb/udi_cdc.c similarity index 100% rename from Marlin/src/HAL/HAL_DUE/usb/udi_cdc.c rename to Marlin/src/HAL/DUE/usb/udi_cdc.c diff --git a/Marlin/src/HAL/HAL_DUE/usb/udi_cdc.h b/Marlin/src/HAL/DUE/usb/udi_cdc.h similarity index 100% rename from Marlin/src/HAL/HAL_DUE/usb/udi_cdc.h rename to Marlin/src/HAL/DUE/usb/udi_cdc.h diff --git a/Marlin/src/HAL/HAL_DUE/usb/udi_cdc_conf.h b/Marlin/src/HAL/DUE/usb/udi_cdc_conf.h similarity index 100% rename from Marlin/src/HAL/HAL_DUE/usb/udi_cdc_conf.h rename to Marlin/src/HAL/DUE/usb/udi_cdc_conf.h diff --git a/Marlin/src/HAL/HAL_DUE/usb/udi_cdc_desc.c b/Marlin/src/HAL/DUE/usb/udi_cdc_desc.c similarity index 100% rename from Marlin/src/HAL/HAL_DUE/usb/udi_cdc_desc.c rename to Marlin/src/HAL/DUE/usb/udi_cdc_desc.c diff --git a/Marlin/src/HAL/HAL_DUE/usb/udi_composite_desc.c b/Marlin/src/HAL/DUE/usb/udi_composite_desc.c similarity index 100% rename from Marlin/src/HAL/HAL_DUE/usb/udi_composite_desc.c rename to Marlin/src/HAL/DUE/usb/udi_composite_desc.c diff --git a/Marlin/src/HAL/HAL_DUE/usb/udi_msc.c b/Marlin/src/HAL/DUE/usb/udi_msc.c similarity index 100% rename from Marlin/src/HAL/HAL_DUE/usb/udi_msc.c rename to Marlin/src/HAL/DUE/usb/udi_msc.c diff --git a/Marlin/src/HAL/HAL_DUE/usb/udi_msc.h b/Marlin/src/HAL/DUE/usb/udi_msc.h similarity index 100% rename from Marlin/src/HAL/HAL_DUE/usb/udi_msc.h rename to Marlin/src/HAL/DUE/usb/udi_msc.h diff --git a/Marlin/src/HAL/HAL_DUE/usb/uotghs_device_due.c b/Marlin/src/HAL/DUE/usb/uotghs_device_due.c similarity index 100% rename from Marlin/src/HAL/HAL_DUE/usb/uotghs_device_due.c rename to Marlin/src/HAL/DUE/usb/uotghs_device_due.c diff --git a/Marlin/src/HAL/HAL_DUE/usb/uotghs_device_due.h b/Marlin/src/HAL/DUE/usb/uotghs_device_due.h similarity index 100% rename from Marlin/src/HAL/HAL_DUE/usb/uotghs_device_due.h rename to Marlin/src/HAL/DUE/usb/uotghs_device_due.h diff --git a/Marlin/src/HAL/HAL_DUE/usb/uotghs_otg.h b/Marlin/src/HAL/DUE/usb/uotghs_otg.h similarity index 100% rename from Marlin/src/HAL/HAL_DUE/usb/uotghs_otg.h rename to Marlin/src/HAL/DUE/usb/uotghs_otg.h diff --git a/Marlin/src/HAL/HAL_DUE/usb/usb_protocol.h b/Marlin/src/HAL/DUE/usb/usb_protocol.h similarity index 100% rename from Marlin/src/HAL/HAL_DUE/usb/usb_protocol.h rename to Marlin/src/HAL/DUE/usb/usb_protocol.h diff --git a/Marlin/src/HAL/HAL_DUE/usb/usb_protocol_cdc.h b/Marlin/src/HAL/DUE/usb/usb_protocol_cdc.h similarity index 100% rename from Marlin/src/HAL/HAL_DUE/usb/usb_protocol_cdc.h rename to Marlin/src/HAL/DUE/usb/usb_protocol_cdc.h diff --git a/Marlin/src/HAL/HAL_DUE/usb/usb_protocol_msc.h b/Marlin/src/HAL/DUE/usb/usb_protocol_msc.h similarity index 100% rename from Marlin/src/HAL/HAL_DUE/usb/usb_protocol_msc.h rename to Marlin/src/HAL/DUE/usb/usb_protocol_msc.h diff --git a/Marlin/src/HAL/HAL_DUE/usb/usb_task.c b/Marlin/src/HAL/DUE/usb/usb_task.c similarity index 100% rename from Marlin/src/HAL/HAL_DUE/usb/usb_task.c rename to Marlin/src/HAL/DUE/usb/usb_task.c diff --git a/Marlin/src/HAL/HAL_DUE/usb/usb_task.h b/Marlin/src/HAL/DUE/usb/usb_task.h similarity index 100% rename from Marlin/src/HAL/HAL_DUE/usb/usb_task.h rename to Marlin/src/HAL/DUE/usb/usb_task.h diff --git a/Marlin/src/HAL/HAL_DUE/watchdog.cpp b/Marlin/src/HAL/DUE/watchdog.cpp similarity index 100% rename from Marlin/src/HAL/HAL_DUE/watchdog.cpp rename to Marlin/src/HAL/DUE/watchdog.cpp diff --git a/Marlin/src/HAL/HAL_DUE/watchdog.h b/Marlin/src/HAL/DUE/watchdog.h similarity index 100% rename from Marlin/src/HAL/HAL_DUE/watchdog.h rename to Marlin/src/HAL/DUE/watchdog.h diff --git a/Marlin/src/HAL/HAL_ESP32/FlushableHardwareSerial.cpp b/Marlin/src/HAL/ESP32/FlushableHardwareSerial.cpp similarity index 100% rename from Marlin/src/HAL/HAL_ESP32/FlushableHardwareSerial.cpp rename to Marlin/src/HAL/ESP32/FlushableHardwareSerial.cpp diff --git a/Marlin/src/HAL/HAL_ESP32/FlushableHardwareSerial.h b/Marlin/src/HAL/ESP32/FlushableHardwareSerial.h similarity index 100% rename from Marlin/src/HAL/HAL_ESP32/FlushableHardwareSerial.h rename to Marlin/src/HAL/ESP32/FlushableHardwareSerial.h diff --git a/Marlin/src/HAL/HAL_ESP32/HAL.cpp b/Marlin/src/HAL/ESP32/HAL.cpp similarity index 100% rename from Marlin/src/HAL/HAL_ESP32/HAL.cpp rename to Marlin/src/HAL/ESP32/HAL.cpp diff --git a/Marlin/src/HAL/HAL_ESP32/HAL.h b/Marlin/src/HAL/ESP32/HAL.h similarity index 100% rename from Marlin/src/HAL/HAL_ESP32/HAL.h rename to Marlin/src/HAL/ESP32/HAL.h diff --git a/Marlin/src/HAL/HAL_ESP32/HAL_SPI.cpp b/Marlin/src/HAL/ESP32/HAL_SPI.cpp similarity index 100% rename from Marlin/src/HAL/HAL_ESP32/HAL_SPI.cpp rename to Marlin/src/HAL/ESP32/HAL_SPI.cpp diff --git a/Marlin/src/HAL/HAL_ESP32/Servo.cpp b/Marlin/src/HAL/ESP32/Servo.cpp similarity index 100% rename from Marlin/src/HAL/HAL_ESP32/Servo.cpp rename to Marlin/src/HAL/ESP32/Servo.cpp diff --git a/Marlin/src/HAL/HAL_ESP32/Servo.h b/Marlin/src/HAL/ESP32/Servo.h similarity index 100% rename from Marlin/src/HAL/HAL_ESP32/Servo.h rename to Marlin/src/HAL/ESP32/Servo.h diff --git a/Marlin/src/HAL/HAL_ESP32/WebSocketSerial.cpp b/Marlin/src/HAL/ESP32/WebSocketSerial.cpp similarity index 100% rename from Marlin/src/HAL/HAL_ESP32/WebSocketSerial.cpp rename to Marlin/src/HAL/ESP32/WebSocketSerial.cpp diff --git a/Marlin/src/HAL/HAL_ESP32/WebSocketSerial.h b/Marlin/src/HAL/ESP32/WebSocketSerial.h similarity index 100% rename from Marlin/src/HAL/HAL_ESP32/WebSocketSerial.h rename to Marlin/src/HAL/ESP32/WebSocketSerial.h diff --git a/Marlin/src/HAL/HAL_ESP32/endstop_interrupts.h b/Marlin/src/HAL/ESP32/endstop_interrupts.h similarity index 100% rename from Marlin/src/HAL/HAL_ESP32/endstop_interrupts.h rename to Marlin/src/HAL/ESP32/endstop_interrupts.h diff --git a/Marlin/src/HAL/HAL_ESP32/fastio.h b/Marlin/src/HAL/ESP32/fastio.h similarity index 100% rename from Marlin/src/HAL/HAL_ESP32/fastio.h rename to Marlin/src/HAL/ESP32/fastio.h diff --git a/Marlin/src/HAL/HAL_ESP32/i2s.cpp b/Marlin/src/HAL/ESP32/i2s.cpp similarity index 100% rename from Marlin/src/HAL/HAL_ESP32/i2s.cpp rename to Marlin/src/HAL/ESP32/i2s.cpp diff --git a/Marlin/src/HAL/HAL_ESP32/i2s.h b/Marlin/src/HAL/ESP32/i2s.h similarity index 100% rename from Marlin/src/HAL/HAL_ESP32/i2s.h rename to Marlin/src/HAL/ESP32/i2s.h diff --git a/Marlin/src/HAL/HAL_ESP32/inc/Conditionals_LCD.h b/Marlin/src/HAL/ESP32/inc/Conditionals_LCD.h similarity index 100% rename from Marlin/src/HAL/HAL_ESP32/inc/Conditionals_LCD.h rename to Marlin/src/HAL/ESP32/inc/Conditionals_LCD.h diff --git a/Marlin/src/HAL/HAL_ESP32/inc/Conditionals_adv.h b/Marlin/src/HAL/ESP32/inc/Conditionals_adv.h similarity index 100% rename from Marlin/src/HAL/HAL_ESP32/inc/Conditionals_adv.h rename to Marlin/src/HAL/ESP32/inc/Conditionals_adv.h diff --git a/Marlin/src/HAL/HAL_DUE/inc/Conditionals_post.h b/Marlin/src/HAL/ESP32/inc/Conditionals_post.h similarity index 100% rename from Marlin/src/HAL/HAL_DUE/inc/Conditionals_post.h rename to Marlin/src/HAL/ESP32/inc/Conditionals_post.h diff --git a/Marlin/src/HAL/HAL_ESP32/inc/SanityCheck.h b/Marlin/src/HAL/ESP32/inc/SanityCheck.h similarity index 100% rename from Marlin/src/HAL/HAL_ESP32/inc/SanityCheck.h rename to Marlin/src/HAL/ESP32/inc/SanityCheck.h diff --git a/Marlin/src/HAL/HAL_ESP32/ota.cpp b/Marlin/src/HAL/ESP32/ota.cpp similarity index 100% rename from Marlin/src/HAL/HAL_ESP32/ota.cpp rename to Marlin/src/HAL/ESP32/ota.cpp diff --git a/Marlin/src/HAL/HAL_ESP32/ota.h b/Marlin/src/HAL/ESP32/ota.h similarity index 100% rename from Marlin/src/HAL/HAL_ESP32/ota.h rename to Marlin/src/HAL/ESP32/ota.h diff --git a/Marlin/src/HAL/HAL_ESP32/persistent_store_impl.cpp b/Marlin/src/HAL/ESP32/persistent_store_impl.cpp similarity index 100% rename from Marlin/src/HAL/HAL_ESP32/persistent_store_impl.cpp rename to Marlin/src/HAL/ESP32/persistent_store_impl.cpp diff --git a/Marlin/src/HAL/HAL_ESP32/servotimers.h b/Marlin/src/HAL/ESP32/servotimers.h similarity index 100% rename from Marlin/src/HAL/HAL_ESP32/servotimers.h rename to Marlin/src/HAL/ESP32/servotimers.h diff --git a/Marlin/src/HAL/HAL_ESP32/spi_pins.h b/Marlin/src/HAL/ESP32/spi_pins.h similarity index 100% rename from Marlin/src/HAL/HAL_ESP32/spi_pins.h rename to Marlin/src/HAL/ESP32/spi_pins.h diff --git a/Marlin/src/HAL/HAL_ESP32/spiffs.cpp b/Marlin/src/HAL/ESP32/spiffs.cpp similarity index 100% rename from Marlin/src/HAL/HAL_ESP32/spiffs.cpp rename to Marlin/src/HAL/ESP32/spiffs.cpp diff --git a/Marlin/src/HAL/HAL_ESP32/spiffs.h b/Marlin/src/HAL/ESP32/spiffs.h similarity index 100% rename from Marlin/src/HAL/HAL_ESP32/spiffs.h rename to Marlin/src/HAL/ESP32/spiffs.h diff --git a/Marlin/src/HAL/HAL_ESP32/timers.cpp b/Marlin/src/HAL/ESP32/timers.cpp similarity index 100% rename from Marlin/src/HAL/HAL_ESP32/timers.cpp rename to Marlin/src/HAL/ESP32/timers.cpp diff --git a/Marlin/src/HAL/HAL_ESP32/timers.h b/Marlin/src/HAL/ESP32/timers.h similarity index 100% rename from Marlin/src/HAL/HAL_ESP32/timers.h rename to Marlin/src/HAL/ESP32/timers.h diff --git a/Marlin/src/HAL/HAL_ESP32/watchdog.cpp b/Marlin/src/HAL/ESP32/watchdog.cpp similarity index 100% rename from Marlin/src/HAL/HAL_ESP32/watchdog.cpp rename to Marlin/src/HAL/ESP32/watchdog.cpp diff --git a/Marlin/src/HAL/HAL_ESP32/watchdog.h b/Marlin/src/HAL/ESP32/watchdog.h similarity index 100% rename from Marlin/src/HAL/HAL_ESP32/watchdog.h rename to Marlin/src/HAL/ESP32/watchdog.h diff --git a/Marlin/src/HAL/HAL_ESP32/web.cpp b/Marlin/src/HAL/ESP32/web.cpp similarity index 100% rename from Marlin/src/HAL/HAL_ESP32/web.cpp rename to Marlin/src/HAL/ESP32/web.cpp diff --git a/Marlin/src/HAL/HAL_ESP32/web.h b/Marlin/src/HAL/ESP32/web.h similarity index 100% rename from Marlin/src/HAL/HAL_ESP32/web.h rename to Marlin/src/HAL/ESP32/web.h diff --git a/Marlin/src/HAL/HAL_ESP32/wifi.cpp b/Marlin/src/HAL/ESP32/wifi.cpp similarity index 100% rename from Marlin/src/HAL/HAL_ESP32/wifi.cpp rename to Marlin/src/HAL/ESP32/wifi.cpp diff --git a/Marlin/src/HAL/HAL_ESP32/wifi.h b/Marlin/src/HAL/ESP32/wifi.h similarity index 100% rename from Marlin/src/HAL/HAL_ESP32/wifi.h rename to Marlin/src/HAL/ESP32/wifi.h diff --git a/Marlin/src/HAL/HAL_LPC1768/inc/SanityCheck.h b/Marlin/src/HAL/HAL_LPC1768/inc/SanityCheck.h deleted file mode 100644 index a1fa342040..0000000000 --- a/Marlin/src/HAL/HAL_LPC1768/inc/SanityCheck.h +++ /dev/null @@ -1,127 +0,0 @@ -/** - * Marlin 3D Printer Firmware - * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * - * Based on Sprinter and grbl. - * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm - * - * This program is free software: you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with this program. If not, see . - * - */ -#pragma once - -#if PIO_PLATFORM_VERSION < 1001 - #error "nxplpc-arduino-lpc176x package is out of date, Please update the PlatformIO platforms, frameworks and libraries. You may need to remove the platform and let it reinstall automatically." -#endif -#if PIO_FRAMEWORK_VERSION < 2002 - #error "framework-arduino-lpc176x package is out of date, Please update the PlatformIO platforms, frameworks and libraries." -#endif - -/** - * Detect an old pins file by checking for old ADC pins values. - */ -#define _OLD_TEMP_PIN(P) PIN_EXISTS(P) && _CAT(P,_PIN) <= 7 && _CAT(P,_PIN) != 2 && _CAT(P,_PIN) != 3 -#if _OLD_TEMP_PIN(TEMP_BED) - #error "TEMP_BED_PIN must be defined using the Pn_nn or Pn_nn_An format. (See the included pins files)." -#elif _OLD_TEMP_PIN(TEMP_0) - #error "TEMP_0_PIN must be defined using the Pn_nn or Pn_nn_An format. (See the included pins files)." -#elif _OLD_TEMP_PIN(TEMP_1) - #error "TEMP_1_PIN must be defined using the Pn_nn or Pn_nn_An format. (See the included pins files)." -#elif _OLD_TEMP_PIN(TEMP_2) - #error "TEMP_2_PIN must be defined using the Pn_nn or Pn_nn_An format. (See the included pins files)." -#elif _OLD_TEMP_PIN(TEMP_3) - #error "TEMP_3_PIN must be defined using the Pn_nn or Pn_nn_An format. (See the included pins files)." -#elif _OLD_TEMP_PIN(TEMP_4) - #error "TEMP_4_PIN must be defined using the Pn_nn or Pn_nn_An format. (See the included pins files)." -#elif _OLD_TEMP_PIN(TEMP_5) - #error "TEMP_5_PIN must be defined using the Pn_nn or Pn_nn_An format. (See the included pins files)." -#elif _OLD_TEMP_PIN(TEMP_6) - #error "TEMP_6_PIN must be defined using the Pn_nn or Pn_nn_An format. (See the included pins files)." -#elif _OLD_TEMP_PIN(TEMP_7) - #error "TEMP_7_PIN must be defined using the Pn_nn or Pn_nn_An format. (See the included pins files)." -#endif -#undef _OLD_TEMP_PIN - -/** - * Because PWM hardware channels all share the same frequency, along with the - * fallback software channels, FAST_PWM_FAN is incompatible with Servos. - */ -#if NUM_SERVOS > 0 && ENABLED(FAST_PWM_FAN) - #error "BLTOUCH and Servos are incompatible with FAST_PWM_FAN on LPC176x boards." -#endif - -/** - * Test LPC176x-specific configuration values for errors at compile-time. - */ - -//#if ENABLED(SPINDLE_LASER_PWM) && !(SPINDLE_LASER_PWM_PIN == 4 || SPINDLE_LASER_PWM_PIN == 6 || SPINDLE_LASER_PWM_PIN == 11) -// #error "SPINDLE_LASER_PWM_PIN must use SERVO0, SERVO1 or SERVO3 connector" -//#endif - -#if IS_RE_ARM_BOARD && ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) && HAS_DRIVER(TMC2130) && DISABLED(TMC_USE_SW_SPI) - #error "Re-ARM with REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER and TMC2130 require TMC_USE_SW_SPI" -#endif - -#if ENABLED(BAUD_RATE_GCODE) - #error "BAUD_RATE_GCODE is not yet supported on LPC176x." -#endif - -/** - * Flag any serial port conflicts - * - * Port | TX | RX | - * --- | --- | --- | - * Serial | P0_02 | P0_03 | - * Serial1 | P0_15 | P0_16 | - * Serial2 | P0_10 | P0_11 | - * Serial3 | P0_00 | P0_01 | - */ -#if (defined(SERIAL_PORT) && SERIAL_PORT == 0) || (defined(SERIAL_PORT_2) && SERIAL_PORT_2 == 0) || (defined(DGUS_SERIAL_PORT) && DGUS_SERIAL_PORT == 0) - #if X_CS_PIN == P0_02 || TMC_SW_MISO == P0_02 || (E_STEPPERS && E_MUX1_PIN == P0_02) \ - || Y_CS_PIN == P0_03 || TMC_SW_MOSI == P0_03 || (E_STEPPERS && E_MUX0_PIN == P0_03) - #error "Serial port assignment (0) conflicts with other pins!" - #endif -#endif - -#if SERIAL_PORT == 1 || SERIAL_PORT_2 == 1 || DGUS_SERIAL_PORT == 1 - #if TMC_SW_SCK == P0_15 - #error "Serial port assignment (1) conflicts with other pins!" - #elif HAS_SPI_LCD - #if BTN_EN2 == P0_15 || SCK_PIN == P0_15 || LCD_PINS_D4 == P0_15 || DOGLCD_SCK == P0_15 || LCD_RESET_PIN == P0_15 || LCD_PINS_RS == P0_15 || SHIFT_CLK == P0_15 \ - || BTN_EN1 == P0_16 || LCD_SDSS == P0_16 || LCD_PINS_RS == P0_16 || MISO_PIN == P0_16 || DOGLCD_A0 == P0_16 || SS_PIN == P0_16 || LCD_SDSS == P0_16 || DOGLCD_CS == P0_16 || LCD_RESET_PIN == P0_16 || LCD_BACKLIGHT_PIN == P0_16 - #error "Serial port assignment (1) conflicts with other pins!" - #endif - #endif -#endif - -#if SERIAL_PORT == 2 || SERIAL_PORT_2 == 2 || DGUS_SERIAL_PORT == 2 - #if Y_MIN_PIN == P0_10 || Z_MIN_PROBE_PIN == P0_10 \ - || X_ENABLE_PIN == P0_10 || Y_ENABLE_PIN == P0_10 || X2_ENABLE_PIN == P0_10 || Y2_ENABLE_PIN == P0_10 || Z2_ENABLE_PIN == P0_10 || Z3_ENABLE_PIN == P0_10 || Z4_ENABLE_PIN == P0_10 \ - || X2_CS_PIN == P0_10 || Y2_CS_PIN == P0_10 || Z2_CS_PIN == P0_10 || Z3_CS_PIN == P0_10 || Z4_CS_PIN == P0_10 \ - || X_DIR_PIN == P0_11 || Y_DIR_PIN == P0_11 || X2_DIR_PIN == P0_11 || Y2_DIR_PIN == P0_11 || Z2_DIR_PIN == P0_11 || Z3_DIR_PIN == P0_11 || Z4_DIR_PIN == P0_11 \ - || X2_STEP_PIN == P0_11 || Y2_STEP_PIN == P0_11 || Z2_STEP_PIN == P0_11 || Z3_STEP_PIN == P0_11 || Z4_STEP_PIN == P0_11 - #error "Serial port assignment (2) conflicts with other pins!" - #elif (E_STEPPERS > 1 && (E1_ENABLE_PIN == P0_10 || E1_CS_PIN == P0_10)) || (E_STEPPERS > 0 && (E0_DIR_PIN == P0_11 || E0_STEP_PIN == P0_11)) - #error "Serial port assignment (2) conflicts with other pins!" - #endif -#endif - -#if SERIAL_PORT == 3 || SERIAL_PORT_2 == 3 || DGUS_SERIAL_PORT == 3 - #if X_MIN_PIN == P0_00 || Y_SERIAL_TX_PIN == P0_00 || Y_SERIAL_RX_PIN == P0_00 \ - || X_MAX_PIN == P0_01 || X_SERIAL_TX_PIN == P0_01 || X_SERIAL_RX_PIN == P0_01 - #error "Serial port assignment (2) conflicts with other pins!" - #elif E_STEPPERS > 1 && (E1_DIR_PIN == P0_00 || E1_STEP_PIN == P0_01) - #error "Serial port assignment (2) conflicts with other pins!" - #endif -#endif diff --git a/Marlin/src/HAL/HAL_LINUX/HAL.cpp b/Marlin/src/HAL/LINUX/HAL.cpp similarity index 100% rename from Marlin/src/HAL/HAL_LINUX/HAL.cpp rename to Marlin/src/HAL/LINUX/HAL.cpp diff --git a/Marlin/src/HAL/HAL_LINUX/HAL.h b/Marlin/src/HAL/LINUX/HAL.h similarity index 100% rename from Marlin/src/HAL/HAL_LINUX/HAL.h rename to Marlin/src/HAL/LINUX/HAL.h diff --git a/Marlin/src/HAL/HAL_LINUX/arduino.cpp b/Marlin/src/HAL/LINUX/arduino.cpp similarity index 100% rename from Marlin/src/HAL/HAL_LINUX/arduino.cpp rename to Marlin/src/HAL/LINUX/arduino.cpp diff --git a/Marlin/src/HAL/HAL_LINUX/fastio.h b/Marlin/src/HAL/LINUX/fastio.h similarity index 100% rename from Marlin/src/HAL/HAL_LINUX/fastio.h rename to Marlin/src/HAL/LINUX/fastio.h diff --git a/Marlin/src/HAL/HAL_LINUX/hardware/Clock.cpp b/Marlin/src/HAL/LINUX/hardware/Clock.cpp similarity index 100% rename from Marlin/src/HAL/HAL_LINUX/hardware/Clock.cpp rename to Marlin/src/HAL/LINUX/hardware/Clock.cpp diff --git a/Marlin/src/HAL/HAL_LINUX/hardware/Clock.h b/Marlin/src/HAL/LINUX/hardware/Clock.h similarity index 100% rename from Marlin/src/HAL/HAL_LINUX/hardware/Clock.h rename to Marlin/src/HAL/LINUX/hardware/Clock.h diff --git a/Marlin/src/HAL/HAL_LINUX/hardware/Gpio.cpp b/Marlin/src/HAL/LINUX/hardware/Gpio.cpp similarity index 100% rename from Marlin/src/HAL/HAL_LINUX/hardware/Gpio.cpp rename to Marlin/src/HAL/LINUX/hardware/Gpio.cpp diff --git a/Marlin/src/HAL/HAL_LINUX/hardware/Gpio.h b/Marlin/src/HAL/LINUX/hardware/Gpio.h similarity index 100% rename from Marlin/src/HAL/HAL_LINUX/hardware/Gpio.h rename to Marlin/src/HAL/LINUX/hardware/Gpio.h diff --git a/Marlin/src/HAL/HAL_LINUX/hardware/Heater.cpp b/Marlin/src/HAL/LINUX/hardware/Heater.cpp similarity index 100% rename from Marlin/src/HAL/HAL_LINUX/hardware/Heater.cpp rename to Marlin/src/HAL/LINUX/hardware/Heater.cpp diff --git a/Marlin/src/HAL/HAL_LINUX/hardware/Heater.h b/Marlin/src/HAL/LINUX/hardware/Heater.h similarity index 100% rename from Marlin/src/HAL/HAL_LINUX/hardware/Heater.h rename to Marlin/src/HAL/LINUX/hardware/Heater.h diff --git a/Marlin/src/HAL/HAL_LINUX/hardware/IOLoggerCSV.cpp b/Marlin/src/HAL/LINUX/hardware/IOLoggerCSV.cpp similarity index 100% rename from Marlin/src/HAL/HAL_LINUX/hardware/IOLoggerCSV.cpp rename to Marlin/src/HAL/LINUX/hardware/IOLoggerCSV.cpp diff --git a/Marlin/src/HAL/HAL_LINUX/hardware/IOLoggerCSV.h b/Marlin/src/HAL/LINUX/hardware/IOLoggerCSV.h similarity index 100% rename from Marlin/src/HAL/HAL_LINUX/hardware/IOLoggerCSV.h rename to Marlin/src/HAL/LINUX/hardware/IOLoggerCSV.h diff --git a/Marlin/src/HAL/HAL_LINUX/hardware/LinearAxis.cpp b/Marlin/src/HAL/LINUX/hardware/LinearAxis.cpp similarity index 100% rename from Marlin/src/HAL/HAL_LINUX/hardware/LinearAxis.cpp rename to Marlin/src/HAL/LINUX/hardware/LinearAxis.cpp diff --git a/Marlin/src/HAL/HAL_LINUX/hardware/LinearAxis.h b/Marlin/src/HAL/LINUX/hardware/LinearAxis.h similarity index 100% rename from Marlin/src/HAL/HAL_LINUX/hardware/LinearAxis.h rename to Marlin/src/HAL/LINUX/hardware/LinearAxis.h diff --git a/Marlin/src/HAL/HAL_LINUX/hardware/Timer.cpp b/Marlin/src/HAL/LINUX/hardware/Timer.cpp similarity index 100% rename from Marlin/src/HAL/HAL_LINUX/hardware/Timer.cpp rename to Marlin/src/HAL/LINUX/hardware/Timer.cpp diff --git a/Marlin/src/HAL/HAL_LINUX/hardware/Timer.h b/Marlin/src/HAL/LINUX/hardware/Timer.h similarity index 100% rename from Marlin/src/HAL/HAL_LINUX/hardware/Timer.h rename to Marlin/src/HAL/LINUX/hardware/Timer.h diff --git a/Marlin/src/HAL/HAL_LINUX/inc/Conditionals_LCD.h b/Marlin/src/HAL/LINUX/inc/Conditionals_LCD.h similarity index 100% rename from Marlin/src/HAL/HAL_LINUX/inc/Conditionals_LCD.h rename to Marlin/src/HAL/LINUX/inc/Conditionals_LCD.h diff --git a/Marlin/src/HAL/HAL_LINUX/inc/Conditionals_adv.h b/Marlin/src/HAL/LINUX/inc/Conditionals_adv.h similarity index 100% rename from Marlin/src/HAL/HAL_LINUX/inc/Conditionals_adv.h rename to Marlin/src/HAL/LINUX/inc/Conditionals_adv.h diff --git a/Marlin/src/HAL/HAL_ESP32/inc/Conditionals_post.h b/Marlin/src/HAL/LINUX/inc/Conditionals_post.h similarity index 100% rename from Marlin/src/HAL/HAL_ESP32/inc/Conditionals_post.h rename to Marlin/src/HAL/LINUX/inc/Conditionals_post.h diff --git a/Marlin/src/HAL/HAL_LINUX/inc/SanityCheck.h b/Marlin/src/HAL/LINUX/inc/SanityCheck.h similarity index 100% rename from Marlin/src/HAL/HAL_LINUX/inc/SanityCheck.h rename to Marlin/src/HAL/LINUX/inc/SanityCheck.h diff --git a/Marlin/src/HAL/HAL_LINUX/include/Arduino.h b/Marlin/src/HAL/LINUX/include/Arduino.h similarity index 100% rename from Marlin/src/HAL/HAL_LINUX/include/Arduino.h rename to Marlin/src/HAL/LINUX/include/Arduino.h diff --git a/Marlin/src/HAL/HAL_LINUX/include/pinmapping.cpp b/Marlin/src/HAL/LINUX/include/pinmapping.cpp similarity index 100% rename from Marlin/src/HAL/HAL_LINUX/include/pinmapping.cpp rename to Marlin/src/HAL/LINUX/include/pinmapping.cpp diff --git a/Marlin/src/HAL/HAL_LINUX/include/pinmapping.h b/Marlin/src/HAL/LINUX/include/pinmapping.h similarity index 100% rename from Marlin/src/HAL/HAL_LINUX/include/pinmapping.h rename to Marlin/src/HAL/LINUX/include/pinmapping.h diff --git a/Marlin/src/HAL/HAL_LINUX/include/serial.h b/Marlin/src/HAL/LINUX/include/serial.h similarity index 99% rename from Marlin/src/HAL/HAL_LINUX/include/serial.h rename to Marlin/src/HAL/LINUX/include/serial.h index 1036d6539d..c881d5dbda 100644 --- a/Marlin/src/HAL/HAL_LINUX/include/serial.h +++ b/Marlin/src/HAL/LINUX/include/serial.h @@ -23,7 +23,7 @@ #include "../../../inc/MarlinConfigPre.h" #if ENABLED(EMERGENCY_PARSER) - #include "../../../feature/emergency_parser.h" + #include "../../../feature/e_parser.h" #endif #include diff --git a/Marlin/src/HAL/HAL_LINUX/main.cpp b/Marlin/src/HAL/LINUX/main.cpp similarity index 100% rename from Marlin/src/HAL/HAL_LINUX/main.cpp rename to Marlin/src/HAL/LINUX/main.cpp diff --git a/Marlin/src/HAL/HAL_LINUX/persistent_store_impl.cpp b/Marlin/src/HAL/LINUX/persistent_store_impl.cpp similarity index 100% rename from Marlin/src/HAL/HAL_LINUX/persistent_store_impl.cpp rename to Marlin/src/HAL/LINUX/persistent_store_impl.cpp diff --git a/Marlin/src/HAL/HAL_LINUX/pinsDebug.h b/Marlin/src/HAL/LINUX/pinsDebug.h similarity index 100% rename from Marlin/src/HAL/HAL_LINUX/pinsDebug.h rename to Marlin/src/HAL/LINUX/pinsDebug.h diff --git a/Marlin/src/HAL/HAL_LINUX/servo_private.h b/Marlin/src/HAL/LINUX/servo_private.h similarity index 100% rename from Marlin/src/HAL/HAL_LINUX/servo_private.h rename to Marlin/src/HAL/LINUX/servo_private.h diff --git a/Marlin/src/HAL/HAL_LINUX/spi_pins.h b/Marlin/src/HAL/LINUX/spi_pins.h similarity index 100% rename from Marlin/src/HAL/HAL_LINUX/spi_pins.h rename to Marlin/src/HAL/LINUX/spi_pins.h diff --git a/Marlin/src/HAL/HAL_LINUX/timers.cpp b/Marlin/src/HAL/LINUX/timers.cpp similarity index 100% rename from Marlin/src/HAL/HAL_LINUX/timers.cpp rename to Marlin/src/HAL/LINUX/timers.cpp diff --git a/Marlin/src/HAL/HAL_LINUX/timers.h b/Marlin/src/HAL/LINUX/timers.h similarity index 100% rename from Marlin/src/HAL/HAL_LINUX/timers.h rename to Marlin/src/HAL/LINUX/timers.h diff --git a/Marlin/src/HAL/HAL_LINUX/watchdog.cpp b/Marlin/src/HAL/LINUX/watchdog.cpp similarity index 100% rename from Marlin/src/HAL/HAL_LINUX/watchdog.cpp rename to Marlin/src/HAL/LINUX/watchdog.cpp diff --git a/Marlin/src/HAL/HAL_LINUX/watchdog.h b/Marlin/src/HAL/LINUX/watchdog.h similarity index 100% rename from Marlin/src/HAL/HAL_LINUX/watchdog.h rename to Marlin/src/HAL/LINUX/watchdog.h diff --git a/Marlin/src/HAL/HAL_LPC1768/DebugMonitor.cpp b/Marlin/src/HAL/LPC1768/DebugMonitor.cpp similarity index 100% rename from Marlin/src/HAL/HAL_LPC1768/DebugMonitor.cpp rename to Marlin/src/HAL/LPC1768/DebugMonitor.cpp diff --git a/Marlin/src/HAL/HAL_LPC1768/HAL.cpp b/Marlin/src/HAL/LPC1768/HAL.cpp similarity index 100% rename from Marlin/src/HAL/HAL_LPC1768/HAL.cpp rename to Marlin/src/HAL/LPC1768/HAL.cpp diff --git a/Marlin/src/HAL/HAL_LPC1768/HAL.h b/Marlin/src/HAL/LPC1768/HAL.h similarity index 100% rename from Marlin/src/HAL/HAL_LPC1768/HAL.h rename to Marlin/src/HAL/LPC1768/HAL.h diff --git a/Marlin/src/HAL/HAL_LPC1768/HAL_SPI.cpp b/Marlin/src/HAL/LPC1768/HAL_SPI.cpp similarity index 100% rename from Marlin/src/HAL/HAL_LPC1768/HAL_SPI.cpp rename to Marlin/src/HAL/LPC1768/HAL_SPI.cpp diff --git a/Marlin/src/HAL/HAL_LPC1768/MarlinSerial.cpp b/Marlin/src/HAL/LPC1768/MarlinSerial.cpp similarity index 100% rename from Marlin/src/HAL/HAL_LPC1768/MarlinSerial.cpp rename to Marlin/src/HAL/LPC1768/MarlinSerial.cpp diff --git a/Marlin/src/HAL/HAL_LPC1768/MarlinSerial.h b/Marlin/src/HAL/LPC1768/MarlinSerial.h similarity index 97% rename from Marlin/src/HAL/HAL_LPC1768/MarlinSerial.h rename to Marlin/src/HAL/LPC1768/MarlinSerial.h index cfddc28406..b6bbf8e453 100644 --- a/Marlin/src/HAL/HAL_LPC1768/MarlinSerial.h +++ b/Marlin/src/HAL/LPC1768/MarlinSerial.h @@ -26,7 +26,7 @@ #include "../../inc/MarlinConfigPre.h" #if ENABLED(EMERGENCY_PARSER) - #include "../../feature/emergency_parser.h" + #include "../../feature/e_parser.h" #endif #ifndef SERIAL_PORT diff --git a/Marlin/src/HAL/HAL_LPC1768/Servo.h b/Marlin/src/HAL/LPC1768/Servo.h similarity index 100% rename from Marlin/src/HAL/HAL_LPC1768/Servo.h rename to Marlin/src/HAL/LPC1768/Servo.h diff --git a/Marlin/src/HAL/HAL_LPC1768/endstop_interrupts.h b/Marlin/src/HAL/LPC1768/endstop_interrupts.h similarity index 100% rename from Marlin/src/HAL/HAL_LPC1768/endstop_interrupts.h rename to Marlin/src/HAL/LPC1768/endstop_interrupts.h diff --git a/Marlin/src/HAL/HAL_LPC1768/fast_pwm.cpp b/Marlin/src/HAL/LPC1768/fast_pwm.cpp similarity index 100% rename from Marlin/src/HAL/HAL_LPC1768/fast_pwm.cpp rename to Marlin/src/HAL/LPC1768/fast_pwm.cpp diff --git a/Marlin/src/HAL/HAL_LPC1768/fastio.h b/Marlin/src/HAL/LPC1768/fastio.h similarity index 100% rename from Marlin/src/HAL/HAL_LPC1768/fastio.h rename to Marlin/src/HAL/LPC1768/fastio.h diff --git a/Marlin/src/HAL/HAL_LPC1768/inc/Conditionals_LCD.h b/Marlin/src/HAL/LPC1768/inc/Conditionals_LCD.h similarity index 100% rename from Marlin/src/HAL/HAL_LPC1768/inc/Conditionals_LCD.h rename to Marlin/src/HAL/LPC1768/inc/Conditionals_LCD.h diff --git a/Marlin/src/HAL/HAL_LPC1768/inc/Conditionals_adv.h b/Marlin/src/HAL/LPC1768/inc/Conditionals_adv.h similarity index 100% rename from Marlin/src/HAL/HAL_LPC1768/inc/Conditionals_adv.h rename to Marlin/src/HAL/LPC1768/inc/Conditionals_adv.h diff --git a/Marlin/src/HAL/HAL_STM32F1/inc/Conditionals_post.h b/Marlin/src/HAL/LPC1768/inc/Conditionals_post.h similarity index 82% rename from Marlin/src/HAL/HAL_STM32F1/inc/Conditionals_post.h rename to Marlin/src/HAL/LPC1768/inc/Conditionals_post.h index 0285c52ee3..2637174543 100644 --- a/Marlin/src/HAL/HAL_STM32F1/inc/Conditionals_post.h +++ b/Marlin/src/HAL/LPC1768/inc/Conditionals_post.h @@ -20,3 +20,11 @@ * */ #pragma once + +#if ENABLED(EEPROM_SETTINGS) + #undef USE_REAL_EEPROM + #define USE_EMULATED_EEPROM 1 + #if DISABLED(FLASH_EEPROM_EMULATION) + #define SDCARD_EEPROM_EMULATION 1 + #endif +#endif diff --git a/Marlin/src/HAL/LPC1768/inc/SanityCheck.h b/Marlin/src/HAL/LPC1768/inc/SanityCheck.h new file mode 100644 index 0000000000..949c7f4899 --- /dev/null +++ b/Marlin/src/HAL/LPC1768/inc/SanityCheck.h @@ -0,0 +1,253 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +#if PIO_PLATFORM_VERSION < 1001 + #error "nxplpc-arduino-lpc176x package is out of date, Please update the PlatformIO platforms, frameworks and libraries. You may need to remove the platform and let it reinstall automatically." +#endif +#if PIO_FRAMEWORK_VERSION < 2002 + #error "framework-arduino-lpc176x package is out of date, Please update the PlatformIO platforms, frameworks and libraries." +#endif + +/** + * Detect an old pins file by checking for old ADC pins values. + */ +#define _OLD_TEMP_PIN(P) PIN_EXISTS(P) && _CAT(P,_PIN) <= 7 && _CAT(P,_PIN) != 2 && _CAT(P,_PIN) != 3 +#if _OLD_TEMP_PIN(TEMP_BED) + #error "TEMP_BED_PIN must be defined using the Pn_nn or Pn_nn_An format. (See the included pins files)." +#elif _OLD_TEMP_PIN(TEMP_0) + #error "TEMP_0_PIN must be defined using the Pn_nn or Pn_nn_An format. (See the included pins files)." +#elif _OLD_TEMP_PIN(TEMP_1) + #error "TEMP_1_PIN must be defined using the Pn_nn or Pn_nn_An format. (See the included pins files)." +#elif _OLD_TEMP_PIN(TEMP_2) + #error "TEMP_2_PIN must be defined using the Pn_nn or Pn_nn_An format. (See the included pins files)." +#elif _OLD_TEMP_PIN(TEMP_3) + #error "TEMP_3_PIN must be defined using the Pn_nn or Pn_nn_An format. (See the included pins files)." +#elif _OLD_TEMP_PIN(TEMP_4) + #error "TEMP_4_PIN must be defined using the Pn_nn or Pn_nn_An format. (See the included pins files)." +#elif _OLD_TEMP_PIN(TEMP_5) + #error "TEMP_5_PIN must be defined using the Pn_nn or Pn_nn_An format. (See the included pins files)." +#elif _OLD_TEMP_PIN(TEMP_6) + #error "TEMP_6_PIN must be defined using the Pn_nn or Pn_nn_An format. (See the included pins files)." +#elif _OLD_TEMP_PIN(TEMP_7) + #error "TEMP_7_PIN must be defined using the Pn_nn or Pn_nn_An format. (See the included pins files)." +#endif +#undef _OLD_TEMP_PIN + +/** + * Because PWM hardware channels all share the same frequency, along with the + * fallback software channels, FAST_PWM_FAN is incompatible with Servos. + */ +static_assert(!(NUM_SERVOS && ENABLED(FAST_PWM_FAN)), "BLTOUCH and Servos are incompatible with FAST_PWM_FAN on LPC176x boards."); + +/** + * Test LPC176x-specific configuration values for errors at compile-time. + */ + +//#if ENABLED(SPINDLE_LASER_PWM) && !(SPINDLE_LASER_PWM_PIN == 4 || SPINDLE_LASER_PWM_PIN == 6 || SPINDLE_LASER_PWM_PIN == 11) +// #error "SPINDLE_LASER_PWM_PIN must use SERVO0, SERVO1 or SERVO3 connector" +//#endif + +#if MB(RAMPS_14_RE_ARM_EFB, RAMPS_14_RE_ARM_EEB, RAMPS_14_RE_ARM_EFF, RAMPS_14_RE_ARM_EEF, RAMPS_14_RE_ARM_SF) + #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) && HAS_DRIVER(TMC2130) && DISABLED(TMC_USE_SW_SPI) + #error "Re-ARM with REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER and TMC2130 requires TMC_USE_SW_SPI." + #endif +#endif + +static_assert(DISABLED(BAUD_RATE_GCODE), "BAUD_RATE_GCODE is not yet supported on LPC176x."); + +/** + * Flag any serial port conflicts + * + * Port | TX | RX | + * --- | --- | --- | + * Serial | P0_02 | P0_03 | + * Serial1 | P0_15 | P0_16 | + * Serial2 | P0_10 | P0_11 | + * Serial3 | P0_00 | P0_01 | + */ +#if (defined(SERIAL_PORT) && SERIAL_PORT == 0) || (defined(SERIAL_PORT_2) && SERIAL_PORT_2 == 0) || (defined(DGUS_SERIAL_PORT) && DGUS_SERIAL_PORT == 0) + #define IS_TX0(P) (P == P0_02) + #define IS_RX0(P) (P == P0_03) + #if IS_TX0(TMC_SW_MISO) || IS_RX0(TMC_SW_MOSI) + #error "Serial port pins (0) conflict with Trinamic SPI pins!" + #elif ENABLED(MK2_MULTIPLEXER) && (IS_TX0(E_MUX1_PIN) || IS_RX0(E_MUX0_PIN)) + #error "Serial port pins (0) conflict with MK2 multiplexer pins!" + #elif (AXIS_HAS_SPI(X) && IS_TX0(X_CS_PIN)) || (AXIS_HAS_SPI(Y) && IS_RX0(Y_CS_PIN)) + #error "Serial port pins (0) conflict with X/Y axis SPI pins!" + #endif + #undef IS_TX0 + #undef IS_RX0 +#endif + +#if SERIAL_PORT == 1 || SERIAL_PORT_2 == 1 || DGUS_SERIAL_PORT == 1 + #define IS_TX1(P) (P == P0_15) + #define IS_RX1(P) (P == P0_16) + #if IS_TX1(TMC_SW_SCK) + #error "Serial port pins (1) conflict with other pins!" + #elif HAS_SPI_LCD + #if IS_TX1(BTN_EN2) || IS_RX1(BTN_EN1) + #error "Serial port pins (1) conflict with Encoder Buttons!" + #elif IS_TX1(SCK_PIN) || IS_TX1(LCD_PINS_D4) || IS_TX1(DOGLCD_SCK) || IS_TX1(LCD_RESET_PIN) || IS_TX1(LCD_PINS_RS) || IS_TX1(SHIFT_CLK) \ + || IS_RX1(LCD_SDSS) || IS_RX1(LCD_PINS_RS) || IS_RX1(MISO_PIN) || IS_RX1(DOGLCD_A0) || IS_RX1(SS_PIN) || IS_RX1(LCD_SDSS) || IS_RX1(DOGLCD_CS) || IS_RX1(LCD_RESET_PIN) || IS_RX1(LCD_BACKLIGHT_PIN) + #error "Serial port pins (1) conflict with LCD pins!" + #endif + #endif + #undef IS_TX1 + #undef IS_RX1 +#endif + +#if SERIAL_PORT == 2 || SERIAL_PORT_2 == 2 || DGUS_SERIAL_PORT == 2 + #define IS_TX2(P) (P == P0_10) + #define IS_RX2(P) (P == P0_11) + #if IS_TX2(X2_ENABLE_PIN) || IS_RX2(X2_DIR_PIN) || IS_RX2(X2_STEP_PIN) || (AXIS_HAS_SPI(X2) && IS_TX2(X2_CS_PIN)) + #error "Serial port pins (2) conflict with X2 pins!" + #elif IS_TX2(Y2_ENABLE_PIN) || IS_RX2(Y2_DIR_PIN) || IS_RX2(Y2_STEP_PIN) || (AXIS_HAS_SPI(Y2) && IS_TX2(Y2_CS_PIN)) + #error "Serial port pins (2) conflict with Y2 pins!" + #elif IS_TX2(Z2_ENABLE_PIN) || IS_RX2(Z2_DIR_PIN) || IS_RX2(Z2_STEP_PIN) || (AXIS_HAS_SPI(Z2) && IS_TX2(Z2_CS_PIN)) + #error "Serial port pins (2) conflict with Z2 pins!" + #elif IS_TX2(Z3_ENABLE_PIN) || IS_RX2(Z3_DIR_PIN) || IS_RX2(Z3_STEP_PIN) || (AXIS_HAS_SPI(Z3) && IS_TX2(Z3_CS_PIN)) + #error "Serial port pins (2) conflict with Z3 pins!" + #elif IS_TX2(Z4_ENABLE_PIN) || IS_RX2(Z4_DIR_PIN) || IS_RX2(Z4_STEP_PIN) || (AXIS_HAS_SPI(Z4) && IS_TX2(Z4_CS_PIN)) + #error "Serial port pins (2) conflict with Z4 pins!" + #elif IS_RX2(X_DIR_PIN) || IS_RX2(Y_DIR_PIN) + #error "Serial port pins (2) conflict with other pins!" + #elif Y_HOME_DIR < 0 && 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!" + #elif IS_TX2(X_ENABLE_PIN) || IS_RX2(X_DIR_PIN) || IS_TX2(Y_ENABLE_PIN) || IS_RX2(Y_DIR_PIN) + #error "Serial port pins (2) conflict with X/Y stepper pins!" + #elif EXTRUDERS > 1 && (IS_TX2(E1_ENABLE_PIN) || (AXIS_HAS_SPI(E1) && IS_TX2(E1_CS_PIN))) + #error "Serial port pins (2) conflict with E1 stepper pins!" + #elif EXTRUDERS && (IS_RX2(E0_DIR_PIN) || IS_RX2(E0_STEP_PIN)) + #error "Serial port pins (2) conflict with E stepper pins!" + #endif + #undef IS_TX2 + #undef IS_RX2 +#endif + +#if SERIAL_PORT == 3 || SERIAL_PORT_2 == 3 || DGUS_SERIAL_PORT == 3 + #define PIN_IS_TX3(P) (PIN_EXISTS(P) && P##_PIN == P0_00) + #define PIN_IS_RX3(P) (P##_PIN == P0_01) + #if PIN_IS_TX3(X_MIN) || PIN_IS_RX3(X_MAX) + #error "Serial port pins (3) conflict with X endstop pins!" + #elif PIN_IS_TX3(Y_SERIAL_TX) || PIN_IS_TX3(Y_SERIAL_RX) \ + || PIN_IS_RX3(X_SERIAL_TX) || PIN_IS_RX3(X_SERIAL_RX) + #error "Serial port pins (3) conflict with X/Y axis UART pins!" + #elif PIN_IS_TX3(X2_DIR) || PIN_IS_RX3(X2_STEP) + #error "Serial port pins (3) conflict with X2 pins!" + #elif PIN_IS_TX3(Y2_DIR) || PIN_IS_RX3(Y2_STEP) + #error "Serial port pins (3) conflict with Y2 pins!" + #elif PIN_IS_TX3(Z2_DIR) || PIN_IS_RX3(Z2_STEP) + #error "Serial port pins (3) conflict with Z2 pins!" + #elif PIN_IS_TX3(Z3_DIR) || PIN_IS_RX3(Z3_STEP) + #error "Serial port pins (3) conflict with Z3 pins!" + #elif PIN_IS_TX3(Z4_DIR) || PIN_IS_RX3(Z4_STEP) + #error "Serial port pins (3) conflict with Z4 pins!" + #elif EXTRUDERS > 1 && (PIN_IS_TX3(E1_DIR) || PIN_IS_RX3(E1_STEP)) + #error "Serial port pins (3) conflict with E1 pins!" + #endif + #undef PIN_IS_TX3 + #undef PIN_IS_RX3 +#endif + +// +// Flag any i2c pin conflicts +// +#if ANY(DIGIPOT_I2C, DIGIPOT_MCP4018, DAC_STEPPER_CURRENT, EXPERIMENTAL_I2CBUS, I2C_POSITION_ENCODERS, PCA9632, I2C_EEPROM) + #define USEDI2CDEV_M 1 // /Wire.cpp + + #if USEDI2CDEV_M == 0 // P0_27 [D57] (AUX-1) .......... P0_28 [D58] (AUX-1) + #define PIN_IS_SDA0(P) (P##_PIN == P0_27) + #define IS_SCL0(P) (P == P0_28) + #if ENABLED(SDSUPPORT) && PIN_IS_SDA0(SD_DETECT) + #error "SDA0 overlaps with SD_DETECT_PIN!" + #elif PIN_IS_SDA0(E0_AUTO_FAN) + #error "SDA0 overlaps with E0_AUTO_FAN_PIN!" + #elif PIN_IS_SDA0(BEEPER) + #error "SDA0 overlaps with BEEPER_PIN!" + #elif IS_SCL0(BTN_ENC) + #error "SCL0 overlaps with Encoder Button!" + #elif IS_SCL0(SS_PIN) + #error "SCL0 overlaps with SS_PIN!" + #elif IS_SCL0(LCD_SDSS) + #error "SCL0 overlaps with LCD_SDSS!" + #endif + #undef PIN_IS_SDA0 + #undef IS_SCL0 + #elif USEDI2CDEV_M == 1 // P0_00 [D20] (SCA) ............ P0_01 [D21] (SCL) + #define PIN_IS_SDA1(P) (PIN_EXISTS(P) && P##_PIN == P0_00) + #define PIN_IS_SCL1(P) (P##_PIN == P0_01) + #if PIN_IS_SDA1(X_MIN) || PIN_IS_SCL1(X_MAX) + #error "One or more i2c (1) pins overlaps with X endstop pins! Disable i2c peripherals." + #elif PIN_IS_SDA1(X2_DIR) || PIN_IS_SCL1(X2_STEP) + #error "One or more i2c (1) pins overlaps with X2 pins! Disable i2c peripherals." + #elif PIN_IS_SDA1(Y2_DIR) || PIN_IS_SCL1(Y2_STEP) + #error "One or more i2c (1) pins overlaps with Y2 pins! Disable i2c peripherals." + #elif PIN_IS_SDA1(Z2_DIR) || PIN_IS_SCL1(Z2_STEP) + #error "One or more i2c (1) pins overlaps with Z2 pins! Disable i2c peripherals." + #elif PIN_IS_SDA1(Z3_DIR) || PIN_IS_SCL1(Z3_STEP) + #error "One or more i2c (1) pins overlaps with Z3 pins! Disable i2c peripherals." + #elif PIN_IS_SDA1(Z4_DIR) || PIN_IS_SCL1(Z4_STEP) + #error "One or more i2c (1) pins overlaps with Z4 pins! Disable i2c peripherals." + #elif EXTRUDERS > 1 && (PIN_IS_SDA1(E1_DIR) || PIN_IS_SCL1(E1_STEP)) + #error "One or more i2c (1) pins overlaps with E1 pins! Disable i2c peripherals." + #endif + #undef PIN_IS_SDA1 + #undef PIN_IS_SCL1 + #elif USEDI2CDEV_M == 2 // P0_10 [D38] (X_ENABLE_PIN) ... P0_11 [D55] (X_DIR_PIN) + #define PIN_IS_SDA2(P) (P##_PIN == P0_10) + #define PIN_IS_SCL2(P) (P##_PIN == P0_11) + #if PIN_IS_SDA2(Y_STOP) + #error "i2c SDA2 overlaps with Y endstop pin!" + #elif HAS_CUSTOM_PROBE_PIN && PIN_IS_SDA2(Z_MIN_PROBE) + #error "i2c SDA2 overlaps with Z probe pin!" + #elif PIN_IS_SDA2(X_ENABLE) || PIN_IS_SDA2(Y_ENABLE) + #error "i2c SDA2 overlaps with X/Y ENABLE pin!" + #elif AXIS_HAS_SPI(X) && PIN_IS_SDA2(X_CS) + #error "i2c SDA2 overlaps with X CS pin!" + #elif PIN_IS_SDA2(X2_ENABLE) + #error "i2c SDA2 overlaps with X2 enable pin! Disable i2c peripherals." + #elif PIN_IS_SDA2(Y2_ENABLE) + #error "i2c SDA2 overlaps with Y2 enable pin! Disable i2c peripherals." + #elif PIN_IS_SDA2(Z2_ENABLE) + #error "i2c SDA2 overlaps with Z2 enable pin! Disable i2c peripherals." + #elif PIN_IS_SDA2(Z3_ENABLE) + #error "i2c SDA2 overlaps with Z3 enable pin! Disable i2c peripherals." + #elif PIN_IS_SDA2(Z4_ENABLE) + #error "i2c SDA2 overlaps with Z4 enable pin! Disable i2c peripherals." + #elif EXTRUDERS > 1 && PIN_IS_SDA2(E1_ENABLE) + #error "i2c SDA2 overlaps with E1 enable pin! Disable i2c peripherals." + #elif EXTRUDERS > 1 && AXIS_HAS_SPI(E1) && PIN_IS_SDA2(E1_CS) + #error "i2c SDA2 overlaps with E1 CS pin! Disable i2c peripherals." + #elif EXTRUDERS && (PIN_IS_SDA2(E0_STEP) || PIN_IS_SDA2(E0_DIR)) + #error "i2c SCL2 overlaps with E0 STEP/DIR pin! Disable i2c peripherals." + #elif PIN_IS_SDA2(X_DIR) || PIN_IS_SDA2(Y_DIR) + #error "One or more i2c pins overlaps with X/Y DIR pin! Disable i2c peripherals." + #endif + #undef PIN_IS_SDA2 + #undef PIN_IS_SCL2 + #endif + + #undef USEDI2CDEV_M +#endif diff --git a/Marlin/src/HAL/HAL_LPC1768/include/SPI.h b/Marlin/src/HAL/LPC1768/include/SPI.h similarity index 100% rename from Marlin/src/HAL/HAL_LPC1768/include/SPI.h rename to Marlin/src/HAL/LPC1768/include/SPI.h diff --git a/Marlin/src/HAL/HAL_LPC1768/include/digipot_mcp4451_I2C_routines.c b/Marlin/src/HAL/LPC1768/include/digipot_mcp4451_I2C_routines.c similarity index 100% rename from Marlin/src/HAL/HAL_LPC1768/include/digipot_mcp4451_I2C_routines.c rename to Marlin/src/HAL/LPC1768/include/digipot_mcp4451_I2C_routines.c diff --git a/Marlin/src/HAL/HAL_LPC1768/include/digipot_mcp4451_I2C_routines.h b/Marlin/src/HAL/LPC1768/include/digipot_mcp4451_I2C_routines.h similarity index 100% rename from Marlin/src/HAL/HAL_LPC1768/include/digipot_mcp4451_I2C_routines.h rename to Marlin/src/HAL/LPC1768/include/digipot_mcp4451_I2C_routines.h diff --git a/Marlin/src/HAL/HAL_LPC1768/include/i2c_util.c b/Marlin/src/HAL/LPC1768/include/i2c_util.c similarity index 100% rename from Marlin/src/HAL/HAL_LPC1768/include/i2c_util.c rename to Marlin/src/HAL/LPC1768/include/i2c_util.c diff --git a/Marlin/src/HAL/HAL_LPC1768/include/i2c_util.h b/Marlin/src/HAL/LPC1768/include/i2c_util.h similarity index 100% rename from Marlin/src/HAL/HAL_LPC1768/include/i2c_util.h rename to Marlin/src/HAL/LPC1768/include/i2c_util.h diff --git a/Marlin/src/HAL/HAL_LPC1768/main.cpp b/Marlin/src/HAL/LPC1768/main.cpp similarity index 98% rename from Marlin/src/HAL/HAL_LPC1768/main.cpp rename to Marlin/src/HAL/LPC1768/main.cpp index d7ba62fe5e..fb7394344e 100644 --- a/Marlin/src/HAL/HAL_LPC1768/main.cpp +++ b/Marlin/src/HAL/LPC1768/main.cpp @@ -37,6 +37,7 @@ extern "C" { #include "../../sd/cardreader.h" #include "../../inc/MarlinConfig.h" +#include "../../core/millis_t.h" #include "HAL.h" #include "timers.h" @@ -66,7 +67,7 @@ void HAL_init() { #endif // Flash status LED 3 times to indicate Marlin has started booting - for (uint8_t i = 0; i < 6; ++i) { + LOOP_L_N(i, 6) { TOGGLE(LED_PIN); delay(100); } diff --git a/Marlin/src/HAL/HAL_LPC1768/persistent_store_api.h b/Marlin/src/HAL/LPC1768/persistent_store_api.h similarity index 100% rename from Marlin/src/HAL/HAL_LPC1768/persistent_store_api.h rename to Marlin/src/HAL/LPC1768/persistent_store_api.h diff --git a/Marlin/src/HAL/HAL_LPC1768/persistent_store_flash.cpp b/Marlin/src/HAL/LPC1768/persistent_store_flash.cpp similarity index 98% rename from Marlin/src/HAL/HAL_LPC1768/persistent_store_flash.cpp rename to Marlin/src/HAL/LPC1768/persistent_store_flash.cpp index c7cad4d96c..5525f818a0 100644 --- a/Marlin/src/HAL/HAL_LPC1768/persistent_store_flash.cpp +++ b/Marlin/src/HAL/LPC1768/persistent_store_flash.cpp @@ -38,13 +38,11 @@ */ #include "../../inc/MarlinConfigPre.h" -#if ENABLED(EEPROM_SETTINGS) +#if ENABLED(FLASH_EEPROM_EMULATION) #include "persistent_store_api.h" #include "../../inc/MarlinConfig.h" -#if ENABLED(FLASH_EEPROM_EMULATION) - extern "C" { #include } @@ -128,5 +126,4 @@ bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t size_t PersistentStore::capacity() { return EEPROM_SIZE; } #endif // FLASH_EEPROM_EMULATION -#endif // EEPROM_SETTINGS #endif // TARGET_LPC1768 diff --git a/Marlin/src/HAL/HAL_LPC1768/persistent_store_sdcard.cpp b/Marlin/src/HAL/LPC1768/persistent_store_sdcard.cpp similarity index 97% rename from Marlin/src/HAL/HAL_LPC1768/persistent_store_sdcard.cpp rename to Marlin/src/HAL/LPC1768/persistent_store_sdcard.cpp index 50d52fb860..aa61938b02 100644 --- a/Marlin/src/HAL/HAL_LPC1768/persistent_store_sdcard.cpp +++ b/Marlin/src/HAL/LPC1768/persistent_store_sdcard.cpp @@ -22,14 +22,11 @@ */ #ifdef TARGET_LPC1768 -#include "../../inc/MarlinConfigPre.h" - -#if ENABLED(EEPROM_SETTINGS) - #include "../../inc/MarlinConfig.h" -#include "persistent_store_api.h" -#if DISABLED(FLASH_EEPROM_EMULATION) +#if ENABLED(SDCARD_EEPROM_EMULATION) + +#include "persistent_store_api.h" #include #include @@ -178,6 +175,5 @@ bool PersistentStore::read_data(int &pos, uint8_t* value, const size_t size, uin size_t PersistentStore::capacity() { return 4096; } // 4KiB of Emulated EEPROM -#endif // !FLASH_EEPROM_EMULATION -#endif // EEPROM_SETTINGS +#endif // SDCARD_EEPROM_EMULATION #endif // TARGET_LPC1768 diff --git a/Marlin/src/HAL/HAL_LPC1768/pinsDebug.h b/Marlin/src/HAL/LPC1768/pinsDebug.h similarity index 100% rename from Marlin/src/HAL/HAL_LPC1768/pinsDebug.h rename to Marlin/src/HAL/LPC1768/pinsDebug.h diff --git a/Marlin/src/HAL/HAL_LPC1768/spi_pins.h b/Marlin/src/HAL/LPC1768/spi_pins.h similarity index 100% rename from Marlin/src/HAL/HAL_LPC1768/spi_pins.h rename to Marlin/src/HAL/LPC1768/spi_pins.h diff --git a/Marlin/src/HAL/HAL_LPC1768/timers.cpp b/Marlin/src/HAL/LPC1768/timers.cpp similarity index 100% rename from Marlin/src/HAL/HAL_LPC1768/timers.cpp rename to Marlin/src/HAL/LPC1768/timers.cpp diff --git a/Marlin/src/HAL/HAL_LPC1768/timers.h b/Marlin/src/HAL/LPC1768/timers.h similarity index 100% rename from Marlin/src/HAL/HAL_LPC1768/timers.h rename to Marlin/src/HAL/LPC1768/timers.h diff --git a/Marlin/src/HAL/HAL_LPC1768/u8g/LCD_I2C_routines.cpp b/Marlin/src/HAL/LPC1768/u8g/LCD_I2C_routines.cpp similarity index 100% rename from Marlin/src/HAL/HAL_LPC1768/u8g/LCD_I2C_routines.cpp rename to Marlin/src/HAL/LPC1768/u8g/LCD_I2C_routines.cpp diff --git a/Marlin/src/HAL/HAL_LPC1768/u8g/LCD_I2C_routines.h b/Marlin/src/HAL/LPC1768/u8g/LCD_I2C_routines.h similarity index 100% rename from Marlin/src/HAL/HAL_LPC1768/u8g/LCD_I2C_routines.h rename to Marlin/src/HAL/LPC1768/u8g/LCD_I2C_routines.h diff --git a/Marlin/src/HAL/HAL_LPC1768/u8g/LCD_defines.h b/Marlin/src/HAL/LPC1768/u8g/LCD_defines.h similarity index 100% rename from Marlin/src/HAL/HAL_LPC1768/u8g/LCD_defines.h rename to Marlin/src/HAL/LPC1768/u8g/LCD_defines.h diff --git a/Marlin/src/HAL/HAL_LPC1768/u8g/LCD_delay.h b/Marlin/src/HAL/LPC1768/u8g/LCD_delay.h similarity index 100% rename from Marlin/src/HAL/HAL_LPC1768/u8g/LCD_delay.h rename to Marlin/src/HAL/LPC1768/u8g/LCD_delay.h diff --git a/Marlin/src/HAL/HAL_LPC1768/u8g/LCD_pin_routines.c b/Marlin/src/HAL/LPC1768/u8g/LCD_pin_routines.c similarity index 100% rename from Marlin/src/HAL/HAL_LPC1768/u8g/LCD_pin_routines.c rename to Marlin/src/HAL/LPC1768/u8g/LCD_pin_routines.c diff --git a/Marlin/src/HAL/HAL_LPC1768/u8g/LCD_pin_routines.h b/Marlin/src/HAL/LPC1768/u8g/LCD_pin_routines.h similarity index 100% rename from Marlin/src/HAL/HAL_LPC1768/u8g/LCD_pin_routines.h rename to Marlin/src/HAL/LPC1768/u8g/LCD_pin_routines.h diff --git a/Marlin/src/HAL/HAL_LPC1768/u8g/u8g_com_HAL_LPC1768_hw_spi.cpp b/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_hw_spi.cpp similarity index 100% rename from Marlin/src/HAL/HAL_LPC1768/u8g/u8g_com_HAL_LPC1768_hw_spi.cpp rename to Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_hw_spi.cpp diff --git a/Marlin/src/HAL/HAL_LPC1768/u8g/u8g_com_HAL_LPC1768_ssd_hw_i2c.cpp b/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_ssd_hw_i2c.cpp similarity index 100% rename from Marlin/src/HAL/HAL_LPC1768/u8g/u8g_com_HAL_LPC1768_ssd_hw_i2c.cpp rename to Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_ssd_hw_i2c.cpp diff --git a/Marlin/src/HAL/HAL_LPC1768/u8g/u8g_com_HAL_LPC1768_st7920_hw_spi.cpp b/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_st7920_hw_spi.cpp similarity index 100% rename from Marlin/src/HAL/HAL_LPC1768/u8g/u8g_com_HAL_LPC1768_st7920_hw_spi.cpp rename to Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_st7920_hw_spi.cpp diff --git a/Marlin/src/HAL/HAL_LPC1768/u8g/u8g_com_HAL_LPC1768_st7920_sw_spi.cpp b/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_st7920_sw_spi.cpp similarity index 100% rename from Marlin/src/HAL/HAL_LPC1768/u8g/u8g_com_HAL_LPC1768_st7920_sw_spi.cpp rename to Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_st7920_sw_spi.cpp diff --git a/Marlin/src/HAL/HAL_LPC1768/u8g/u8g_com_HAL_LPC1768_sw_spi.cpp b/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_sw_spi.cpp similarity index 94% rename from Marlin/src/HAL/HAL_LPC1768/u8g/u8g_com_HAL_LPC1768_sw_spi.cpp rename to Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_sw_spi.cpp index a98c5eea9c..6eac5daf24 100644 --- a/Marlin/src/HAL/HAL_LPC1768/u8g/u8g_com_HAL_LPC1768_sw_spi.cpp +++ b/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_sw_spi.cpp @@ -73,7 +73,7 @@ uint8_t swSpiTransfer_mode_0(uint8_t b, const uint8_t spi_speed, const pin_t sck_pin, const pin_t miso_pin, const pin_t mosi_pin ) { - for (uint8_t i = 0; i < 8; i++) { + LOOP_L_N(i, 8) { if (spi_speed == 0) { LPC176x::gpio_set(mosi_pin, !!(b & 0x80)); LPC176x::gpio_set(sck_pin, HIGH); @@ -83,16 +83,16 @@ uint8_t swSpiTransfer_mode_0(uint8_t b, const uint8_t spi_speed, const pin_t sck } else { const uint8_t state = (b & 0x80) ? HIGH : LOW; - for (uint8_t j = 0; j < spi_speed; j++) + LOOP_L_N(j, spi_speed) LPC176x::gpio_set(mosi_pin, state); - for (uint8_t j = 0; j < spi_speed + (miso_pin >= 0 ? 0 : 1); j++) + LOOP_L_N(j, spi_speed + (miso_pin >= 0 ? 0 : 1)) LPC176x::gpio_set(sck_pin, HIGH); b <<= 1; if (miso_pin >= 0 && LPC176x::gpio_get(miso_pin)) b |= 1; - for (uint8_t j = 0; j < spi_speed; j++) + LOOP_L_N(j, spi_speed) LPC176x::gpio_set(sck_pin, LOW); } } @@ -102,7 +102,7 @@ uint8_t swSpiTransfer_mode_0(uint8_t b, const uint8_t spi_speed, const pin_t sck uint8_t swSpiTransfer_mode_3(uint8_t b, const uint8_t spi_speed, const pin_t sck_pin, const pin_t miso_pin, const pin_t mosi_pin ) { - for (uint8_t i = 0; i < 8; i++) { + LOOP_L_N(i, 8) { const uint8_t state = (b & 0x80) ? HIGH : LOW; if (spi_speed == 0) { LPC176x::gpio_set(sck_pin, LOW); @@ -111,13 +111,13 @@ uint8_t swSpiTransfer_mode_3(uint8_t b, const uint8_t spi_speed, const pin_t sck LPC176x::gpio_set(sck_pin, HIGH); } else { - for (uint8_t j = 0; j < spi_speed + (miso_pin >= 0 ? 0 : 1); j++) + LOOP_L_N(j, spi_speed + (miso_pin >= 0 ? 0 : 1)) LPC176x::gpio_set(sck_pin, LOW); - for (uint8_t j = 0; j < spi_speed; j++) + LOOP_L_N(j, spi_speed) LPC176x::gpio_set(mosi_pin, state); - for (uint8_t j = 0; j < spi_speed; j++) + LOOP_L_N(j, spi_speed) LPC176x::gpio_set(sck_pin, HIGH); } b <<= 1; diff --git a/Marlin/src/HAL/HAL_LPC1768/upload_extra_script.py b/Marlin/src/HAL/LPC1768/upload_extra_script.py similarity index 100% rename from Marlin/src/HAL/HAL_LPC1768/upload_extra_script.py rename to Marlin/src/HAL/LPC1768/upload_extra_script.py diff --git a/Marlin/src/HAL/HAL_LPC1768/usb_serial.cpp b/Marlin/src/HAL/LPC1768/usb_serial.cpp similarity index 96% rename from Marlin/src/HAL/HAL_LPC1768/usb_serial.cpp rename to Marlin/src/HAL/LPC1768/usb_serial.cpp index 0af2d8347b..ddb31da20f 100644 --- a/Marlin/src/HAL/HAL_LPC1768/usb_serial.cpp +++ b/Marlin/src/HAL/LPC1768/usb_serial.cpp @@ -26,7 +26,7 @@ #if ENABLED(EMERGENCY_PARSER) -#include "../../feature/emergency_parser.h" +#include "../../feature/e_parser.h" EmergencyParser::State emergency_state; bool CDC_RecvCallback(const char buffer) { emergency_parser.update(emergency_state, buffer); diff --git a/Marlin/src/HAL/HAL_LPC1768/watchdog.cpp b/Marlin/src/HAL/LPC1768/watchdog.cpp similarity index 100% rename from Marlin/src/HAL/HAL_LPC1768/watchdog.cpp rename to Marlin/src/HAL/LPC1768/watchdog.cpp diff --git a/Marlin/src/HAL/HAL_LPC1768/watchdog.h b/Marlin/src/HAL/LPC1768/watchdog.h similarity index 100% rename from Marlin/src/HAL/HAL_LPC1768/watchdog.h rename to Marlin/src/HAL/LPC1768/watchdog.h diff --git a/Marlin/src/HAL/HAL_LPC1768/win_usb_driver/lpc176x_usb_driver.inf b/Marlin/src/HAL/LPC1768/win_usb_driver/lpc176x_usb_driver.inf similarity index 100% rename from Marlin/src/HAL/HAL_LPC1768/win_usb_driver/lpc176x_usb_driver.inf rename to Marlin/src/HAL/LPC1768/win_usb_driver/lpc176x_usb_driver.inf diff --git a/Marlin/src/HAL/HAL_SAMD51/HAL.cpp b/Marlin/src/HAL/SAMD51/HAL.cpp similarity index 98% rename from Marlin/src/HAL/HAL_SAMD51/HAL.cpp rename to Marlin/src/HAL/SAMD51/HAL.cpp index 4828c40ff7..b3a741fe13 100644 --- a/Marlin/src/HAL/HAL_SAMD51/HAL.cpp +++ b/Marlin/src/HAL/SAMD51/HAL.cpp @@ -478,10 +478,10 @@ void HAL_adc_init() { #if ADC_IS_REQUIRED memset(HAL_adc_results, 0xFF, sizeof(HAL_adc_results)); // Fill result with invalid values - for (uint8_t pi = 0; pi < COUNT(adc_pins); ++pi) + LOOP_L_N(pi, COUNT(adc_pins)) pinPeripheral(adc_pins[pi], PIO_ANALOG); - for (uint8_t ai = FIRST_ADC; ai <= LAST_ADC; ++ai) { + LOOP_S_LE_N(ai, FIRST_ADC, LAST_ADC) { Adc* adc = ((Adc*[])ADC_INSTS)[ai]; // ADC clock setup @@ -513,7 +513,7 @@ void HAL_adc_init() { void HAL_adc_start_conversion(const uint8_t adc_pin) { #if ADC_IS_REQUIRED - for (uint8_t pi = 0; pi < COUNT(adc_pins); ++pi) { + LOOP_L_N(pi, COUNT(adc_pins)) { if (adc_pin == adc_pins[pi]) { HAL_adc_result = HAL_adc_results[pi]; return; diff --git a/Marlin/src/HAL/HAL_SAMD51/HAL.h b/Marlin/src/HAL/SAMD51/HAL.h similarity index 100% rename from Marlin/src/HAL/HAL_SAMD51/HAL.h rename to Marlin/src/HAL/SAMD51/HAL.h diff --git a/Marlin/src/HAL/HAL_SAMD51/HAL_SPI.cpp b/Marlin/src/HAL/SAMD51/HAL_SPI.cpp similarity index 100% rename from Marlin/src/HAL/HAL_SAMD51/HAL_SPI.cpp rename to Marlin/src/HAL/SAMD51/HAL_SPI.cpp diff --git a/Marlin/src/HAL/HAL_SAMD51/MarlinSerial_AGCM4.cpp b/Marlin/src/HAL/SAMD51/MarlinSerial_AGCM4.cpp similarity index 100% rename from Marlin/src/HAL/HAL_SAMD51/MarlinSerial_AGCM4.cpp rename to Marlin/src/HAL/SAMD51/MarlinSerial_AGCM4.cpp diff --git a/Marlin/src/HAL/HAL_SAMD51/MarlinSerial_AGCM4.h b/Marlin/src/HAL/SAMD51/MarlinSerial_AGCM4.h similarity index 100% rename from Marlin/src/HAL/HAL_SAMD51/MarlinSerial_AGCM4.h rename to Marlin/src/HAL/SAMD51/MarlinSerial_AGCM4.h diff --git a/Marlin/src/HAL/HAL_SAMD51/SAMD51.h b/Marlin/src/HAL/SAMD51/SAMD51.h similarity index 100% rename from Marlin/src/HAL/HAL_SAMD51/SAMD51.h rename to Marlin/src/HAL/SAMD51/SAMD51.h diff --git a/Marlin/src/HAL/HAL_SAMD51/Servo.cpp b/Marlin/src/HAL/SAMD51/Servo.cpp similarity index 100% rename from Marlin/src/HAL/HAL_SAMD51/Servo.cpp rename to Marlin/src/HAL/SAMD51/Servo.cpp diff --git a/Marlin/src/HAL/HAL_SAMD51/ServoTimers.h b/Marlin/src/HAL/SAMD51/ServoTimers.h similarity index 100% rename from Marlin/src/HAL/HAL_SAMD51/ServoTimers.h rename to Marlin/src/HAL/SAMD51/ServoTimers.h diff --git a/Marlin/src/HAL/HAL_SAMD51/endstop_interrupts.h b/Marlin/src/HAL/SAMD51/endstop_interrupts.h similarity index 100% rename from Marlin/src/HAL/HAL_SAMD51/endstop_interrupts.h rename to Marlin/src/HAL/SAMD51/endstop_interrupts.h diff --git a/Marlin/src/HAL/HAL_SAMD51/fastio.h b/Marlin/src/HAL/SAMD51/fastio.h similarity index 99% rename from Marlin/src/HAL/HAL_SAMD51/fastio.h rename to Marlin/src/HAL/SAMD51/fastio.h index e00fa77a7c..f6a2675de0 100644 --- a/Marlin/src/HAL/HAL_SAMD51/fastio.h +++ b/Marlin/src/HAL/SAMD51/fastio.h @@ -37,7 +37,7 @@ /** * Magic I/O routines * - * Now you can simply SET_OUTPUT(STEP); WRITE(STEP, HIGH); WRITE(STEP, LOW); + * Now you can simply SET_OUTPUT(IO); WRITE(IO, HIGH); WRITE(IO, LOW); */ // Read a pin diff --git a/Marlin/src/HAL/HAL_SAMD51/inc/Conditionals_LCD.h b/Marlin/src/HAL/SAMD51/inc/Conditionals_LCD.h similarity index 100% rename from Marlin/src/HAL/HAL_SAMD51/inc/Conditionals_LCD.h rename to Marlin/src/HAL/SAMD51/inc/Conditionals_LCD.h diff --git a/Marlin/src/HAL/HAL_SAMD51/inc/Conditionals_adv.h b/Marlin/src/HAL/SAMD51/inc/Conditionals_adv.h similarity index 100% rename from Marlin/src/HAL/HAL_SAMD51/inc/Conditionals_adv.h rename to Marlin/src/HAL/SAMD51/inc/Conditionals_adv.h diff --git a/Marlin/src/HAL/HAL_STM32_F4_F7/inc/Conditionals_post.h b/Marlin/src/HAL/SAMD51/inc/Conditionals_post.h similarity index 86% rename from Marlin/src/HAL/HAL_STM32_F4_F7/inc/Conditionals_post.h rename to Marlin/src/HAL/SAMD51/inc/Conditionals_post.h index 0285c52ee3..223890d790 100644 --- a/Marlin/src/HAL/HAL_STM32_F4_F7/inc/Conditionals_post.h +++ b/Marlin/src/HAL/SAMD51/inc/Conditionals_post.h @@ -20,3 +20,9 @@ * */ #pragma once + +#if USE_EMULATED_EEPROM + #undef SRAM_EEPROM_EMULATION + #undef SDCARD_EEPROM_EMULATION + #define FLASH_EEPROM_EMULATION 1 +#endif diff --git a/Marlin/src/HAL/HAL_SAMD51/inc/SanityCheck.h b/Marlin/src/HAL/SAMD51/inc/SanityCheck.h similarity index 91% rename from Marlin/src/HAL/HAL_SAMD51/inc/SanityCheck.h rename to Marlin/src/HAL/SAMD51/inc/SanityCheck.h index ddea64f2d0..cc7a10e7a6 100644 --- a/Marlin/src/HAL/HAL_SAMD51/inc/SanityCheck.h +++ b/Marlin/src/HAL/SAMD51/inc/SanityCheck.h @@ -23,6 +23,10 @@ * Test SAMD51 specific configuration values for errors at compile-time. */ +#if ENABLED(FLASH_EEPROM_EMULATION) + #warning "Did you activate the SmartEEPROM? See https://github.com/GMagician/SAMD51-SmartEEprom-Manager/releases" +#endif + #if defined(ADAFRUIT_GRAND_CENTRAL_M4) && SD_CONNECTION_IS(CUSTOM_CABLE) #error "No custom SD drive cable defined for this board." #endif @@ -42,11 +46,3 @@ #if ENABLED(FAST_PWM_FAN) #error "FAST_PWM_FAN is not yet implemented for this platform." #endif - -#if ENABLED(EEPROM_SETTINGS) && NONE(SPI_EEPROM, I2C_EEPROM) - #warning "Did you activate the SmartEEPROM? See https://github.com/GMagician/SAMD51-SmartEEprom-Manager/releases" -#endif - -#if HAS_TMC_SW_SERIAL - #error "TMC220x Software Serial is not supported on this platform." -#endif diff --git a/Marlin/src/HAL/HAL_SAMD51/persistent_store_eeprom.cpp b/Marlin/src/HAL/SAMD51/persistent_store_eeprom.cpp similarity index 93% rename from Marlin/src/HAL/HAL_SAMD51/persistent_store_eeprom.cpp rename to Marlin/src/HAL/SAMD51/persistent_store_eeprom.cpp index c450599d7b..6b7326bb25 100644 --- a/Marlin/src/HAL/HAL_SAMD51/persistent_store_eeprom.cpp +++ b/Marlin/src/HAL/SAMD51/persistent_store_eeprom.cpp @@ -27,7 +27,7 @@ #include "../shared/persistent_store_api.h" -#if NONE(SPI_EEPROM, I2C_EEPROM) +#if ENABLED(FLASH_EEPROM_EMULATION) #define NVMCTRL_CMD(c) do{ \ SYNC(!NVMCTRL->STATUS.bit.READY); \ NVMCTRL->INTFLAG.bit.DONE = true; \ @@ -41,7 +41,7 @@ #endif bool PersistentStore::access_start() { - #if NONE(SPI_EEPROM, I2C_EEPROM) + #if ENABLED(FLASH_EEPROM_EMULATION) NVMCTRL->SEECFG.reg = NVMCTRL_SEECFG_WMODE_BUFFERED; // Buffered mode and segment reallocation active #endif @@ -49,7 +49,7 @@ bool PersistentStore::access_start() { } bool PersistentStore::access_finish() { - #if NONE(SPI_EEPROM, I2C_EEPROM) + #if ENABLED(FLASH_EEPROM_EMULATION) NVMCTRL_FLUSH(); if (!NVMCTRL->SEESTAT.bit.LOCK) NVMCTRL_CMD(NVMCTRL_CTRLB_CMD_LSEE); // Lock E2P data write access @@ -59,14 +59,20 @@ bool PersistentStore::access_finish() { } bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) { - #if NONE(SPI_EEPROM, I2C_EEPROM) + #if ENABLED(FLASH_EEPROM_EMULATION) if (NVMCTRL->SEESTAT.bit.RLOCK) NVMCTRL_CMD(NVMCTRL_CTRLB_CMD_USEE); // Unlock E2P data write access #endif while (size--) { const uint8_t v = *value; - #if ANY(SPI_EEPROM, I2C_EEPROM) + #if ENABLED(FLASH_EEPROM_EMULATION) + SYNC(NVMCTRL->SEESTAT.bit.BUSY); + if (NVMCTRL->INTFLAG.bit.SEESFULL) + NVMCTRL_FLUSH(); // Next write will trigger a sector reallocation. I need to flush 'pagebuffer' + ((volatile uint8_t *)SEEPROM_ADDR)[pos] = v; + SYNC(!NVMCTRL->INTFLAG.bit.SEEWRC); + #else uint8_t * const p = (uint8_t * const)pos; if (v != eeprom_read_byte(p)) { eeprom_write_byte(p, v); @@ -76,12 +82,6 @@ bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, ui return true; } } - #else - SYNC(NVMCTRL->SEESTAT.bit.BUSY); - if (NVMCTRL->INTFLAG.bit.SEESFULL) - NVMCTRL_FLUSH(); // Next write will trigger a sector reallocation. I need to flush 'pagebuffer' - ((volatile uint8_t *)SEEPROM_ADDR)[pos] = v; - SYNC(!NVMCTRL->INTFLAG.bit.SEEWRC); #endif crc16(crc, &v, 1); pos++; @@ -93,11 +93,11 @@ bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, ui bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t *crc, const bool writing/*=true*/) { while (size--) { uint8_t c; - #if ANY(SPI_EEPROM, I2C_EEPROM) - c = eeprom_read_byte((uint8_t*)pos); - #else + #if ENABLED(FLASH_EEPROM_EMULATION) SYNC(NVMCTRL->SEESTAT.bit.BUSY); c = ((volatile uint8_t *)SEEPROM_ADDR)[pos]; + #else + c = eeprom_read_byte((uint8_t*)pos); #endif if (writing) *value = c; crc16(crc, &c, 1); @@ -108,9 +108,7 @@ bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t } size_t PersistentStore::capacity() { - #if ANY(SPI_EEPROM, I2C_EEPROM) - return E2END + 1; - #else + #if ENABLED(FLASH_EEPROM_EMULATION) const uint8_t psz = NVMCTRL->SEESTAT.bit.PSZ, sblk = NVMCTRL->SEESTAT.bit.SBLK; @@ -121,6 +119,8 @@ size_t PersistentStore::capacity() { else if (sblk <= 4 || psz == 5) return 16384; else if (sblk >= 9 && psz == 7) return 65536; else return 32768; + #else + return E2END + 1; #endif } diff --git a/Marlin/src/HAL/HAL_SAMD51/pinsDebug.h b/Marlin/src/HAL/SAMD51/pinsDebug.h similarity index 100% rename from Marlin/src/HAL/HAL_SAMD51/pinsDebug.h rename to Marlin/src/HAL/SAMD51/pinsDebug.h diff --git a/Marlin/src/HAL/HAL_SAMD51/spi_pins.h b/Marlin/src/HAL/SAMD51/spi_pins.h similarity index 100% rename from Marlin/src/HAL/HAL_SAMD51/spi_pins.h rename to Marlin/src/HAL/SAMD51/spi_pins.h diff --git a/Marlin/src/HAL/HAL_SAMD51/timers.cpp b/Marlin/src/HAL/SAMD51/timers.cpp similarity index 96% rename from Marlin/src/HAL/HAL_SAMD51/timers.cpp rename to Marlin/src/HAL/SAMD51/timers.cpp index 99839cd48a..3eb021c25b 100644 --- a/Marlin/src/HAL/HAL_SAMD51/timers.cpp +++ b/Marlin/src/HAL/SAMD51/timers.cpp @@ -42,7 +42,7 @@ const tTimerConfig TimerConfig[NUM_HARDWARE_TIMERS+1] = { { {.pTc=TC1}, TC1_IRQn, TC_PRIORITY(1) }, // 1 - stepper (needed by 32 bit timers) { {.pTc=TC2}, TC2_IRQn, TC_PRIORITY(2) }, // 2 - tone (framework) { {.pTc=TC3}, TC3_IRQn, TC_PRIORITY(3) }, // 3 - servo - { {.pTc=TC4}, TC4_IRQn, TC_PRIORITY(4) }, + { {.pTc=TC4}, TC4_IRQn, TC_PRIORITY(4) }, // 4 - software serial { {.pTc=TC5}, TC5_IRQn, TC_PRIORITY(5) }, { {.pTc=TC6}, TC6_IRQn, TC_PRIORITY(6) }, { {.pTc=TC7}, TC7_IRQn, TC_PRIORITY(7) }, @@ -145,12 +145,12 @@ void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) { } void HAL_timer_enable_interrupt(const uint8_t timer_num) { - IRQn_Type irq = TimerConfig[timer_num].IRQ_Id; + const IRQn_Type irq = TimerConfig[timer_num].IRQ_Id; NVIC_EnableIRQ(irq); } void HAL_timer_disable_interrupt(const uint8_t timer_num) { - IRQn_Type irq = TimerConfig[timer_num].IRQ_Id; + const IRQn_Type irq = TimerConfig[timer_num].IRQ_Id; Disable_Irq(irq); } @@ -160,7 +160,7 @@ static bool NVIC_GetEnabledIRQ(IRQn_Type IRQn) { } bool HAL_timer_interrupt_enabled(const uint8_t timer_num) { - IRQn_Type irq = TimerConfig[timer_num].IRQ_Id; + const IRQn_Type irq = TimerConfig[timer_num].IRQ_Id; return NVIC_GetEnabledIRQ(irq); } diff --git a/Marlin/src/HAL/HAL_SAMD51/timers.h b/Marlin/src/HAL/SAMD51/timers.h similarity index 93% rename from Marlin/src/HAL/HAL_SAMD51/timers.h rename to Marlin/src/HAL/SAMD51/timers.h index 073239c431..4b21e47162 100644 --- a/Marlin/src/HAL/HAL_SAMD51/timers.h +++ b/Marlin/src/HAL/SAMD51/timers.h @@ -57,16 +57,16 @@ typedef uint32_t hal_timer_t; : (t == TEMP_TIMER_NUM) ? 6 \ : 7 -#define _TC_HANDLER(t) void TC##t##_Handler() -#define TC_HANDLER(t) _TC_HANDLER(t) -#define HAL_STEP_TIMER_ISR() TC_HANDLER(STEP_TIMER_NUM) +#define _TC_HANDLER(t) void TC##t##_Handler() +#define TC_HANDLER(t) _TC_HANDLER(t) +#define HAL_STEP_TIMER_ISR() TC_HANDLER(STEP_TIMER_NUM) #if STEP_TIMER_NUM != PULSE_TIMER_NUM - #define HAL_PULSE_TIMER_ISR() TC_HANDLER(PULSE_TIMER_NUM) + #define HAL_PULSE_TIMER_ISR() TC_HANDLER(PULSE_TIMER_NUM) #endif #if TEMP_TIMER_NUM == RTC_TIMER_NUM - #define HAL_TEMP_TIMER_ISR() void RTC_Handler() + #define HAL_TEMP_TIMER_ISR() void RTC_Handler() #else - #define HAL_TEMP_TIMER_ISR() TC_HANDLER(TEMP_TIMER_NUM) + #define HAL_TEMP_TIMER_ISR() TC_HANDLER(TEMP_TIMER_NUM) #endif // -------------------------------------------------------------------------- diff --git a/Marlin/src/HAL/HAL_SAMD51/watchdog.cpp b/Marlin/src/HAL/SAMD51/watchdog.cpp similarity index 100% rename from Marlin/src/HAL/HAL_SAMD51/watchdog.cpp rename to Marlin/src/HAL/SAMD51/watchdog.cpp diff --git a/Marlin/src/HAL/HAL_SAMD51/watchdog.h b/Marlin/src/HAL/SAMD51/watchdog.h similarity index 100% rename from Marlin/src/HAL/HAL_SAMD51/watchdog.h rename to Marlin/src/HAL/SAMD51/watchdog.h diff --git a/Marlin/src/HAL/HAL_STM32/HAL.cpp b/Marlin/src/HAL/STM32/HAL.cpp similarity index 100% rename from Marlin/src/HAL/HAL_STM32/HAL.cpp rename to Marlin/src/HAL/STM32/HAL.cpp diff --git a/Marlin/src/HAL/HAL_STM32/HAL.h b/Marlin/src/HAL/STM32/HAL.h similarity index 100% rename from Marlin/src/HAL/HAL_STM32/HAL.h rename to Marlin/src/HAL/STM32/HAL.h diff --git a/Marlin/src/HAL/HAL_STM32/HAL_SPI.cpp b/Marlin/src/HAL/STM32/HAL_SPI.cpp similarity index 100% rename from Marlin/src/HAL/HAL_STM32/HAL_SPI.cpp rename to Marlin/src/HAL/STM32/HAL_SPI.cpp diff --git a/Marlin/src/HAL/HAL_STM32/README.md b/Marlin/src/HAL/STM32/README.md similarity index 100% rename from Marlin/src/HAL/HAL_STM32/README.md rename to Marlin/src/HAL/STM32/README.md diff --git a/Marlin/src/HAL/HAL_STM32/Sd2Card_sdio_stm32duino.cpp b/Marlin/src/HAL/STM32/Sd2Card_sdio_stm32duino.cpp similarity index 100% rename from Marlin/src/HAL/HAL_STM32/Sd2Card_sdio_stm32duino.cpp rename to Marlin/src/HAL/STM32/Sd2Card_sdio_stm32duino.cpp diff --git a/Marlin/src/HAL/HAL_STM32/Servo.cpp b/Marlin/src/HAL/STM32/Servo.cpp similarity index 100% rename from Marlin/src/HAL/HAL_STM32/Servo.cpp rename to Marlin/src/HAL/STM32/Servo.cpp diff --git a/Marlin/src/HAL/HAL_STM32/Servo.h b/Marlin/src/HAL/STM32/Servo.h similarity index 97% rename from Marlin/src/HAL/HAL_STM32/Servo.h rename to Marlin/src/HAL/STM32/Servo.h index 1f841f8184..e8b3c4b100 100644 --- a/Marlin/src/HAL/HAL_STM32/Servo.h +++ b/Marlin/src/HAL/STM32/Servo.h @@ -24,6 +24,8 @@ #include +#include "../../core/millis_t.h" + // Inherit and expand on the official library class libServo : public Servo { public: diff --git a/Marlin/src/HAL/HAL_STM32/SoftwareSerial.cpp b/Marlin/src/HAL/STM32/SoftwareSerial.cpp similarity index 100% rename from Marlin/src/HAL/HAL_STM32/SoftwareSerial.cpp rename to Marlin/src/HAL/STM32/SoftwareSerial.cpp diff --git a/Marlin/src/HAL/HAL_STM32/SoftwareSerial.h b/Marlin/src/HAL/STM32/SoftwareSerial.h similarity index 100% rename from Marlin/src/HAL/HAL_STM32/SoftwareSerial.h rename to Marlin/src/HAL/STM32/SoftwareSerial.h diff --git a/Marlin/src/HAL/HAL_STM32/endstop_interrupts.h b/Marlin/src/HAL/STM32/endstop_interrupts.h similarity index 100% rename from Marlin/src/HAL/HAL_STM32/endstop_interrupts.h rename to Marlin/src/HAL/STM32/endstop_interrupts.h diff --git a/Marlin/src/HAL/HAL_STM32/fastio.cpp b/Marlin/src/HAL/STM32/fastio.cpp similarity index 95% rename from Marlin/src/HAL/HAL_STM32/fastio.cpp rename to Marlin/src/HAL/STM32/fastio.cpp index 4c8b63fa10..c51effaa04 100644 --- a/Marlin/src/HAL/HAL_STM32/fastio.cpp +++ b/Marlin/src/HAL/STM32/fastio.cpp @@ -27,7 +27,7 @@ GPIO_TypeDef* FastIOPortMap[LastPort + 1]; void FastIO_init() { - for (uint8_t i = 0; i < NUM_DIGITAL_PINS; i++) + LOOP_L_N(i, NUM_DIGITAL_PINS) FastIOPortMap[STM_PORT(digitalPin[i])] = get_GPIO_Port(STM_PORT(digitalPin[i])); } diff --git a/Marlin/src/HAL/HAL_STM32/fastio.h b/Marlin/src/HAL/STM32/fastio.h similarity index 98% rename from Marlin/src/HAL/HAL_STM32/fastio.h rename to Marlin/src/HAL/STM32/fastio.h index fa94d4703c..c17901fa99 100644 --- a/Marlin/src/HAL/HAL_STM32/fastio.h +++ b/Marlin/src/HAL/STM32/fastio.h @@ -55,7 +55,7 @@ void FastIO_init(); // Must be called before using fast io macros else FastIOPortMap[STM_PORT(digitalPin[IO])]->BRR = _BV32(STM_PIN(digitalPin[IO])) ; \ }while(0) #else - #define _WRITE(IO, V) (FastIOPortMap[STM_PORT(digitalPin[IO])]->BSRR = _BV32(STM_PIN(digitalPin[IO]) + (V ? 0 : 16))) + #define _WRITE(IO, V) (FastIOPortMap[STM_PORT(digitalPin[IO])]->BSRR = _BV32(STM_PIN(digitalPin[IO]) + ((V) ? 0 : 16))) #endif #define _READ(IO) bool(READ_BIT(FastIOPortMap[STM_PORT(digitalPin[IO])]->IDR, _BV32(STM_PIN(digitalPin[IO])))) diff --git a/Marlin/src/HAL/HAL_STM32/inc/Conditionals_LCD.h b/Marlin/src/HAL/STM32/inc/Conditionals_LCD.h similarity index 100% rename from Marlin/src/HAL/HAL_STM32/inc/Conditionals_LCD.h rename to Marlin/src/HAL/STM32/inc/Conditionals_LCD.h diff --git a/Marlin/src/HAL/HAL_STM32/inc/Conditionals_adv.h b/Marlin/src/HAL/STM32/inc/Conditionals_adv.h similarity index 100% rename from Marlin/src/HAL/HAL_STM32/inc/Conditionals_adv.h rename to Marlin/src/HAL/STM32/inc/Conditionals_adv.h diff --git a/Marlin/src/HAL/HAL_LINUX/inc/Conditionals_post.h b/Marlin/src/HAL/STM32/inc/Conditionals_post.h similarity index 100% rename from Marlin/src/HAL/HAL_LINUX/inc/Conditionals_post.h rename to Marlin/src/HAL/STM32/inc/Conditionals_post.h diff --git a/Marlin/src/HAL/HAL_STM32/inc/SanityCheck.h b/Marlin/src/HAL/STM32/inc/SanityCheck.h similarity index 100% rename from Marlin/src/HAL/HAL_STM32/inc/SanityCheck.h rename to Marlin/src/HAL/STM32/inc/SanityCheck.h diff --git a/Marlin/src/HAL/HAL_STM32/persistent_store_flash.cpp b/Marlin/src/HAL/STM32/persistent_store_flash.cpp similarity index 100% rename from Marlin/src/HAL/HAL_STM32/persistent_store_flash.cpp rename to Marlin/src/HAL/STM32/persistent_store_flash.cpp diff --git a/Marlin/src/HAL/HAL_STM32/persistent_store_impl.cpp b/Marlin/src/HAL/STM32/persistent_store_impl.cpp similarity index 90% rename from Marlin/src/HAL/HAL_STM32/persistent_store_impl.cpp rename to Marlin/src/HAL/STM32/persistent_store_impl.cpp index b4e58a795e..d9538741dd 100644 --- a/Marlin/src/HAL/HAL_STM32/persistent_store_impl.cpp +++ b/Marlin/src/HAL/STM32/persistent_store_impl.cpp @@ -24,7 +24,7 @@ #include "../../inc/MarlinConfig.h" -#if ENABLED(EEPROM_SETTINGS) && ANY(SRAM_EEPROM_EMULATION, SPI_EEPROM, I2C_EEPROM) +#if EITHER(USE_REAL_EEPROM, SRAM_EEPROM_EMULATION) #include "../shared/persistent_store_api.h" @@ -41,7 +41,7 @@ bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, ui uint8_t v = *value; // Save to either external EEPROM, program flash or Backup SRAM - #if EITHER(SPI_EEPROM, I2C_EEPROM) + #if USE_REAL_EEPROM // EEPROM has only ~100,000 write cycles, // so only write bytes that have changed! uint8_t * const p = (uint8_t * const)pos; @@ -68,7 +68,7 @@ bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t do { // Read from either external EEPROM, program flash or Backup SRAM const uint8_t c = ( - #if EITHER(SPI_EEPROM, I2C_EEPROM) + #if USE_REAL_EEPROM eeprom_read_byte((uint8_t*)pos) #else (*(__IO uint8_t *)(BKPSRAM_BASE + ((uint8_t*)pos))) @@ -85,13 +85,13 @@ bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t size_t PersistentStore::capacity() { return ( - #if ENABLED(SRAM_EEPROM_EMULATION) - 4096 // 4kB - #else + #if USE_REAL_EEPROM E2END + 1 + #else + 4096 // 4kB #endif ); } -#endif // EEPROM_SETTINGS && (SRAM_EEPROM_EMULATION || SPI_EEPROM || I2C_EEPROM) +#endif // USE_REAL_EEPROM || SRAM_EEPROM_EMULATION #endif // ARDUINO_ARCH_STM32 && !STM32GENERIC diff --git a/Marlin/src/HAL/HAL_STM32/persistent_store_sdcard.cpp b/Marlin/src/HAL/STM32/persistent_store_sdcard.cpp similarity index 95% rename from Marlin/src/HAL/HAL_STM32/persistent_store_sdcard.cpp rename to Marlin/src/HAL/STM32/persistent_store_sdcard.cpp index 2df90d2328..c5afc557e9 100644 --- a/Marlin/src/HAL/HAL_STM32/persistent_store_sdcard.cpp +++ b/Marlin/src/HAL/STM32/persistent_store_sdcard.cpp @@ -28,7 +28,7 @@ #include "../../inc/MarlinConfig.h" -#if ENABLED(EEPROM_SETTINGS) && NONE(FLASH_EEPROM_EMULATION, SRAM_EEPROM_EMULATION, SPI_EEPROM, I2C_EEPROM) +#if ENABLED(SDCARD_EEPROM_EMULATION) #include "../shared/persistent_store_api.h" @@ -99,5 +99,5 @@ bool PersistentStore::read_data(int &pos, uint8_t* value, const size_t size, uin size_t PersistentStore::capacity() { return HAL_EEPROM_SIZE; } -#endif // EEPROM_SETTINGS -#endif // STM32 +#endif // SDCARD_EEPROM_EMULATION +#endif // STM32 && !STM32GENERIC diff --git a/Marlin/src/HAL/HAL_STM32/pinsDebug.h b/Marlin/src/HAL/STM32/pinsDebug.h similarity index 100% rename from Marlin/src/HAL/HAL_STM32/pinsDebug.h rename to Marlin/src/HAL/STM32/pinsDebug.h diff --git a/Marlin/src/HAL/HAL_STM32/pinsDebug_STM32GENERIC.h b/Marlin/src/HAL/STM32/pinsDebug_STM32GENERIC.h similarity index 98% rename from Marlin/src/HAL/HAL_STM32/pinsDebug_STM32GENERIC.h rename to Marlin/src/HAL/STM32/pinsDebug_STM32GENERIC.h index 43f430a48f..e3d28aed07 100644 --- a/Marlin/src/HAL/HAL_STM32/pinsDebug_STM32GENERIC.h +++ b/Marlin/src/HAL/STM32/pinsDebug_STM32GENERIC.h @@ -29,9 +29,9 @@ #ifdef BOARD_NR_GPIO_PINS // Only in STM32GENERIC (Maple) #ifdef __STM32F1__ - #include "../HAL_STM32F1/fastio.h" + #include "../STM32F1/fastio.h" #elif defined(STM32F4) || defined(STM32F7) - #include "../HAL_STM32_F4_F7/fastio.h" + #include "../STM32_F4_F7/fastio.h" #else #include "fastio.h" #endif diff --git a/Marlin/src/HAL/HAL_STM32/pinsDebug_STM32duino.h b/Marlin/src/HAL/STM32/pinsDebug_STM32duino.h similarity index 100% rename from Marlin/src/HAL/HAL_STM32/pinsDebug_STM32duino.h rename to Marlin/src/HAL/STM32/pinsDebug_STM32duino.h diff --git a/Marlin/src/HAL/HAL_STM32/pins_Xref.h b/Marlin/src/HAL/STM32/pins_Xref.h similarity index 100% rename from Marlin/src/HAL/HAL_STM32/pins_Xref.h rename to Marlin/src/HAL/STM32/pins_Xref.h diff --git a/Marlin/src/HAL/HAL_STM32/spi_pins.h b/Marlin/src/HAL/STM32/spi_pins.h similarity index 100% rename from Marlin/src/HAL/HAL_STM32/spi_pins.h rename to Marlin/src/HAL/STM32/spi_pins.h diff --git a/Marlin/src/HAL/HAL_STM32/timers.cpp b/Marlin/src/HAL/STM32/timers.cpp similarity index 100% rename from Marlin/src/HAL/HAL_STM32/timers.cpp rename to Marlin/src/HAL/STM32/timers.cpp diff --git a/Marlin/src/HAL/HAL_STM32/timers.h b/Marlin/src/HAL/STM32/timers.h similarity index 100% rename from Marlin/src/HAL/HAL_STM32/timers.h rename to Marlin/src/HAL/STM32/timers.h diff --git a/Marlin/src/HAL/HAL_STM32/watchdog.cpp b/Marlin/src/HAL/STM32/watchdog.cpp similarity index 100% rename from Marlin/src/HAL/HAL_STM32/watchdog.cpp rename to Marlin/src/HAL/STM32/watchdog.cpp diff --git a/Marlin/src/HAL/HAL_STM32/watchdog.h b/Marlin/src/HAL/STM32/watchdog.h similarity index 100% rename from Marlin/src/HAL/HAL_STM32/watchdog.h rename to Marlin/src/HAL/STM32/watchdog.h diff --git a/Marlin/src/HAL/HAL_STM32F1/HAL.cpp b/Marlin/src/HAL/STM32F1/HAL.cpp similarity index 100% rename from Marlin/src/HAL/HAL_STM32F1/HAL.cpp rename to Marlin/src/HAL/STM32F1/HAL.cpp diff --git a/Marlin/src/HAL/HAL_STM32F1/HAL.h b/Marlin/src/HAL/STM32F1/HAL.h similarity index 100% rename from Marlin/src/HAL/HAL_STM32F1/HAL.h rename to Marlin/src/HAL/STM32F1/HAL.h diff --git a/Marlin/src/HAL/HAL_STM32F1/HAL_SPI.cpp b/Marlin/src/HAL/STM32F1/HAL_SPI.cpp similarity index 100% rename from Marlin/src/HAL/HAL_STM32F1/HAL_SPI.cpp rename to Marlin/src/HAL/STM32F1/HAL_SPI.cpp diff --git a/Marlin/src/HAL/HAL_STM32F1/README.md b/Marlin/src/HAL/STM32F1/README.md similarity index 100% rename from Marlin/src/HAL/HAL_STM32F1/README.md rename to Marlin/src/HAL/STM32F1/README.md diff --git a/Marlin/src/HAL/HAL_STM32F1/SPI.cpp b/Marlin/src/HAL/STM32F1/SPI.cpp similarity index 100% rename from Marlin/src/HAL/HAL_STM32F1/SPI.cpp rename to Marlin/src/HAL/STM32F1/SPI.cpp diff --git a/Marlin/src/HAL/HAL_STM32F1/SPI.h b/Marlin/src/HAL/STM32F1/SPI.h similarity index 100% rename from Marlin/src/HAL/HAL_STM32F1/SPI.h rename to Marlin/src/HAL/STM32F1/SPI.h diff --git a/Marlin/src/HAL/HAL_STM32F1/Servo.cpp b/Marlin/src/HAL/STM32F1/Servo.cpp similarity index 100% rename from Marlin/src/HAL/HAL_STM32F1/Servo.cpp rename to Marlin/src/HAL/STM32F1/Servo.cpp diff --git a/Marlin/src/HAL/HAL_STM32F1/Servo.h b/Marlin/src/HAL/STM32F1/Servo.h similarity index 100% rename from Marlin/src/HAL/HAL_STM32F1/Servo.h rename to Marlin/src/HAL/STM32F1/Servo.h diff --git a/Marlin/src/HAL/HAL_STM32F1/SoftwareSerial.cpp b/Marlin/src/HAL/STM32F1/SoftwareSerial.cpp similarity index 100% rename from Marlin/src/HAL/HAL_STM32F1/SoftwareSerial.cpp rename to Marlin/src/HAL/STM32F1/SoftwareSerial.cpp diff --git a/Marlin/src/HAL/HAL_STM32F1/SoftwareSerial.h b/Marlin/src/HAL/STM32F1/SoftwareSerial.h similarity index 100% rename from Marlin/src/HAL/HAL_STM32F1/SoftwareSerial.h rename to Marlin/src/HAL/STM32F1/SoftwareSerial.h diff --git a/Marlin/src/HAL/HAL_STM32F1/build_flags.py b/Marlin/src/HAL/STM32F1/build_flags.py similarity index 95% rename from Marlin/src/HAL/HAL_STM32F1/build_flags.py rename to Marlin/src/HAL/STM32F1/build_flags.py index 6310740fe0..98c871a1d8 100755 --- a/Marlin/src/HAL/HAL_STM32F1/build_flags.py +++ b/Marlin/src/HAL/STM32F1/build_flags.py @@ -15,7 +15,7 @@ if __name__ == "__main__": "--specs=nano.specs", "--specs=nosys.specs", - "-IMarlin/src/HAL/HAL_STM32F1", + "-IMarlin/src/HAL/STM32F1", "-MMD", "-MP", diff --git a/Marlin/src/HAL/HAL_STM32F1/dogm/u8g_com_stm32duino_fsmc.cpp b/Marlin/src/HAL/STM32F1/dogm/u8g_com_stm32duino_fsmc.cpp similarity index 100% rename from Marlin/src/HAL/HAL_STM32F1/dogm/u8g_com_stm32duino_fsmc.cpp rename to Marlin/src/HAL/STM32F1/dogm/u8g_com_stm32duino_fsmc.cpp diff --git a/Marlin/src/HAL/HAL_STM32F1/dogm/u8g_com_stm32duino_swspi.cpp b/Marlin/src/HAL/STM32F1/dogm/u8g_com_stm32duino_swspi.cpp similarity index 91% rename from Marlin/src/HAL/HAL_STM32F1/dogm/u8g_com_stm32duino_swspi.cpp rename to Marlin/src/HAL/STM32F1/dogm/u8g_com_stm32duino_swspi.cpp index 8cf9099c81..2e9d11f97e 100644 --- a/Marlin/src/HAL/HAL_STM32F1/dogm/u8g_com_stm32duino_swspi.cpp +++ b/Marlin/src/HAL/STM32F1/dogm/u8g_com_stm32duino_swspi.cpp @@ -32,7 +32,7 @@ static uint8_t SPI_speed = SPI_SPEED; static inline uint8_t swSpiTransfer_mode_0(uint8_t b, const uint8_t spi_speed, const pin_t miso_pin=-1) { - for (uint8_t i = 0; i < 8; i++) { + LOOP_L_N(i, 8) { if (spi_speed == 0) { WRITE(DOGLCD_MOSI, !!(b & 0x80)); WRITE(DOGLCD_SCK, HIGH); @@ -42,16 +42,16 @@ static inline uint8_t swSpiTransfer_mode_0(uint8_t b, const uint8_t spi_speed, c } else { const uint8_t state = (b & 0x80) ? HIGH : LOW; - for (uint8_t j = 0; j < spi_speed; j++) + LOOP_L_N(j, spi_speed) WRITE(DOGLCD_MOSI, state); - for (uint8_t j = 0; j < spi_speed + (miso_pin >= 0 ? 0 : 1); j++) + LOOP_L_N(j, spi_speed + (miso_pin >= 0 ? 0 : 1)) WRITE(DOGLCD_SCK, HIGH); b <<= 1; if (miso_pin >= 0 && READ(miso_pin)) b |= 1; - for (uint8_t j = 0; j < spi_speed; j++) + LOOP_L_N(j, spi_speed) WRITE(DOGLCD_SCK, LOW); } } @@ -59,7 +59,7 @@ static inline uint8_t swSpiTransfer_mode_0(uint8_t b, const uint8_t spi_speed, c } static inline uint8_t swSpiTransfer_mode_3(uint8_t b, const uint8_t spi_speed, const pin_t miso_pin=-1) { - for (uint8_t i = 0; i < 8; i++) { + LOOP_L_N(i, 8) { const uint8_t state = (b & 0x80) ? HIGH : LOW; if (spi_speed == 0) { WRITE(DOGLCD_SCK, LOW); @@ -68,13 +68,13 @@ static inline uint8_t swSpiTransfer_mode_3(uint8_t b, const uint8_t spi_speed, c WRITE(DOGLCD_SCK, HIGH); } else { - for (uint8_t j = 0; j < spi_speed + (miso_pin >= 0 ? 0 : 1); j++) + LOOP_L_N(j, spi_speed + (miso_pin >= 0 ? 0 : 1)) WRITE(DOGLCD_SCK, LOW); - for (uint8_t j = 0; j < spi_speed; j++) + LOOP_L_N(j, spi_speed) WRITE(DOGLCD_MOSI, state); - for (uint8_t j = 0; j < spi_speed; j++) + LOOP_L_N(j, spi_speed) WRITE(DOGLCD_SCK, HIGH); } b <<= 1; diff --git a/Marlin/src/HAL/HAL_STM32F1/endstop_interrupts.h b/Marlin/src/HAL/STM32F1/endstop_interrupts.h similarity index 100% rename from Marlin/src/HAL/HAL_STM32F1/endstop_interrupts.h rename to Marlin/src/HAL/STM32F1/endstop_interrupts.h diff --git a/Marlin/src/HAL/HAL_STM32F1/fastio.h b/Marlin/src/HAL/STM32F1/fastio.h similarity index 100% rename from Marlin/src/HAL/HAL_STM32F1/fastio.h rename to Marlin/src/HAL/STM32F1/fastio.h diff --git a/Marlin/src/HAL/HAL_STM32F1/inc/Conditionals_LCD.h b/Marlin/src/HAL/STM32F1/inc/Conditionals_LCD.h similarity index 100% rename from Marlin/src/HAL/HAL_STM32F1/inc/Conditionals_LCD.h rename to Marlin/src/HAL/STM32F1/inc/Conditionals_LCD.h diff --git a/Marlin/src/HAL/HAL_STM32F1/inc/Conditionals_adv.h b/Marlin/src/HAL/STM32F1/inc/Conditionals_adv.h similarity index 100% rename from Marlin/src/HAL/HAL_STM32F1/inc/Conditionals_adv.h rename to Marlin/src/HAL/STM32F1/inc/Conditionals_adv.h diff --git a/Marlin/src/HAL/HAL_LPC1768/inc/Conditionals_post.h b/Marlin/src/HAL/STM32F1/inc/Conditionals_post.h similarity index 100% rename from Marlin/src/HAL/HAL_LPC1768/inc/Conditionals_post.h rename to Marlin/src/HAL/STM32F1/inc/Conditionals_post.h diff --git a/Marlin/src/HAL/HAL_STM32F1/inc/SanityCheck.h b/Marlin/src/HAL/STM32F1/inc/SanityCheck.h similarity index 100% rename from Marlin/src/HAL/HAL_STM32F1/inc/SanityCheck.h rename to Marlin/src/HAL/STM32F1/inc/SanityCheck.h diff --git a/Marlin/src/HAL/HAL_STM32F1/maple_win_usb_driver/maple_serial.inf b/Marlin/src/HAL/STM32F1/maple_win_usb_driver/maple_serial.inf similarity index 100% rename from Marlin/src/HAL/HAL_STM32F1/maple_win_usb_driver/maple_serial.inf rename to Marlin/src/HAL/STM32F1/maple_win_usb_driver/maple_serial.inf diff --git a/Marlin/src/HAL/HAL_STM32F1/msc_sd.cpp b/Marlin/src/HAL/STM32F1/msc_sd.cpp similarity index 100% rename from Marlin/src/HAL/HAL_STM32F1/msc_sd.cpp rename to Marlin/src/HAL/STM32F1/msc_sd.cpp diff --git a/Marlin/src/HAL/HAL_STM32F1/msc_sd.h b/Marlin/src/HAL/STM32F1/msc_sd.h similarity index 100% rename from Marlin/src/HAL/HAL_STM32F1/msc_sd.h rename to Marlin/src/HAL/STM32F1/msc_sd.h diff --git a/Marlin/src/HAL/HAL_STM32F1/onboard_sd.cpp b/Marlin/src/HAL/STM32F1/onboard_sd.cpp similarity index 100% rename from Marlin/src/HAL/HAL_STM32F1/onboard_sd.cpp rename to Marlin/src/HAL/STM32F1/onboard_sd.cpp diff --git a/Marlin/src/HAL/HAL_STM32F1/onboard_sd.h b/Marlin/src/HAL/STM32F1/onboard_sd.h similarity index 100% rename from Marlin/src/HAL/HAL_STM32F1/onboard_sd.h rename to Marlin/src/HAL/STM32F1/onboard_sd.h diff --git a/Marlin/src/HAL/HAL_STM32F1/persistent_store_eeprom.cpp b/Marlin/src/HAL/STM32F1/persistent_store_eeprom.cpp similarity index 94% rename from Marlin/src/HAL/HAL_STM32F1/persistent_store_eeprom.cpp rename to Marlin/src/HAL/STM32F1/persistent_store_eeprom.cpp index f2a1cb031a..1b3714c56d 100644 --- a/Marlin/src/HAL/HAL_STM32F1/persistent_store_eeprom.cpp +++ b/Marlin/src/HAL/STM32F1/persistent_store_eeprom.cpp @@ -22,7 +22,7 @@ #include "../../inc/MarlinConfig.h" -#if ENABLED(EEPROM_SETTINGS) && EITHER(SPI_EEPROM, I2C_EEPROM) +#if USE_REAL_EEPROM #include "../shared/persistent_store_api.h" @@ -73,5 +73,5 @@ bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t size_t PersistentStore::capacity() { return E2END + 1; } -#endif // EEPROM_SETTINGS && EITHER(SPI_EEPROM, I2C_EEPROM) +#endif // USE_REAL_EEPROM #endif // __STM32F1__ diff --git a/Marlin/src/HAL/HAL_STM32F1/persistent_store_flash.cpp b/Marlin/src/HAL/STM32F1/persistent_store_flash.cpp similarity index 100% rename from Marlin/src/HAL/HAL_STM32F1/persistent_store_flash.cpp rename to Marlin/src/HAL/STM32F1/persistent_store_flash.cpp diff --git a/Marlin/src/HAL/HAL_STM32F1/persistent_store_sdcard.cpp b/Marlin/src/HAL/STM32F1/persistent_store_sdcard.cpp similarity index 96% rename from Marlin/src/HAL/HAL_STM32F1/persistent_store_sdcard.cpp rename to Marlin/src/HAL/STM32F1/persistent_store_sdcard.cpp index 0a0d712718..8b5d89ad83 100644 --- a/Marlin/src/HAL/HAL_STM32F1/persistent_store_sdcard.cpp +++ b/Marlin/src/HAL/STM32F1/persistent_store_sdcard.cpp @@ -29,7 +29,7 @@ #include "../../inc/MarlinConfig.h" -#if ENABLED(EEPROM_SETTINGS) && NONE(FLASH_EEPROM_EMULATION, SPI_EEPROM, I2C_EEPROM) +#if ENABLED(SDCARD_EEPROM_EMULATION) #include "../shared/persistent_store_api.h" @@ -100,6 +100,6 @@ bool PersistentStore::read_data(int &pos, uint8_t* value, const size_t size, uin size_t PersistentStore::capacity() { return HAL_EEPROM_SIZE; } -#endif // EEPROM_SETTINGS +#endif // SDCARD_EEPROM_EMULATION #endif // __STM32F1__ diff --git a/Marlin/src/HAL/HAL_STM32F1/pinsDebug.h b/Marlin/src/HAL/STM32F1/pinsDebug.h similarity index 90% rename from Marlin/src/HAL/HAL_STM32F1/pinsDebug.h rename to Marlin/src/HAL/STM32F1/pinsDebug.h index 8d3eed52d0..913cb62afc 100644 --- a/Marlin/src/HAL/HAL_STM32F1/pinsDebug.h +++ b/Marlin/src/HAL/STM32F1/pinsDebug.h @@ -19,9 +19,9 @@ #pragma once #ifdef NUM_DIGITAL_PINS // Only in ST's Arduino core (STM32duino, STM32Core) - #include "../HAL_STM32/pinsDebug_STM32duino.h" + #include "../STM32/pinsDebug_STM32duino.h" #elif defined(BOARD_NR_GPIO_PINS) // Only in STM32GENERIC (Maple) - #include "../HAL_STM32/pinsDebug_STM32GENERIC.h" + #include "../STM32/pinsDebug_STM32GENERIC.h" #else #error "M43 not supported for this board" #endif diff --git a/Marlin/src/HAL/HAL_STM32F1/sdio.cpp b/Marlin/src/HAL/STM32F1/sdio.cpp similarity index 100% rename from Marlin/src/HAL/HAL_STM32F1/sdio.cpp rename to Marlin/src/HAL/STM32F1/sdio.cpp diff --git a/Marlin/src/HAL/HAL_STM32F1/sdio.h b/Marlin/src/HAL/STM32F1/sdio.h similarity index 100% rename from Marlin/src/HAL/HAL_STM32F1/sdio.h rename to Marlin/src/HAL/STM32F1/sdio.h diff --git a/Marlin/src/HAL/HAL_STM32F1/spi_pins.h b/Marlin/src/HAL/STM32F1/spi_pins.h similarity index 100% rename from Marlin/src/HAL/HAL_STM32F1/spi_pins.h rename to Marlin/src/HAL/STM32F1/spi_pins.h diff --git a/Marlin/src/HAL/HAL_STM32F1/timers.cpp b/Marlin/src/HAL/STM32F1/timers.cpp similarity index 100% rename from Marlin/src/HAL/HAL_STM32F1/timers.cpp rename to Marlin/src/HAL/STM32F1/timers.cpp diff --git a/Marlin/src/HAL/HAL_STM32F1/timers.h b/Marlin/src/HAL/STM32F1/timers.h similarity index 100% rename from Marlin/src/HAL/HAL_STM32F1/timers.h rename to Marlin/src/HAL/STM32F1/timers.h diff --git a/Marlin/src/HAL/HAL_STM32F1/watchdog.cpp b/Marlin/src/HAL/STM32F1/watchdog.cpp similarity index 100% rename from Marlin/src/HAL/HAL_STM32F1/watchdog.cpp rename to Marlin/src/HAL/STM32F1/watchdog.cpp diff --git a/Marlin/src/HAL/HAL_STM32F1/watchdog.h b/Marlin/src/HAL/STM32F1/watchdog.h similarity index 100% rename from Marlin/src/HAL/HAL_STM32F1/watchdog.h rename to Marlin/src/HAL/STM32F1/watchdog.h diff --git a/Marlin/src/HAL/HAL_STM32_F4_F7/EmulatedEeprom.cpp b/Marlin/src/HAL/STM32_F4_F7/EmulatedEeprom.cpp similarity index 92% rename from Marlin/src/HAL/HAL_STM32_F4_F7/EmulatedEeprom.cpp rename to Marlin/src/HAL/STM32_F4_F7/EmulatedEeprom.cpp index 4852234ba4..cc1a1bb01e 100644 --- a/Marlin/src/HAL/HAL_STM32_F4_F7/EmulatedEeprom.cpp +++ b/Marlin/src/HAL/STM32_F4_F7/EmulatedEeprom.cpp @@ -27,13 +27,7 @@ // Include configs and pins to get all EEPROM flags #include "../../inc/MarlinConfig.h" -#ifdef STM32F7 - #define HAS_EMULATED_EEPROM 1 -#else - #define HAS_EMULATED_EEPROM NONE(I2C_EEPROM, SPI_EEPROM) -#endif - -#if HAS_EMULATED_EEPROM && ENABLED(EEPROM_SETTINGS) +#if ENABLED(FLASH_EEPROM_EMULATION) // ------------------------ // Includes @@ -108,7 +102,7 @@ void eeprom_read_block(void *__dst, const void *__src, size_t __n) { uint16_t data = 0xFF; uint16_t eeprom_address = unsigned(__src); - for (uint8_t c = 0; c < __n; c++) { + LOOP_L_N(c, __n) { EE_ReadVariable(eeprom_address+c, &data); *((uint8_t*)__dst + c) = data; } @@ -118,5 +112,5 @@ void eeprom_update_block(const void *__src, void *__dst, size_t __n) { } -#endif // EEPROM_SETTINGS +#endif // FLASH_EEPROM_EMULATION #endif // STM32GENERIC && (STM32F4 || STM32F7) diff --git a/Marlin/src/HAL/HAL_STM32_F4_F7/HAL.cpp b/Marlin/src/HAL/STM32_F4_F7/HAL.cpp similarity index 100% rename from Marlin/src/HAL/HAL_STM32_F4_F7/HAL.cpp rename to Marlin/src/HAL/STM32_F4_F7/HAL.cpp diff --git a/Marlin/src/HAL/HAL_STM32_F4_F7/HAL.h b/Marlin/src/HAL/STM32_F4_F7/HAL.h similarity index 100% rename from Marlin/src/HAL/HAL_STM32_F4_F7/HAL.h rename to Marlin/src/HAL/STM32_F4_F7/HAL.h diff --git a/Marlin/src/HAL/HAL_STM32_F4_F7/HAL_SPI.cpp b/Marlin/src/HAL/STM32_F4_F7/HAL_SPI.cpp similarity index 100% rename from Marlin/src/HAL/HAL_STM32_F4_F7/HAL_SPI.cpp rename to Marlin/src/HAL/STM32_F4_F7/HAL_SPI.cpp diff --git a/Marlin/src/HAL/HAL_STM32_F4_F7/README.md b/Marlin/src/HAL/STM32_F4_F7/README.md similarity index 100% rename from Marlin/src/HAL/HAL_STM32_F4_F7/README.md rename to Marlin/src/HAL/STM32_F4_F7/README.md diff --git a/Marlin/src/HAL/HAL_STM32_F4_F7/STM32F4/README.md b/Marlin/src/HAL/STM32_F4_F7/STM32F4/README.md similarity index 100% rename from Marlin/src/HAL/HAL_STM32_F4_F7/STM32F4/README.md rename to Marlin/src/HAL/STM32_F4_F7/STM32F4/README.md diff --git a/Marlin/src/HAL/HAL_STM32_F4_F7/STM32F4/timers.cpp b/Marlin/src/HAL/STM32_F4_F7/STM32F4/timers.cpp similarity index 100% rename from Marlin/src/HAL/HAL_STM32_F4_F7/STM32F4/timers.cpp rename to Marlin/src/HAL/STM32_F4_F7/STM32F4/timers.cpp diff --git a/Marlin/src/HAL/HAL_STM32_F4_F7/STM32F4/timers.h b/Marlin/src/HAL/STM32_F4_F7/STM32F4/timers.h similarity index 100% rename from Marlin/src/HAL/HAL_STM32_F4_F7/STM32F4/timers.h rename to Marlin/src/HAL/STM32_F4_F7/STM32F4/timers.h diff --git a/Marlin/src/HAL/HAL_STM32_F4_F7/STM32F7/README.md b/Marlin/src/HAL/STM32_F4_F7/STM32F7/README.md similarity index 100% rename from Marlin/src/HAL/HAL_STM32_F4_F7/STM32F7/README.md rename to Marlin/src/HAL/STM32_F4_F7/STM32F7/README.md diff --git a/Marlin/src/HAL/HAL_STM32_F4_F7/STM32F7/TMC2660.cpp b/Marlin/src/HAL/STM32_F4_F7/STM32F7/TMC2660.cpp similarity index 100% rename from Marlin/src/HAL/HAL_STM32_F4_F7/STM32F7/TMC2660.cpp rename to Marlin/src/HAL/STM32_F4_F7/STM32F7/TMC2660.cpp diff --git a/Marlin/src/HAL/HAL_STM32_F4_F7/STM32F7/TMC2660.h b/Marlin/src/HAL/STM32_F4_F7/STM32F7/TMC2660.h similarity index 100% rename from Marlin/src/HAL/HAL_STM32_F4_F7/STM32F7/TMC2660.h rename to Marlin/src/HAL/STM32_F4_F7/STM32F7/TMC2660.h diff --git a/Marlin/src/HAL/HAL_STM32_F4_F7/STM32F7/timers.cpp b/Marlin/src/HAL/STM32_F4_F7/STM32F7/timers.cpp similarity index 100% rename from Marlin/src/HAL/HAL_STM32_F4_F7/STM32F7/timers.cpp rename to Marlin/src/HAL/STM32_F4_F7/STM32F7/timers.cpp diff --git a/Marlin/src/HAL/HAL_STM32_F4_F7/STM32F7/timers.h b/Marlin/src/HAL/STM32_F4_F7/STM32F7/timers.h similarity index 100% rename from Marlin/src/HAL/HAL_STM32_F4_F7/STM32F7/timers.h rename to Marlin/src/HAL/STM32_F4_F7/STM32F7/timers.h diff --git a/Marlin/src/HAL/HAL_STM32_F4_F7/Servo.cpp b/Marlin/src/HAL/STM32_F4_F7/Servo.cpp similarity index 100% rename from Marlin/src/HAL/HAL_STM32_F4_F7/Servo.cpp rename to Marlin/src/HAL/STM32_F4_F7/Servo.cpp diff --git a/Marlin/src/HAL/HAL_STM32_F4_F7/Servo.h b/Marlin/src/HAL/STM32_F4_F7/Servo.h similarity index 100% rename from Marlin/src/HAL/HAL_STM32_F4_F7/Servo.h rename to Marlin/src/HAL/STM32_F4_F7/Servo.h diff --git a/Marlin/src/HAL/HAL_STM32_F4_F7/eeprom_emul.cpp b/Marlin/src/HAL/STM32_F4_F7/eeprom_emul.cpp similarity index 100% rename from Marlin/src/HAL/HAL_STM32_F4_F7/eeprom_emul.cpp rename to Marlin/src/HAL/STM32_F4_F7/eeprom_emul.cpp diff --git a/Marlin/src/HAL/HAL_STM32_F4_F7/eeprom_emul.h b/Marlin/src/HAL/STM32_F4_F7/eeprom_emul.h similarity index 100% rename from Marlin/src/HAL/HAL_STM32_F4_F7/eeprom_emul.h rename to Marlin/src/HAL/STM32_F4_F7/eeprom_emul.h diff --git a/Marlin/src/HAL/HAL_STM32_F4_F7/endstop_interrupts.h b/Marlin/src/HAL/STM32_F4_F7/endstop_interrupts.h similarity index 100% rename from Marlin/src/HAL/HAL_STM32_F4_F7/endstop_interrupts.h rename to Marlin/src/HAL/STM32_F4_F7/endstop_interrupts.h diff --git a/Marlin/src/HAL/HAL_STM32_F4_F7/fastio.h b/Marlin/src/HAL/STM32_F4_F7/fastio.h similarity index 100% rename from Marlin/src/HAL/HAL_STM32_F4_F7/fastio.h rename to Marlin/src/HAL/STM32_F4_F7/fastio.h diff --git a/Marlin/src/HAL/HAL_STM32_F4_F7/inc/Conditionals_LCD.h b/Marlin/src/HAL/STM32_F4_F7/inc/Conditionals_LCD.h similarity index 100% rename from Marlin/src/HAL/HAL_STM32_F4_F7/inc/Conditionals_LCD.h rename to Marlin/src/HAL/STM32_F4_F7/inc/Conditionals_LCD.h diff --git a/Marlin/src/HAL/HAL_STM32_F4_F7/inc/Conditionals_adv.h b/Marlin/src/HAL/STM32_F4_F7/inc/Conditionals_adv.h similarity index 100% rename from Marlin/src/HAL/HAL_STM32_F4_F7/inc/Conditionals_adv.h rename to Marlin/src/HAL/STM32_F4_F7/inc/Conditionals_adv.h diff --git a/Marlin/src/HAL/HAL_TEENSY35_36/inc/Conditionals_post.h b/Marlin/src/HAL/STM32_F4_F7/inc/Conditionals_post.h similarity index 80% rename from Marlin/src/HAL/HAL_TEENSY35_36/inc/Conditionals_post.h rename to Marlin/src/HAL/STM32_F4_F7/inc/Conditionals_post.h index 0285c52ee3..6e2cf62101 100644 --- a/Marlin/src/HAL/HAL_TEENSY35_36/inc/Conditionals_post.h +++ b/Marlin/src/HAL/STM32_F4_F7/inc/Conditionals_post.h @@ -20,3 +20,11 @@ * */ #pragma once + +#if ENABLED(EEPROM_SETTINGS) && defined(STM32F7) + #undef USE_REAL_EEPROM + #define USE_EMULATED_EEPROM 1 + #undef SRAM_EEPROM_EMULATION + #undef SDCARD_EEPROM_EMULATION + #define FLASH_EEPROM_EMULATION 1 +#endif diff --git a/Marlin/src/HAL/HAL_STM32_F4_F7/inc/SanityCheck.h b/Marlin/src/HAL/STM32_F4_F7/inc/SanityCheck.h similarity index 100% rename from Marlin/src/HAL/HAL_STM32_F4_F7/inc/SanityCheck.h rename to Marlin/src/HAL/STM32_F4_F7/inc/SanityCheck.h diff --git a/Marlin/src/HAL/HAL_STM32_F4_F7/persistent_store_eeprom.cpp b/Marlin/src/HAL/STM32_F4_F7/persistent_store_eeprom.cpp similarity index 100% rename from Marlin/src/HAL/HAL_STM32_F4_F7/persistent_store_eeprom.cpp rename to Marlin/src/HAL/STM32_F4_F7/persistent_store_eeprom.cpp diff --git a/Marlin/src/HAL/HAL_STM32_F4_F7/pinsDebug.h b/Marlin/src/HAL/STM32_F4_F7/pinsDebug.h similarity index 91% rename from Marlin/src/HAL/HAL_STM32_F4_F7/pinsDebug.h rename to Marlin/src/HAL/STM32_F4_F7/pinsDebug.h index 8672dd0a1b..208a3524f7 100644 --- a/Marlin/src/HAL/HAL_STM32_F4_F7/pinsDebug.h +++ b/Marlin/src/HAL/STM32_F4_F7/pinsDebug.h @@ -19,9 +19,9 @@ #pragma once #ifdef NUM_DIGITAL_PINS // Only in ST's Arduino core (STM32duino, STM32Core) - #include "../HAL_STM32/pinsDebug_STM32duino.h" + #include "../STM32/pinsDebug_STM32duino.h" #elif defined(BOARD_NR_GPIO_PINS) // Only in STM32GENERIC (Maple) - #include "../HAL_STM32/pinsDebug_STM32GENERIC.h" + #include "../STM32/pinsDebug_STM32GENERIC.h" #else #error "M43 Pins Debugging not supported for this board." #endif diff --git a/Marlin/src/HAL/HAL_STM32_F4_F7/spi_pins.h b/Marlin/src/HAL/STM32_F4_F7/spi_pins.h similarity index 100% rename from Marlin/src/HAL/HAL_STM32_F4_F7/spi_pins.h rename to Marlin/src/HAL/STM32_F4_F7/spi_pins.h diff --git a/Marlin/src/HAL/HAL_STM32_F4_F7/timers.h b/Marlin/src/HAL/STM32_F4_F7/timers.h similarity index 100% rename from Marlin/src/HAL/HAL_STM32_F4_F7/timers.h rename to Marlin/src/HAL/STM32_F4_F7/timers.h diff --git a/Marlin/src/HAL/HAL_STM32_F4_F7/watchdog.cpp b/Marlin/src/HAL/STM32_F4_F7/watchdog.cpp similarity index 100% rename from Marlin/src/HAL/HAL_STM32_F4_F7/watchdog.cpp rename to Marlin/src/HAL/STM32_F4_F7/watchdog.cpp diff --git a/Marlin/src/HAL/HAL_STM32_F4_F7/watchdog.h b/Marlin/src/HAL/STM32_F4_F7/watchdog.h similarity index 100% rename from Marlin/src/HAL/HAL_STM32_F4_F7/watchdog.h rename to Marlin/src/HAL/STM32_F4_F7/watchdog.h diff --git a/Marlin/src/HAL/HAL_TEENSY31_32/HAL.cpp b/Marlin/src/HAL/TEENSY31_32/HAL.cpp similarity index 100% rename from Marlin/src/HAL/HAL_TEENSY31_32/HAL.cpp rename to Marlin/src/HAL/TEENSY31_32/HAL.cpp diff --git a/Marlin/src/HAL/HAL_TEENSY31_32/HAL.h b/Marlin/src/HAL/TEENSY31_32/HAL.h similarity index 100% rename from Marlin/src/HAL/HAL_TEENSY31_32/HAL.h rename to Marlin/src/HAL/TEENSY31_32/HAL.h diff --git a/Marlin/src/HAL/HAL_TEENSY31_32/HAL_SPI.cpp b/Marlin/src/HAL/TEENSY31_32/HAL_SPI.cpp similarity index 100% rename from Marlin/src/HAL/HAL_TEENSY31_32/HAL_SPI.cpp rename to Marlin/src/HAL/TEENSY31_32/HAL_SPI.cpp diff --git a/Marlin/src/HAL/HAL_TEENSY31_32/Servo.cpp b/Marlin/src/HAL/TEENSY31_32/Servo.cpp similarity index 100% rename from Marlin/src/HAL/HAL_TEENSY31_32/Servo.cpp rename to Marlin/src/HAL/TEENSY31_32/Servo.cpp diff --git a/Marlin/src/HAL/HAL_TEENSY31_32/Servo.h b/Marlin/src/HAL/TEENSY31_32/Servo.h similarity index 100% rename from Marlin/src/HAL/HAL_TEENSY31_32/Servo.h rename to Marlin/src/HAL/TEENSY31_32/Servo.h diff --git a/Marlin/src/HAL/HAL_TEENSY31_32/endstop_interrupts.h b/Marlin/src/HAL/TEENSY31_32/endstop_interrupts.h similarity index 100% rename from Marlin/src/HAL/HAL_TEENSY31_32/endstop_interrupts.h rename to Marlin/src/HAL/TEENSY31_32/endstop_interrupts.h diff --git a/Marlin/src/HAL/HAL_TEENSY31_32/fastio.h b/Marlin/src/HAL/TEENSY31_32/fastio.h similarity index 100% rename from Marlin/src/HAL/HAL_TEENSY31_32/fastio.h rename to Marlin/src/HAL/TEENSY31_32/fastio.h diff --git a/Marlin/src/HAL/HAL_TEENSY31_32/inc/Conditionals_LCD.h b/Marlin/src/HAL/TEENSY31_32/inc/Conditionals_LCD.h similarity index 100% rename from Marlin/src/HAL/HAL_TEENSY31_32/inc/Conditionals_LCD.h rename to Marlin/src/HAL/TEENSY31_32/inc/Conditionals_LCD.h diff --git a/Marlin/src/HAL/HAL_TEENSY31_32/inc/Conditionals_adv.h b/Marlin/src/HAL/TEENSY31_32/inc/Conditionals_adv.h similarity index 100% rename from Marlin/src/HAL/HAL_TEENSY31_32/inc/Conditionals_adv.h rename to Marlin/src/HAL/TEENSY31_32/inc/Conditionals_adv.h diff --git a/Marlin/src/HAL/HAL_SAMD51/inc/Conditionals_post.h b/Marlin/src/HAL/TEENSY31_32/inc/Conditionals_post.h similarity index 100% rename from Marlin/src/HAL/HAL_SAMD51/inc/Conditionals_post.h rename to Marlin/src/HAL/TEENSY31_32/inc/Conditionals_post.h diff --git a/Marlin/src/HAL/HAL_TEENSY31_32/inc/SanityCheck.h b/Marlin/src/HAL/TEENSY31_32/inc/SanityCheck.h similarity index 100% rename from Marlin/src/HAL/HAL_TEENSY31_32/inc/SanityCheck.h rename to Marlin/src/HAL/TEENSY31_32/inc/SanityCheck.h diff --git a/Marlin/src/HAL/HAL_TEENSY31_32/persistent_store_impl.cpp b/Marlin/src/HAL/TEENSY31_32/persistent_store_impl.cpp similarity index 100% rename from Marlin/src/HAL/HAL_TEENSY31_32/persistent_store_impl.cpp rename to Marlin/src/HAL/TEENSY31_32/persistent_store_impl.cpp diff --git a/Marlin/src/HAL/HAL_TEENSY31_32/pinsDebug.h b/Marlin/src/HAL/TEENSY31_32/pinsDebug.h similarity index 100% rename from Marlin/src/HAL/HAL_TEENSY31_32/pinsDebug.h rename to Marlin/src/HAL/TEENSY31_32/pinsDebug.h diff --git a/Marlin/src/HAL/HAL_TEENSY31_32/spi_pins.h b/Marlin/src/HAL/TEENSY31_32/spi_pins.h similarity index 100% rename from Marlin/src/HAL/HAL_TEENSY31_32/spi_pins.h rename to Marlin/src/HAL/TEENSY31_32/spi_pins.h diff --git a/Marlin/src/HAL/HAL_TEENSY31_32/timers.cpp b/Marlin/src/HAL/TEENSY31_32/timers.cpp similarity index 100% rename from Marlin/src/HAL/HAL_TEENSY31_32/timers.cpp rename to Marlin/src/HAL/TEENSY31_32/timers.cpp diff --git a/Marlin/src/HAL/HAL_TEENSY31_32/timers.h b/Marlin/src/HAL/TEENSY31_32/timers.h similarity index 100% rename from Marlin/src/HAL/HAL_TEENSY31_32/timers.h rename to Marlin/src/HAL/TEENSY31_32/timers.h diff --git a/Marlin/src/HAL/HAL_TEENSY31_32/watchdog.cpp b/Marlin/src/HAL/TEENSY31_32/watchdog.cpp similarity index 100% rename from Marlin/src/HAL/HAL_TEENSY31_32/watchdog.cpp rename to Marlin/src/HAL/TEENSY31_32/watchdog.cpp diff --git a/Marlin/src/HAL/HAL_TEENSY31_32/watchdog.h b/Marlin/src/HAL/TEENSY31_32/watchdog.h similarity index 100% rename from Marlin/src/HAL/HAL_TEENSY31_32/watchdog.h rename to Marlin/src/HAL/TEENSY31_32/watchdog.h diff --git a/Marlin/src/HAL/HAL_TEENSY35_36/HAL.cpp b/Marlin/src/HAL/TEENSY35_36/HAL.cpp similarity index 100% rename from Marlin/src/HAL/HAL_TEENSY35_36/HAL.cpp rename to Marlin/src/HAL/TEENSY35_36/HAL.cpp diff --git a/Marlin/src/HAL/HAL_TEENSY35_36/HAL.h b/Marlin/src/HAL/TEENSY35_36/HAL.h similarity index 100% rename from Marlin/src/HAL/HAL_TEENSY35_36/HAL.h rename to Marlin/src/HAL/TEENSY35_36/HAL.h diff --git a/Marlin/src/HAL/HAL_TEENSY35_36/HAL_SPI.cpp b/Marlin/src/HAL/TEENSY35_36/HAL_SPI.cpp similarity index 100% rename from Marlin/src/HAL/HAL_TEENSY35_36/HAL_SPI.cpp rename to Marlin/src/HAL/TEENSY35_36/HAL_SPI.cpp diff --git a/Marlin/src/HAL/HAL_TEENSY35_36/Servo.cpp b/Marlin/src/HAL/TEENSY35_36/Servo.cpp similarity index 100% rename from Marlin/src/HAL/HAL_TEENSY35_36/Servo.cpp rename to Marlin/src/HAL/TEENSY35_36/Servo.cpp diff --git a/Marlin/src/HAL/HAL_TEENSY35_36/Servo.h b/Marlin/src/HAL/TEENSY35_36/Servo.h similarity index 100% rename from Marlin/src/HAL/HAL_TEENSY35_36/Servo.h rename to Marlin/src/HAL/TEENSY35_36/Servo.h diff --git a/Marlin/src/HAL/HAL_TEENSY35_36/endstop_interrupts.h b/Marlin/src/HAL/TEENSY35_36/endstop_interrupts.h similarity index 100% rename from Marlin/src/HAL/HAL_TEENSY35_36/endstop_interrupts.h rename to Marlin/src/HAL/TEENSY35_36/endstop_interrupts.h diff --git a/Marlin/src/HAL/HAL_TEENSY35_36/fastio.h b/Marlin/src/HAL/TEENSY35_36/fastio.h similarity index 100% rename from Marlin/src/HAL/HAL_TEENSY35_36/fastio.h rename to Marlin/src/HAL/TEENSY35_36/fastio.h diff --git a/Marlin/src/HAL/HAL_TEENSY35_36/inc/Conditionals_LCD.h b/Marlin/src/HAL/TEENSY35_36/inc/Conditionals_LCD.h similarity index 100% rename from Marlin/src/HAL/HAL_TEENSY35_36/inc/Conditionals_LCD.h rename to Marlin/src/HAL/TEENSY35_36/inc/Conditionals_LCD.h diff --git a/Marlin/src/HAL/HAL_TEENSY35_36/inc/Conditionals_adv.h b/Marlin/src/HAL/TEENSY35_36/inc/Conditionals_adv.h similarity index 100% rename from Marlin/src/HAL/HAL_TEENSY35_36/inc/Conditionals_adv.h rename to Marlin/src/HAL/TEENSY35_36/inc/Conditionals_adv.h diff --git a/Marlin/src/HAL/HAL_STM32/inc/Conditionals_post.h b/Marlin/src/HAL/TEENSY35_36/inc/Conditionals_post.h similarity index 100% rename from Marlin/src/HAL/HAL_STM32/inc/Conditionals_post.h rename to Marlin/src/HAL/TEENSY35_36/inc/Conditionals_post.h diff --git a/Marlin/src/HAL/HAL_TEENSY35_36/inc/SanityCheck.h b/Marlin/src/HAL/TEENSY35_36/inc/SanityCheck.h similarity index 100% rename from Marlin/src/HAL/HAL_TEENSY35_36/inc/SanityCheck.h rename to Marlin/src/HAL/TEENSY35_36/inc/SanityCheck.h diff --git a/Marlin/src/HAL/HAL_TEENSY35_36/persistent_store_eeprom.cpp b/Marlin/src/HAL/TEENSY35_36/persistent_store_eeprom.cpp similarity index 100% rename from Marlin/src/HAL/HAL_TEENSY35_36/persistent_store_eeprom.cpp rename to Marlin/src/HAL/TEENSY35_36/persistent_store_eeprom.cpp diff --git a/Marlin/src/HAL/HAL_TEENSY35_36/pinsDebug.h b/Marlin/src/HAL/TEENSY35_36/pinsDebug.h similarity index 100% rename from Marlin/src/HAL/HAL_TEENSY35_36/pinsDebug.h rename to Marlin/src/HAL/TEENSY35_36/pinsDebug.h diff --git a/Marlin/src/HAL/HAL_TEENSY35_36/spi_pins.h b/Marlin/src/HAL/TEENSY35_36/spi_pins.h similarity index 100% rename from Marlin/src/HAL/HAL_TEENSY35_36/spi_pins.h rename to Marlin/src/HAL/TEENSY35_36/spi_pins.h diff --git a/Marlin/src/HAL/HAL_TEENSY35_36/timers.cpp b/Marlin/src/HAL/TEENSY35_36/timers.cpp similarity index 100% rename from Marlin/src/HAL/HAL_TEENSY35_36/timers.cpp rename to Marlin/src/HAL/TEENSY35_36/timers.cpp diff --git a/Marlin/src/HAL/HAL_TEENSY35_36/timers.h b/Marlin/src/HAL/TEENSY35_36/timers.h similarity index 100% rename from Marlin/src/HAL/HAL_TEENSY35_36/timers.h rename to Marlin/src/HAL/TEENSY35_36/timers.h diff --git a/Marlin/src/HAL/HAL_TEENSY35_36/watchdog.cpp b/Marlin/src/HAL/TEENSY35_36/watchdog.cpp similarity index 100% rename from Marlin/src/HAL/HAL_TEENSY35_36/watchdog.cpp rename to Marlin/src/HAL/TEENSY35_36/watchdog.cpp diff --git a/Marlin/src/HAL/HAL_TEENSY35_36/watchdog.h b/Marlin/src/HAL/TEENSY35_36/watchdog.h similarity index 100% rename from Marlin/src/HAL/HAL_TEENSY35_36/watchdog.h rename to Marlin/src/HAL/TEENSY35_36/watchdog.h diff --git a/Marlin/src/HAL/platforms.h b/Marlin/src/HAL/platforms.h index cbf8a9512b..cc462f37c5 100644 --- a/Marlin/src/HAL/platforms.h +++ b/Marlin/src/HAL/platforms.h @@ -21,32 +21,30 @@ */ #pragma once +#define XSTR(V...) #V + #ifdef __AVR__ - #define HAL_PLATFORM HAL_AVR + #define HAL_PATH(PATH, NAME) XSTR(PATH/AVR/NAME) #elif defined(ARDUINO_ARCH_SAM) - #define HAL_PLATFORM HAL_DUE + #define HAL_PATH(PATH, NAME) XSTR(PATH/DUE/NAME) #elif defined(__MK20DX256__) - #define HAL_PLATFORM HAL_TEENSY31_32 + #define HAL_PATH(PATH, NAME) XSTR(PATH/TEENSY31_32/NAME) #elif defined(__MK64FX512__) || defined(__MK66FX1M0__) - #define HAL_PLATFORM HAL_TEENSY35_36 + #define HAL_PATH(PATH, NAME) XSTR(PATH/TEENSY35_36/NAME) #elif defined(TARGET_LPC1768) - #define HAL_PLATFORM HAL_LPC1768 + #define HAL_PATH(PATH, NAME) XSTR(PATH/LPC1768/NAME) #elif defined(__STM32F1__) || defined(TARGET_STM32F1) - #define HAL_PLATFORM HAL_STM32F1 + #define HAL_PATH(PATH, NAME) XSTR(PATH/STM32F1/NAME) #elif defined(STM32GENERIC) && (defined(STM32F4) || defined(STM32F7)) - #define HAL_PLATFORM HAL_STM32_F4_F7 + #define HAL_PATH(PATH, NAME) XSTR(PATH/STM32_F4_F7/NAME) #elif defined(ARDUINO_ARCH_STM32) - #define HAL_PLATFORM HAL_STM32 + #define HAL_PATH(PATH, NAME) XSTR(PATH/STM32/NAME) #elif defined(ARDUINO_ARCH_ESP32) - #define HAL_PLATFORM HAL_ESP32 + #define HAL_PATH(PATH, NAME) XSTR(PATH/ESP32/NAME) #elif defined(__PLAT_LINUX__) - #define HAL_PLATFORM HAL_LINUX + #define HAL_PATH(PATH, NAME) XSTR(PATH/LINUX/NAME) #elif defined(__SAMD51__) - #define HAL_PLATFORM HAL_SAMD51 + #define HAL_PATH(PATH, NAME) XSTR(PATH/SAMD51/NAME) #else #error "Unsupported Platform!" #endif - -#define XSTR_(M) #M -#define XSTR(M) XSTR_(M) -#define HAL_PATH(PATH, NAME) XSTR(PATH/HAL_PLATFORM/NAME) diff --git a/Marlin/src/HAL/shared/Delay.h b/Marlin/src/HAL/shared/Delay.h index 78bf6745ea..5cb68b1503 100644 --- a/Marlin/src/HAL/shared/Delay.h +++ b/Marlin/src/HAL/shared/Delay.h @@ -29,7 +29,6 @@ * DELAY_US(count): Delay execution in microseconds */ -#include "../../core/millis_t.h" #include "../../core/macros.h" #if defined(__arm__) || defined(__thumb__) diff --git a/Marlin/src/HAL/shared/HAL_ST7920.h b/Marlin/src/HAL/shared/HAL_ST7920.h index 12392a5ece..69c1d741ae 100644 --- a/Marlin/src/HAL/shared/HAL_ST7920.h +++ b/Marlin/src/HAL/shared/HAL_ST7920.h @@ -22,7 +22,7 @@ #pragma once /** - * HAL/HAL_ST7920.h + * HAL/ST7920.h * For the HALs that provide direct access to the ST7920 display * (bypassing U8G), it will allow the LIGHTWEIGHT_UI to operate. */ diff --git a/Marlin/src/HAL/shared/MarlinSerial.h b/Marlin/src/HAL/shared/MarlinSerial.h deleted file mode 100644 index 3770f61b3c..0000000000 --- a/Marlin/src/HAL/shared/MarlinSerial.h +++ /dev/null @@ -1,67 +0,0 @@ -/** - * Marlin 3D Printer Firmware - * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * - * Based on Sprinter and grbl. - * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm - * - * This program is free software: you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with this program. If not, see . - * - */ -#pragma once - -/** - * HAL/shared/MarlinSerial.h - */ - -#include "../../inc/MarlinConfigPre.h" - -constexpr bool - #if HAS_DGUS_LCD - bDGUS_SERIAL_STATS_RX_BUFFER_OVERRUNS = (false - #if ENABLED(DGUS_SERIAL_STATS_RX_BUFFER_OVERRUNS) - || true - #endif - ), - #endif - bSERIAL_XON_XOFF = (false - #if ENABLED(SERIAL_XON_XOFF) - || true - #endif - ), - bEMERGENCY_PARSER = (false - #if ENABLED(EMERGENCY_PARSER) - || true - #endif - ), - bSERIAL_STATS_DROPPED_RX = (false - #if ENABLED(SERIAL_STATS_DROPPED_RX) - || true - #endif - ), - bSERIAL_STATS_RX_BUFFER_OVERRUNS = (false - #if ENABLED(SERIAL_STATS_RX_BUFFER_OVERRUNS) - || true - #endif - ), - bSERIAL_STATS_RX_FRAMING_ERRORS = (false - #if ENABLED(SERIAL_STATS_RX_FRAMING_ERRORS) - || true - #endif - ), - bSERIAL_STATS_MAX_RX_QUEUED = (false - #if ENABLED(SERIAL_STATS_MAX_RX_QUEUED) - || true - #endif - ); diff --git a/Marlin/src/HAL/shared/servo.cpp b/Marlin/src/HAL/shared/servo.cpp index d03b80b200..2c3d7bb7d3 100644 --- a/Marlin/src/HAL/shared/servo.cpp +++ b/Marlin/src/HAL/shared/servo.cpp @@ -68,7 +68,7 @@ uint8_t ServoCount = 0; // the total number of attached static boolean isTimerActive(timer16_Sequence_t timer) { // returns true if any servo is active on this timer - for (uint8_t channel = 0; channel < SERVOS_PER_TIMER; channel++) { + LOOP_L_N(channel, SERVOS_PER_TIMER) { if (SERVO(timer, channel).Pin.isActive) return true; } diff --git a/Marlin/src/HAL/shared/servo.h b/Marlin/src/HAL/shared/servo.h index 4e12720553..b582221b86 100644 --- a/Marlin/src/HAL/shared/servo.h +++ b/Marlin/src/HAL/shared/servo.h @@ -68,19 +68,19 @@ */ #if IS_TEENSY32 - #include "../HAL_TEENSY31_32/Servo.h" + #include "../TEENSY31_32/Servo.h" #elif IS_TEENSY35 || IS_TEENSY36 - #include "../HAL_TEENSY35_36/Servo.h" + #include "../TEENSY35_36/Servo.h" #elif defined(TARGET_LPC1768) - #include "../HAL_LPC1768/Servo.h" + #include "../LPC1768/Servo.h" #elif defined(__STM32F1__) || defined(TARGET_STM32F1) - #include "../HAL_STM32F1/Servo.h" + #include "../STM32F1/Servo.h" #elif defined(STM32GENERIC) && defined(STM32F4) - #include "../HAL_STM32_F4_F7/Servo.h" + #include "../STM32_F4_F7/Servo.h" #elif defined(ARDUINO_ARCH_STM32) - #include "../HAL_STM32/Servo.h" + #include "../STM32/Servo.h" #elif defined(ARDUINO_ARCH_ESP32) - #include "../HAL_ESP32/Servo.h" + #include "../ESP32/Servo.h" #else #include diff --git a/Marlin/src/HAL/shared/servo_private.h b/Marlin/src/HAL/shared/servo_private.h index 63761ce0f4..58e455b124 100644 --- a/Marlin/src/HAL/shared/servo_private.h +++ b/Marlin/src/HAL/shared/servo_private.h @@ -44,11 +44,11 @@ // Architecture specific include #ifdef __AVR__ - #include "../HAL_AVR/ServoTimers.h" + #include "../AVR/ServoTimers.h" #elif defined(ARDUINO_ARCH_SAM) - #include "../HAL_DUE/ServoTimers.h" + #include "../DUE/ServoTimers.h" #elif defined(__SAMD51__) - #include "../HAL_SAMD51/ServoTimers.h" + #include "../SAMD51/ServoTimers.h" #else #error "This library only supports boards with an AVR, SAM3X or SAMD51 processor." #endif diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index 5a527482ce..f19aaef968 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -78,7 +78,7 @@ #endif #if ENABLED(MAX7219_DEBUG) - #include "feature/Max7219_Debug_LEDs.h" + #include "feature/max7219.h" #endif #if HAS_COLOR_LEDS @@ -107,10 +107,10 @@ #endif #if ENABLED(I2C_POSITION_ENCODERS) - #include "feature/I2CPositionEncoder.h" + #include "feature/encoder_i2c.h" #endif -#if HAS_TRINAMIC && DISABLED(PSU_DEFAULT_OFF) +#if HAS_TRINAMIC_CONFIG && DISABLED(PSU_DEFAULT_OFF) #include "feature/tmc_util.h" #endif @@ -142,7 +142,7 @@ #endif #if ENABLED(POWER_LOSS_RECOVERY) - #include "feature/power_loss_recovery.h" + #include "feature/powerloss.h" #endif #if ENABLED(CANCEL_OBJECTS) @@ -165,7 +165,7 @@ #include "feature/fanmux.h" #endif -#if DO_SWITCH_EXTRUDER || ANY(SWITCHING_NOZZLE, PARKING_EXTRUDER, MAGNETIC_PARKING_EXTRUDER, ELECTROMAGNETIC_SWITCHING_TOOLHEAD) +#if DO_SWITCH_EXTRUDER || ANY(SWITCHING_NOZZLE, PARKING_EXTRUDER, MAGNETIC_PARKING_EXTRUDER, ELECTROMAGNETIC_SWITCHING_TOOLHEAD, SWITCHING_TOOLHEAD) #include "module/tool_change.h" #endif @@ -174,7 +174,7 @@ #endif #if ENABLED(PRUSA_MMU2) - #include "feature/prusa_MMU2/mmu2.h" + #include "feature/mmu2/mmu2.h" #endif #if HAS_L64XX @@ -192,7 +192,15 @@ const char NUL_STR[] PROGMEM = "", SP_X_STR[] PROGMEM = " X", SP_Y_STR[] PROGMEM = " Y", SP_Z_STR[] PROGMEM = " Z", - SP_E_STR[] PROGMEM = " E"; + SP_E_STR[] PROGMEM = " E", + X_LBL[] PROGMEM = "X:", + Y_LBL[] PROGMEM = "Y:", + Z_LBL[] PROGMEM = "Z:", + E_LBL[] PROGMEM = "E:", + SP_X_LBL[] PROGMEM = " X:", + SP_Y_LBL[] PROGMEM = " Y:", + SP_Z_LBL[] PROGMEM = " Z:", + SP_E_LBL[] PROGMEM = " E:"; bool Running = true; @@ -233,11 +241,8 @@ void setup_powerhold() { OUT_WRITE(SUICIDE_PIN, !SUICIDE_PIN_INVERTING); #endif #if ENABLED(PSU_CONTROL) - #if ENABLED(PSU_DEFAULT_OFF) - powersupply_on = true; PSU_OFF(); - #else - powersupply_on = false; PSU_ON(); - #endif + powersupply_on = ENABLED(PSU_DEFAULT_OFF); + if (ENABLED(PSU_DEFAULT_OFF)) PSU_OFF(); else PSU_ON(); #endif } @@ -269,7 +274,7 @@ void setup_powerhold() { bool pin_is_protected(const pin_t pin) { static const pin_t sensitive_pins[] PROGMEM = SENSITIVE_PINS; - for (uint8_t i = 0; i < COUNT(sensitive_pins); i++) { + LOOP_L_N(i, COUNT(sensitive_pins)) { pin_t sensitive_pin; memcpy_P(&sensitive_pin, &sensitive_pins[i], sizeof(pin_t)); if (pin == sensitive_pin) return true; @@ -413,28 +418,33 @@ void startOrResumeJob() { } inline void finishSDPrinting() { + bool did_state = true; switch (card.sdprinting_done_state) { - #if HAS_RESUME_CONTINUE // Display "Click to Continue..." - case 1: - did_state = queue.enqueue_P(PSTR("M0Q1S" - #if HAS_LCD_MENU - "1800" // ...for 30 minutes with LCD - #else - "60" // ...for 1 minute with no LCD - #endif - )); - break; - #endif - - case 2: print_job_timer.stop(); break; - - case 3: - did_state = print_job_timer.duration() < 60 || queue.enqueue_P(PSTR("M31")); + case 1: + did_state = print_job_timer.duration() < 60 || queue.enqueue_one_P(PSTR("M31")); break; - case 4: + case 2: + did_state = queue.enqueue_one_P(PSTR("M77")); + break; + + case 3: + #if ENABLED(LCD_SET_PROGRESS_MANUALLY) + ui.set_progress_done(); + #endif + break; + + case 4: // Display "Click to Continue..." + #if HAS_RESUME_CONTINUE // 30 min timeout with LCD, 1 min without + did_state = queue.enqueue_one_P( + print_job_timer.duration() < 60 ? PSTR("M0Q1P1") : PSTR("M0Q1S" TERN(HAS_LCD_MENU, "1800", "60")) + ); + #endif + break; + + case 5: #if ENABLED(POWER_LOSS_RECOVERY) recovery.purge(); #endif @@ -443,10 +453,6 @@ void startOrResumeJob() { planner.finish_and_disable(); #endif - #if ENABLED(LCD_SET_PROGRESS_MANUALLY) - ui.set_progress_done(); - #endif - #if ENABLED(SD_REPRINT_LAST_SELECTED_FILE) ui.reselect_last_file(); #endif @@ -493,31 +499,19 @@ inline void manage_inactivity(const bool ignore_stepper_queue=false) { } // Prevent steppers timing-out in the middle of M600 - #if BOTH(ADVANCED_PAUSE_FEATURE, PAUSE_PARK_NO_STEPPER_TIMEOUT) - #define MOVE_AWAY_TEST !did_pause_print - #else - #define MOVE_AWAY_TEST true - #endif + #define STAY_TEST (BOTH(ADVANCED_PAUSE_FEATURE, PAUSE_PARK_NO_STEPPER_TIMEOUT) && did_pause_print) if (stepper_inactive_time) { static bool already_shutdown_steppers; // = false if (planner.has_blocks_queued()) gcode.reset_stepper_timeout(); - else if (MOVE_AWAY_TEST && !ignore_stepper_queue && ELAPSED(ms, gcode.previous_move_ms + stepper_inactive_time)) { + else if (!STAY_TEST && !ignore_stepper_queue && ELAPSED(ms, gcode.previous_move_ms + stepper_inactive_time)) { if (!already_shutdown_steppers) { already_shutdown_steppers = true; // L6470 SPI will consume 99% of free time without this - #if ENABLED(DISABLE_INACTIVE_X) - DISABLE_AXIS_X(); - #endif - #if ENABLED(DISABLE_INACTIVE_Y) - DISABLE_AXIS_Y(); - #endif - #if ENABLED(DISABLE_INACTIVE_Z) - DISABLE_AXIS_Z(); - #endif - #if ENABLED(DISABLE_INACTIVE_E) - disable_e_steppers(); - #endif + if (ENABLED(DISABLE_INACTIVE_X)) DISABLE_AXIS_X(); + if (ENABLED(DISABLE_INACTIVE_Y)) DISABLE_AXIS_Y(); + if (ENABLED(DISABLE_INACTIVE_Z)) DISABLE_AXIS_Z(); + if (ENABLED(DISABLE_INACTIVE_E)) disable_e_steppers(); #if HAS_LCD_MENU && ENABLED(AUTO_BED_LEVELING_UBL) if (ubl.lcd_map_control) { ubl.lcd_map_control = false; @@ -642,7 +636,7 @@ inline void manage_inactivity(const bool ignore_stepper_queue=false) { // travel moves have been received so enact them delayed_move_time = 0xFFFFFFFFUL; // force moves to be done destination = current_position; - prepare_move_to_destination(); + prepare_line_to_destination(); } #endif @@ -866,6 +860,7 @@ void stop() { * • Digipot I2C * • Z probe sled * • status LEDs + * • Max7219 */ void setup() { @@ -879,10 +874,6 @@ void setup() { OUT_WRITE(SMART_EFFECTOR_MOD_PIN, LOW); // Put Smart Effector into NORMAL mode #endif - #if ENABLED(MAX7219_DEBUG) - max7219.init(); - #endif - #if ENABLED(DISABLE_DEBUG) // Disable any hardware debug to free up pins for IO #ifdef JTAGSWD_DISABLE @@ -975,48 +966,66 @@ void setup() { // UI must be initialized before EEPROM // (because EEPROM code calls the UI). + #if ENABLED(MARLIN_DEV_MODE) + auto log_current_ms = [&](PGM_P const msg) { + SERIAL_ECHO_START(); + SERIAL_CHAR('['); SERIAL_ECHO(millis()); SERIAL_ECHO("] "); + serialprintPGM(msg); + SERIAL_EOL(); + }; + #define SETUP_LOG(M) log_current_ms(PSTR(M)) + #else + #define SETUP_LOG(...) NOOP + #endif + #define SETUP_RUN(C) do{ SETUP_LOG(STRINGIFY(C)); C; }while(0) + // Set up LEDs early #if HAS_COLOR_LEDS - leds.setup(); + SETUP_RUN(leds.setup()); #endif - ui.init(); + SETUP_RUN(ui.init()); + SETUP_RUN(ui.reset_status()); // Load welcome message early. (Retained if no errors exist.) + #if HAS_SPI_LCD && ENABLED(SHOW_BOOTSCREEN) - ui.show_bootscreen(); + SETUP_RUN(ui.show_bootscreen()); #endif - ui.reset_status(); // Load welcome message early. (Retained if no errors exist.) - #if ENABLED(SDSUPPORT) - card.mount(); // Mount the SD card before settings.first_load + SETUP_RUN(card.mount()); // Mount the SD card before settings.first_load + #endif + + SETUP_RUN(settings.first_load()); // Load data from EEPROM if available (or use defaults) + // This also updates variables in the planner, elsewhere + + #if HAS_SERVICE_INTERVALS + SETUP_RUN(ui.reset_status(true)); // Show service messages or keep current status #endif - // Load data from EEPROM if available (or use defaults) - settings.first_load(); // This also updates variables in the planner, elsewhere #if ENABLED(TOUCH_BUTTONS) - touch.init(); + SETUP_RUN(touch.init()); #endif - #if HAS_M206_COMMAND // Initialize current position based on home_offset - current_position += home_offset; + #if HAS_M206_COMMAND + current_position += home_offset; // Init current position based on home_offset #endif - sync_plan_position(); // Vital to init stepper/planner equivalent for current_position + sync_plan_position(); // Vital to init stepper/planner equivalent for current_position - thermalManager.init(); // Initialize temperature loop + SETUP_RUN(thermalManager.init()); // Initialize temperature loop - print_job_timer.init(); // Initial setup of print job timer + SETUP_RUN(print_job_timer.init()); // Initial setup of print job timer - endstops.init(); // Init endstops and pullups + SETUP_RUN(endstops.init()); // Init endstops and pullups - stepper.init(); // Init stepper. This enables interrupts! + SETUP_RUN(stepper.init()); // Init stepper. This enables interrupts! #if HAS_SERVOS - servo_init(); + SETUP_RUN(servo_init()); #endif #if HAS_Z_SERVO_PROBE - probe.servo_probe_init(); + SETUP_RUN(probe.servo_probe_init()); #endif #if HAS_PHOTOGRAPH @@ -1024,7 +1033,7 @@ void setup() { #endif #if HAS_CUTTER - cutter.init(); + SETUP_RUN(cutter.init()); #endif #if ENABLED(COOLANT_MIST) @@ -1035,7 +1044,7 @@ void setup() { #endif #if HAS_BED_PROBE - endstops.enable_z_probe(false); + SETUP_RUN(endstops.enable_z_probe(false)); #endif #if ENABLED(USE_CONTROLLER_FAN) @@ -1043,15 +1052,15 @@ void setup() { #endif #if HAS_STEPPER_RESET - enableStepperDrivers(); + SETUP_RUN(enableStepperDrivers()); #endif #if ENABLED(DIGIPOT_I2C) - digipot_i2c_init(); + SETUP_RUN(digipot_i2c_init()); #endif #if ENABLED(DAC_STEPPER_CURRENT) - dac_init(); + SETUP_RUN(dac_init()); #endif #if EITHER(Z_PROBE_SLED, SOLENOID_PROBE) && HAS_SOLENOID_1 @@ -1074,41 +1083,44 @@ void setup() { #if DISABLED(CASE_LIGHT_USE_NEOPIXEL) if (PWM_PIN(CASE_LIGHT_PIN)) SET_PWM(CASE_LIGHT_PIN); else SET_OUTPUT(CASE_LIGHT_PIN); #endif - update_case_light(); + SETUP_RUN(update_case_light()); #endif #if ENABLED(MK2_MULTIPLEXER) + SETUP_LOG("MK2_MULTIPLEXER"); SET_OUTPUT(E_MUX0_PIN); SET_OUTPUT(E_MUX1_PIN); SET_OUTPUT(E_MUX2_PIN); #endif #if HAS_FANMUX - fanmux_init(); + SETUP_RUN(fanmux_init()); #endif #if ENABLED(MIXING_EXTRUDER) - mixer.init(); + SETUP_RUN(mixer.init()); #endif #if ENABLED(BLTOUCH) - bltouch.init(/*set_voltage=*/true); + SETUP_RUN(bltouch.init(/*set_voltage=*/true)); #endif #if ENABLED(I2C_POSITION_ENCODERS) - I2CPEM.init(); + SETUP_RUN(I2CPEM.init()); #endif #if ENABLED(EXPERIMENTAL_I2CBUS) && I2C_SLAVE_ADDRESS > 0 + SETUP_LOG("i2c..."); i2c.onReceive(i2c_on_receive); i2c.onRequest(i2c_on_request); #endif #if DO_SWITCH_EXTRUDER - move_extruder_servo(0); // Initialize extruder servo + SETUP_RUN(move_extruder_servo(0)); // Initialize extruder servo #endif #if ENABLED(SWITCHING_NOZZLE) + SETUP_LOG("SWITCHING_NOZZLE"); // Initialize nozzle servo(s) #if SWITCHING_NOZZLE_TWO_SERVOS lower_nozzle(0); @@ -1119,52 +1131,59 @@ void setup() { #endif #if ENABLED(MAGNETIC_PARKING_EXTRUDER) - mpe_settings_init(); + SETUP_RUN(mpe_settings_init()); #endif #if ENABLED(PARKING_EXTRUDER) - pe_solenoid_init(); + SETUP_RUN(pe_solenoid_init()); + #endif + + #if ENABLED(SWITCHING_TOOLHEAD) + swt_init(); #endif #if ENABLED(ELECTROMAGNETIC_SWITCHING_TOOLHEAD) - est_init(); + SETUP_RUN(est_init()); #endif #if ENABLED(POWER_LOSS_RECOVERY) - recovery.check(); + SETUP_RUN(recovery.check()); #endif #if ENABLED(USE_WATCHDOG) - watchdog_init(); // Reinit watchdog after HAL_get_reset_source call + SETUP_RUN(watchdog_init()); // Reinit watchdog after HAL_get_reset_source call #endif #if ENABLED(EXTERNAL_CLOSED_LOOP_CONTROLLER) - init_closedloop(); + SETUP_RUN(init_closedloop()); #endif #ifdef STARTUP_COMMANDS + SETUP_LOG("STARTUP_COMMANDS"); queue.inject_P(PSTR(STARTUP_COMMANDS)); #endif #if ENABLED(INIT_SDCARD_ON_BOOT) && !HAS_SPI_LCD - card.beginautostart(); + SETUP_RUN(card.beginautostart()); #endif #if ENABLED(HOST_PROMPT_SUPPORT) - host_action_prompt_end(); + SETUP_RUN(host_action_prompt_end()); #endif - #if HAS_TRINAMIC && DISABLED(PSU_DEFAULT_OFF) - test_tmc_connection(true, true, true, true); + #if HAS_TRINAMIC_CONFIG && DISABLED(PSU_DEFAULT_OFF) + SETUP_RUN(test_tmc_connection(true, true, true, true)); #endif #if ENABLED(PRUSA_MMU2) - mmu2.init(); + SETUP_RUN(mmu2.init()); #endif - #if HAS_SERVICE_INTERVALS - ui.reset_status(true); // Show service messages or keep current status + #if ENABLED(MAX7219_DEBUG) + SETUP_RUN(max7219.init()); #endif + + SETUP_LOG("setup() completed."); } /** @@ -1182,7 +1201,6 @@ void setup() { */ void loop() { do { - idle(); #if ENABLED(SDSUPPORT) @@ -1195,9 +1213,5 @@ void loop() { endstops.event_handler(); - } while (false // Return to caller for best compatibility - #ifdef __AVR__ - || true // Loop forever on slower (AVR) boards - #endif - ); + } while (ENABLED(__AVR__)); // Loop forever on slower (AVR) boards } diff --git a/Marlin/src/MarlinCore.h b/Marlin/src/MarlinCore.h index 5a8157bde1..141ce7156e 100644 --- a/Marlin/src/MarlinCore.h +++ b/Marlin/src/MarlinCore.h @@ -40,10 +40,18 @@ void stop(); void idle( #if ENABLED(ADVANCED_PAUSE_FEATURE) - bool no_stepper_sleep = false // pass true to keep steppers from disabling on timeout + bool no_stepper_sleep=false // Pass true to keep steppers from timing out #endif ); +inline void idle_no_sleep() { + idle( + #if ENABLED(ADVANCED_PAUSE_FEATURE) + true + #endif + ); +} + #if ENABLED(EXPERIMENTAL_I2CBUS) #include "feature/twibus.h" extern TWIBus i2c; @@ -115,4 +123,6 @@ void protected_pin_err(); #endif extern const char NUL_STR[], M112_KILL_STR[], G28_STR[], M21_STR[], M23_STR[], M24_STR[], - SP_P_STR[], SP_T_STR[], SP_X_STR[], SP_Y_STR[], SP_Z_STR[], SP_E_STR[]; + SP_P_STR[], SP_T_STR[], SP_X_STR[], SP_Y_STR[], SP_Z_STR[], SP_E_STR[], + X_LBL[], Y_LBL[], Z_LBL[], E_LBL[], SP_X_LBL[], SP_Y_LBL[], SP_Z_LBL[], SP_E_LBL[]; + diff --git a/Marlin/src/core/drivers.h b/Marlin/src/core/drivers.h index 306329d6fe..833899bdcb 100644 --- a/Marlin/src/core/drivers.h +++ b/Marlin/src/core/drivers.h @@ -82,97 +82,97 @@ #define _OR_ADTE(N,T) || AXIS_DRIVER_TYPE_E(N,T) #define HAS_E_DRIVER(T) (0 RREPEAT2(E_STEPPERS, _OR_ADTE, T)) -#define HAS_DRIVER(T) ( AXIS_DRIVER_TYPE_X(T) || AXIS_DRIVER_TYPE_X2(T) \ - || AXIS_DRIVER_TYPE_Y(T) || AXIS_DRIVER_TYPE_Y2(T) \ - || AXIS_DRIVER_TYPE_Z(T) || AXIS_DRIVER_TYPE_Z2(T) \ - || AXIS_DRIVER_TYPE_Z3(T) || AXIS_DRIVER_TYPE_Z4(T) \ - || HAS_E_DRIVER(T) ) +#define HAS_DRIVER(T) ( AXIS_DRIVER_TYPE_X(T) || AXIS_DRIVER_TYPE_Y(T) || AXIS_DRIVER_TYPE_Z(T) \ + || AXIS_DRIVER_TYPE_X2(T) || AXIS_DRIVER_TYPE_Y2(T) || AXIS_DRIVER_TYPE_Z2(T) \ + || AXIS_DRIVER_TYPE_Z3(T) || AXIS_DRIVER_TYPE_Z4(T) || HAS_E_DRIVER(T) ) // Test for supported TMC drivers that require advanced configuration // Does not match standalone configurations -#define HAS_TRINAMIC ( HAS_DRIVER(TMC2130) \ - || HAS_DRIVER(TMC2160) \ - || HAS_DRIVER(TMC2208) \ - || HAS_DRIVER(TMC2209) \ - || HAS_DRIVER(TMC2660) \ - || HAS_DRIVER(TMC5130) \ - || HAS_DRIVER(TMC5160) ) +#if ( HAS_DRIVER(TMC2130) || HAS_DRIVER(TMC2160) \ + || HAS_DRIVER(TMC2208) || HAS_DRIVER(TMC2209) \ + || HAS_DRIVER(TMC2660) \ + || HAS_DRIVER(TMC5130) || HAS_DRIVER(TMC5160) ) + #define HAS_TRINAMIC_CONFIG 1 +#endif -#define HAS_TRINAMIC_STANDALONE ( HAS_DRIVER(TMC2130_STANDALONE) \ - || HAS_DRIVER(TMC2208_STANDALONE) \ - || HAS_DRIVER(TMC2209_STANDALONE) \ - || HAS_DRIVER(TMC26X_STANDALONE) \ - || HAS_DRIVER(TMC2660_STANDALONE) \ - || HAS_DRIVER(TMC5130_STANDALONE) \ - || HAS_DRIVER(TMC5160_STANDALONE) \ - || HAS_DRIVER(TMC2160_STANDALONE) ) +#define HAS_TRINAMIC HAS_TRINAMIC_CONFIG -#define HAS_TMCX1X0 ( HAS_DRIVER(TMC2130) || HAS_DRIVER(TMC2160) \ - || HAS_DRIVER(TMC5130) || HAS_DRIVER(TMC5160)) +#if ( HAS_DRIVER(TMC2130_STANDALONE) || HAS_DRIVER(TMC2160_STANDALONE) \ + || HAS_DRIVER(TMC2208_STANDALONE) || HAS_DRIVER(TMC2209_STANDALONE) \ + || HAS_DRIVER(TMC26X_STANDALONE) || HAS_DRIVER(TMC2660_STANDALONE) \ + || HAS_DRIVER(TMC5130_STANDALONE) || HAS_DRIVER(TMC5160_STANDALONE) ) + #define HAS_TRINAMIC_STANDALONE 1 +#endif -#define HAS_TMC220x (HAS_DRIVER(TMC2208) || HAS_DRIVER(TMC2209)) +#if HAS_DRIVER(TMC2130) || HAS_DRIVER(TMC2160) || HAS_DRIVER(TMC5130) || HAS_DRIVER(TMC5160) + #define HAS_TMCX1X0 1 +#endif -#define AXIS_IS_TMC(A) ( AXIS_DRIVER_TYPE(A,TMC2130) \ - || AXIS_DRIVER_TYPE(A,TMC2160) \ - || AXIS_DRIVER_TYPE(A,TMC2208) \ - || AXIS_DRIVER_TYPE(A,TMC2209) \ +#if HAS_DRIVER(TMC2208) || HAS_DRIVER(TMC2209) + #define HAS_TMC220x 1 +#endif + +#define AXIS_IS_TMC(A) ( AXIS_DRIVER_TYPE(A,TMC2130) || AXIS_DRIVER_TYPE(A,TMC2160) \ + || AXIS_DRIVER_TYPE(A,TMC2208) || AXIS_DRIVER_TYPE(A,TMC2209) \ || AXIS_DRIVER_TYPE(A,TMC2660) \ - || AXIS_DRIVER_TYPE(A,TMC5130) \ - || AXIS_DRIVER_TYPE(A,TMC5160) ) + || AXIS_DRIVER_TYPE(A,TMC5130) || AXIS_DRIVER_TYPE(A,TMC5160) ) // Test for a driver that uses SPI - this allows checking whether a _CS_ pin // is considered sensitive -#define AXIS_HAS_SPI(A) ( AXIS_DRIVER_TYPE(A,TMC2130) \ - || AXIS_DRIVER_TYPE(A,TMC2160) \ +#define AXIS_HAS_SPI(A) ( AXIS_DRIVER_TYPE(A,TMC2130) || AXIS_DRIVER_TYPE(A,TMC2160) \ || AXIS_DRIVER_TYPE(A,TMC2660) \ - || AXIS_DRIVER_TYPE(A,TMC5130) \ - || AXIS_DRIVER_TYPE(A,TMC5160) ) + || AXIS_DRIVER_TYPE(A,TMC5130) || AXIS_DRIVER_TYPE(A,TMC5160) ) -#define AXIS_HAS_UART(A) ( AXIS_DRIVER_TYPE(A,TMC2208) \ - || AXIS_DRIVER_TYPE(A,TMC2209) ) +#define AXIS_HAS_UART(A) ( AXIS_DRIVER_TYPE(A,TMC2208) || AXIS_DRIVER_TYPE(A,TMC2209) ) -#define AXIS_HAS_SW_SERIAL(A) ((AXIS_HAS_UART(A) && !defined(A##_HARDWARE_SERIAL))) +#define AXIS_HAS_RXTX AXIS_HAS_UART -#define AXIS_HAS_STALLGUARD(A) ( AXIS_DRIVER_TYPE(A,TMC2130) \ - || AXIS_DRIVER_TYPE(A,TMC2160) \ +#define AXIS_HAS_SW_SERIAL(A) ( AXIS_HAS_UART(A) && !defined(A##_HARDWARE_SERIAL) ) + +#define AXIS_HAS_STALLGUARD(A) ( AXIS_DRIVER_TYPE(A,TMC2130) || AXIS_DRIVER_TYPE(A,TMC2160) \ || AXIS_DRIVER_TYPE(A,TMC2209) \ || AXIS_DRIVER_TYPE(A,TMC2660) \ - || AXIS_DRIVER_TYPE(A,TMC5130) \ - || AXIS_DRIVER_TYPE(A,TMC5160) ) + || AXIS_DRIVER_TYPE(A,TMC5130) || AXIS_DRIVER_TYPE(A,TMC5160) ) -#define AXIS_HAS_STEALTHCHOP(A) ( AXIS_DRIVER_TYPE(A,TMC2130) \ - || AXIS_DRIVER_TYPE(A,TMC2160) \ - || AXIS_DRIVER_TYPE(A,TMC2208) \ - || AXIS_DRIVER_TYPE(A,TMC2209) \ - || AXIS_DRIVER_TYPE(A,TMC5130) \ - || AXIS_DRIVER_TYPE(A,TMC5160) ) +#define AXIS_HAS_STEALTHCHOP(A) ( AXIS_DRIVER_TYPE(A,TMC2130) || AXIS_DRIVER_TYPE(A,TMC2160) \ + || AXIS_DRIVER_TYPE(A,TMC2208) || AXIS_DRIVER_TYPE(A,TMC2209) \ + || AXIS_DRIVER_TYPE(A,TMC5130) || AXIS_DRIVER_TYPE(A,TMC5160) ) -#define AXIS_HAS_SG_RESULT(A) ( AXIS_DRIVER_TYPE(A,TMC2130) \ - || AXIS_DRIVER_TYPE(A,TMC2160) \ - || AXIS_DRIVER_TYPE(A,TMC2208) \ - || AXIS_DRIVER_TYPE(A,TMC2209) ) +#define AXIS_HAS_SG_RESULT(A) ( AXIS_DRIVER_TYPE(A,TMC2130) || AXIS_DRIVER_TYPE(A,TMC2160) \ + || AXIS_DRIVER_TYPE(A,TMC2208) || AXIS_DRIVER_TYPE(A,TMC2209) ) #define AXIS_HAS_COOLSTEP(A) ( AXIS_DRIVER_TYPE(A,TMC2130) \ || AXIS_DRIVER_TYPE(A,TMC2209) \ - || AXIS_DRIVER_TYPE(A,TMC5130) \ - || AXIS_DRIVER_TYPE(A,TMC5160) ) + || AXIS_DRIVER_TYPE(A,TMC5130) || AXIS_DRIVER_TYPE(A,TMC5160) ) #define _OR_EAH(N,T) || AXIS_HAS_##T(E##N) #define E_AXIS_HAS(T) (0 _OR_EAH(0,T) _OR_EAH(1,T) _OR_EAH(2,T) _OR_EAH(3,T) _OR_EAH(4,T) _OR_EAH(5,T) _OR_EAH(6,T) _OR_EAH(7,T)) -#define ANY_AXIS_HAS(T) ( AXIS_HAS_##T(X) || AXIS_HAS_##T(X2) \ - || AXIS_HAS_##T(Y) || AXIS_HAS_##T(Y2) \ - || AXIS_HAS_##T(Z) || AXIS_HAS_##T(Z2) \ - || AXIS_HAS_##T(Z3) || AXIS_HAS_##T(Z4) \ - || E_AXIS_HAS(T) ) +#define ANY_AXIS_HAS(T) ( AXIS_HAS_##T(X) || AXIS_HAS_##T(Y) || AXIS_HAS_##T(Z) \ + || AXIS_HAS_##T(X2) || AXIS_HAS_##T(Y2) || AXIS_HAS_##T(Z2) \ + || AXIS_HAS_##T(Z3) || AXIS_HAS_##T(Z4) || E_AXIS_HAS(T) ) -#define HAS_STEALTHCHOP ANY_AXIS_HAS(STEALTHCHOP) -#define HAS_STALLGUARD ANY_AXIS_HAS(STALLGUARD) -#define HAS_SG_RESULT ANY_AXIS_HAS(SG_RESULT) -#define HAS_COOLSTEP ANY_AXIS_HAS(COOLSTEP) -#define HAS_TMC_UART ANY_AXIS_HAS(UART) -#define HAS_TMC_SPI ANY_AXIS_HAS(SPI) -#define HAS_TMC_SW_SERIAL ANY_AXIS_HAS(SW_SERIAL) +#if ANY_AXIS_HAS(STEALTHCHOP) + #define HAS_STEALTHCHOP 1 +#endif +#if ANY_AXIS_HAS(STALLGUARD) + #define HAS_STALLGUARD 1 +#endif +#if ANY_AXIS_HAS(SG_RESULT) + #define HAS_SG_RESULT 1 +#endif +#if ANY_AXIS_HAS(COOLSTEP) + #define HAS_COOLSTEP 1 +#endif +#if ANY_AXIS_HAS(RXTX) + #define HAS_TMC_UART 1 +#endif +#if ANY_AXIS_HAS(SPI) + #define HAS_TMC_SPI 1 +#endif + +// Defines that can't be evaluated now +#define HAS_TMC_SW_SERIAL ANY_AXIS_HAS(SW_SERIAL) // // Stretching 'drivers.h' to include LPC/SAMD51 SD options @@ -183,7 +183,11 @@ #define _SDCARD_ID(V) _CAT(_SDCARD_, V) #define SD_CONNECTION_IS(V) (_SDCARD_ID(SDCARD_CONNECTION) == _SDCARD_ID(V)) -#define HAS_L64XX (HAS_DRIVER(L6470) || HAS_DRIVER(L6474) || HAS_DRIVER(L6480) || HAS_DRIVER(POWERSTEP01)) -#define HAS_L64XX_NOT_L6474 (HAS_L64XX && !HAS_DRIVER(L6474)) +#if HAS_DRIVER(L6470) || HAS_DRIVER(L6474) || HAS_DRIVER(L6480) || HAS_DRIVER(POWERSTEP01) + #define HAS_L64XX 1 +#endif +#if HAS_L64XX && !HAS_DRIVER(L6474) + #define HAS_L64XX_NOT_L6474 1 +#endif #define AXIS_IS_L64XX(A) (AXIS_DRIVER_TYPE_##A(L6470) || AXIS_DRIVER_TYPE_##A(L6474) || AXIS_DRIVER_TYPE_##A(L6480) || AXIS_DRIVER_TYPE_##A(POWERSTEP01)) diff --git a/Marlin/src/core/macros.h b/Marlin/src/core/macros.h index 5e0797d67c..56ec11bd7c 100644 --- a/Marlin/src/core/macros.h +++ b/Marlin/src/core/macros.h @@ -177,18 +177,23 @@ // Macros to support option testing #define _CAT(a,V...) a##V #define CAT(a,V...) _CAT(a,V) -#define SWITCH_ENABLED_false 0 -#define SWITCH_ENABLED_true 1 -#define SWITCH_ENABLED_0 0 -#define SWITCH_ENABLED_1 1 -#define SWITCH_ENABLED_0x0 0 -#define SWITCH_ENABLED_0x1 1 -#define SWITCH_ENABLED_ 1 -#define _ENA_1(O) _CAT(SWITCH_ENABLED_, O) -#define _DIS_1(O) !_ENA_1(O) + +#define _ISENA_ ~,1 +#define _ISENA_1 ~,1 +#define _ISENA_0x1 ~,1 +#define _ISENA_true ~,1 +#define _ISENA(V...) IS_PROBE(V) + +#define _ENA_1(O) _ISENA(CAT(_IS,CAT(ENA_, O))) +#define _DIS_1(O) NOT(_ENA_1(O)) #define ENABLED(V...) DO(ENA,&&,V) #define DISABLED(V...) DO(DIS,&&,V) +#define TERN(O,A,B) _TERN(_ENA_1(O),B,A) // OPTION converted to '0' or '1' +#define _TERN(E,V...) __TERN(_CAT(T_,E),V) // Prepend 'T_' to get 'T_0' or 'T_1' +#define __TERN(T,V...) ___TERN(_CAT(_NO,T),V) // Prepend '_NO' to get '_NOT_0' or '_NOT_1' +#define ___TERN(P,V...) THIRD(P,V) // If first argument has a comma, A. Else B. + #define ANY(V...) !DISABLED(V) #define NONE(V...) DISABLED(V) #define ALL(V...) ENABLED(V) @@ -243,6 +248,11 @@ #define _JOIN_1(O) (O) #define JOIN_N(N,C,V...) (DO(JOIN,C,LIST_N(N,V))) +#define LOOP_S_LE_N(VAR, S, N) for (uint8_t VAR=(S); VAR<=(N); VAR++) +#define LOOP_S_L_N(VAR, S, N) for (uint8_t VAR=(S); VAR<(N); VAR++) +#define LOOP_LE_N(VAR, N) LOOP_S_LE_N(VAR, 0, N) +#define LOOP_L_N(VAR, N) LOOP_S_L_N(VAR, 0, N) + #define NOOP (void(0)) #define CEILING(x,y) (((x) + (y) - 1) / (y)) @@ -390,8 +400,9 @@ // // Primitives supporting precompiler REPEAT // -#define FIRST(a,...) a -#define SECOND(a,b,...) b +#define FIRST(a,...) a +#define SECOND(a,b,...) b +#define THIRD(a,b,c,...) c // Defer expansion #define EMPTY() @@ -473,7 +484,7 @@ ( DEFER2(__RREPEAT2)()(ADD1(_RPT_I),SUB1(_RPT_N),_RPT_OP,V) ) \ ( /* Do nothing */ ) #define __RREPEAT2() _RREPEAT2 -#define RREPEAT_S(S,N,OP) EVAL(_RREPEAT(S,SUB##S(N),OP)) +#define RREPEAT_S(S,N,OP) EVAL1024(_RREPEAT(S,SUB##S(N),OP)) #define RREPEAT(N,OP) RREPEAT_S(0,N,OP) -#define RREPEAT2_S(S,N,OP,V...) EVAL(_RREPEAT2(S,SUB##S(N),OP,V)) +#define RREPEAT2_S(S,N,OP,V...) EVAL1024(_RREPEAT2(S,SUB##S(N),OP,V)) #define RREPEAT2(N,OP,V...) RREPEAT2_S(0,N,OP,V) diff --git a/Marlin/src/core/types.h b/Marlin/src/core/types.h index d563963cf7..1212eb5ba2 100644 --- a/Marlin/src/core/types.h +++ b/Marlin/src/core/types.h @@ -24,7 +24,7 @@ #include #include -#include "millis_t.h" +#include "../inc/MarlinConfigPre.h" class __FlashStringHelper; typedef const __FlashStringHelper *progmem_str; @@ -50,12 +50,6 @@ enum AxisEnum : uint8_t { // // Loop over XYZE axes // - -#define LOOP_S_LE_N(VAR, S, N) for (uint8_t VAR=(S); VAR<=(N); VAR++) -#define LOOP_S_L_N(VAR, S, N) for (uint8_t VAR=(S); VAR<(N); VAR++) -#define LOOP_LE_N(VAR, N) LOOP_S_LE_N(VAR, 0, N) -#define LOOP_L_N(VAR, N) LOOP_S_L_N(VAR, 0, N) - #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) @@ -187,6 +181,12 @@ struct XYval { }; FI void set(const T px) { x = px; } FI void set(const T px, const T py) { x = px; y = py; } + 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]; } + #endif FI void reset() { x = y = 0; } FI T magnitude() const { return (T)sqrtf(x*x + y*y); } FI operator T* () { return pos; } @@ -197,6 +197,8 @@ struct XYval { FI XYval asInt() const { return { int16_t(x), int16_t(y) }; } FI XYval asLong() { return { int32_t(x), int32_t(y) }; } FI XYval asLong() const { return { int32_t(x), int32_t(y) }; } + FI XYval ROUNDL() { return { int32_t(LROUND(x)), int32_t(LROUND(y)) }; } + FI XYval ROUNDL() const { return { int32_t(LROUND(x)), int32_t(LROUND(y)) }; } FI XYval asFloat() { return { float(x), float(y) }; } FI XYval asFloat() const { return { float(x), float(y) }; } FI XYval reciprocal() const { return { _RECIP(x), _RECIP(y) }; } @@ -290,6 +292,12 @@ struct XYZval { FI void set(const T px, const T py) { x = px; y = py; } FI void set(const T px, const T py, const T pz) { x = px; y = py; z = pz; } FI void set(const XYval pxy, const T pz) { x = pxy.x; y = pxy.y; z = pz; } + 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]; } + #endif FI void reset() { x = y = z = 0; } FI T magnitude() const { return (T)sqrtf(x*x + y*y + z*z); } FI operator T* () { return pos; } @@ -300,6 +308,8 @@ struct XYZval { FI XYZval asInt() const { return { int16_t(x), int16_t(y), int16_t(z) }; } FI XYZval asLong() { return { int32_t(x), int32_t(y), int32_t(z) }; } FI XYZval asLong() const { return { int32_t(x), int32_t(y), int32_t(z) }; } + FI XYZval ROUNDL() { return { int32_t(LROUND(x)), int32_t(LROUND(y)), int32_t(LROUND(z)) }; } + FI XYZval ROUNDL() const { return { int32_t(LROUND(x)), int32_t(LROUND(y)), int32_t(LROUND(z)) }; } FI XYZval asFloat() { return { float(x), float(y), float(z) }; } FI XYZval asFloat() const { return { float(x), float(y), float(z) }; } FI XYZval reciprocal() const { return { _RECIP(x), _RECIP(y), _RECIP(z) }; } @@ -397,12 +407,20 @@ struct XYZEval { FI void set(const XYval pxy, const T pz, const T pe) { x = pxy.x; y = pxy.y; z = pz; e = pe; } FI void set(const XYval pxy, const XYval pze) { x = pxy.x; y = pxy.y; z = pze.z; e = pze.e; } FI void set(const XYZval pxyz, const T pe) { x = pxyz.x; y = pxyz.y; z = pxyz.z; e = pe; } + 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]; } + #endif FI XYZEval copy() const { return *this; } FI XYZEval ABS() const { return { T(_ABS(x)), T(_ABS(y)), T(_ABS(z)), T(_ABS(e)) }; } FI XYZEval asInt() { return { int16_t(x), int16_t(y), int16_t(z), int16_t(e) }; } FI XYZEval asInt() const { return { int16_t(x), int16_t(y), int16_t(z), int16_t(e) }; } - FI XYZEval asLong() const { return { int32_t(x), int32_t(y), int32_t(z), int32_t(e) }; } FI XYZEval asLong() { return { int32_t(x), int32_t(y), int32_t(z), int32_t(e) }; } + FI XYZEval asLong() const { return { int32_t(x), int32_t(y), int32_t(z), int32_t(e) }; } + FI XYZEval ROUNDL() { return { int32_t(LROUND(x)), int32_t(LROUND(y)), int32_t(LROUND(z)), int32_t(LROUND(e)) }; } + FI XYZEval ROUNDL() const { return { int32_t(LROUND(x)), int32_t(LROUND(y)), int32_t(LROUND(z)), int32_t(LROUND(e)) }; } FI XYZEval asFloat() { return { float(x), float(y), float(z), float(e) }; } FI XYZEval asFloat() const { return { float(x), float(y), float(z), float(e) }; } FI XYZEval reciprocal() const { return { _RECIP(x), _RECIP(y), _RECIP(z), _RECIP(e) }; } @@ -483,3 +501,4 @@ struct XYZEval { #undef FI const xyze_char_t axis_codes { 'X', 'Y', 'Z', 'E' }; +#define XYZ_CHAR(A) ('X' + char(A)) diff --git a/Marlin/src/core/utility.cpp b/Marlin/src/core/utility.cpp index 64783d070f..19247ff69f 100644 --- a/Marlin/src/core/utility.cpp +++ b/Marlin/src/core/utility.cpp @@ -57,39 +57,23 @@ void safe_delay(millis_t ms) { void log_machine_info() { SERIAL_ECHOLNPGM("Machine Type: " - #if ENABLED(DELTA) - "Delta" - #elif IS_SCARA - "SCARA" - #elif IS_CORE - "Core" - #else - "Cartesian" - #endif + TERN(DELTA, "Delta", "") + TERN(IS_SCARA, "SCARA", "") + TERN(IS_CORE, "Core", "") + TERN(IS_CARTESIAN, "Cartesian", "") ); SERIAL_ECHOLNPGM("Probe: " - #if ENABLED(PROBE_MANUALLY) - "PROBE_MANUALLY" - #elif ENABLED(NOZZLE_AS_PROBE) - "NOZZLE_AS_PROBE" - #elif ENABLED(FIX_MOUNTED_PROBE) - "FIX_MOUNTED_PROBE" - #elif ENABLED(BLTOUCH) - "BLTOUCH" - #elif HAS_Z_SERVO_PROBE - "SERVO PROBE" - #elif ENABLED(TOUCH_MI_PROBE) - "TOUCH_MI_PROBE" - #elif ENABLED(Z_PROBE_SLED) - "Z_PROBE_SLED" - #elif ENABLED(Z_PROBE_ALLEN_KEY) - "Z_PROBE_ALLEN_KEY" - #elif ENABLED(SOLENOID_PROBE) - "SOLENOID_PROBE" - #else - "NONE" - #endif + TERN(PROBE_MANUALLY, "PROBE_MANUALLY", "") + TERN(NOZZLE_AS_PROBE, "NOZZLE_AS_PROBE", "") + TERN(FIX_MOUNTED_PROBE, "FIX_MOUNTED_PROBE", "") + TERN(BLTOUCH, "BLTOUCH", "") + TERN(HAS_Z_SERVO_PROBE, TERN(BLTOUCH, "BLTOUCH", "SERVO PROBE"), "") + TERN(TOUCH_MI_PROBE, "TOUCH_MI_PROBE", "") + TERN(Z_PROBE_SLED, "Z_PROBE_SLED", "") + TERN(Z_PROBE_ALLEN_KEY, "Z_PROBE_ALLEN_KEY", "") + TERN(SOLENOID_PROBE, "SOLENOID_PROBE", "") + TERN(PROBE_SELECTED, "", "NONE") ); #if HAS_BED_PROBE @@ -107,20 +91,10 @@ void safe_delay(millis_t ms) { else SERIAL_ECHOPGM(" (Aligned With"); - if (probe.offset_xy.y > 0) { - #if IS_SCARA - SERIAL_ECHOPGM("-Distal"); - #else - SERIAL_ECHOPGM("-Back"); - #endif - } - else if (probe.offset_xy.y < 0) { - #if IS_SCARA - SERIAL_ECHOPGM("-Proximal"); - #else - SERIAL_ECHOPGM("-Front"); - #endif - } + if (probe.offset_xy.y > 0) + serialprintPGM(ENABLED(IS_SCARA) ? PSTR("-Distal") : PSTR("-Back")); + else if (probe.offset_xy.y < 0) + serialprintPGM(ENABLED(IS_SCARA) ? PSTR("-Proximal") : PSTR("-Front")); else if (probe.offset_xy.x != 0) SERIAL_ECHOPGM("-Center"); @@ -128,28 +102,19 @@ void safe_delay(millis_t ms) { #endif - if (probe.offset.z < 0) - SERIAL_ECHOPGM("Below"); - else if (probe.offset.z > 0) - SERIAL_ECHOPGM("Above"); - else - SERIAL_ECHOPGM("Same Z as"); + serialprintPGM(probe.offset.z < 0 ? PSTR("Below") : probe.offset.z > 0 ? PSTR("Above") : PSTR("Same Z as")); SERIAL_ECHOLNPGM(" Nozzle)"); #endif #if HAS_ABL_OR_UBL - SERIAL_ECHOLNPGM("Auto Bed Leveling: " - #if ENABLED(AUTO_BED_LEVELING_LINEAR) - "LINEAR" - #elif ENABLED(AUTO_BED_LEVELING_BILINEAR) - "BILINEAR" - #elif ENABLED(AUTO_BED_LEVELING_3POINT) - "3POINT" - #elif ENABLED(AUTO_BED_LEVELING_UBL) - "UBL" - #endif + SERIAL_ECHOPGM("Auto Bed Leveling: " + TERN(AUTO_BED_LEVELING_LINEAR, "LINEAR", "") + TERN(AUTO_BED_LEVELING_BILINEAR, "BILINEAR", "") + TERN(AUTO_BED_LEVELING_3POINT, "3POINT", "") + TERN(AUTO_BED_LEVELING_UBL, "UBL", "") ); + if (planner.leveling_active) { SERIAL_ECHOLNPGM(" (enabled)"); #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) @@ -160,7 +125,7 @@ void safe_delay(millis_t ms) { SERIAL_ECHOPGM("ABL Adjustment X"); LOOP_XYZ(a) { float v = planner.get_axis_position_mm(AxisEnum(a)) - current_position[a]; - SERIAL_CHAR(' ', 'X' + char(a)); + SERIAL_CHAR(' ', XYZ_CHAR(a)); if (v > 0) SERIAL_CHAR('+'); SERIAL_ECHO(v); } diff --git a/Marlin/src/core/utility.h b/Marlin/src/core/utility.h index e34f9dd58a..0c2e91d31f 100644 --- a/Marlin/src/core/utility.h +++ b/Marlin/src/core/utility.h @@ -23,6 +23,7 @@ #include "../inc/MarlinConfigPre.h" #include "../core/types.h" +#include "../core/millis_t.h" // Delay that ensures heaters and watchdog are kept alive void safe_delay(millis_t ms); @@ -70,7 +71,7 @@ public: inline void restore() { ref_ = val_; } }; -#define REMEMBER(N,X,V...) const restorer restorer_##N(X, ##V) +#define REMEMBER(N,X,V...) restorer restorer_##N(X, ##V) #define RESTORE(N) restorer_##N.restore() // Converts from an uint8_t in the range of 0-255 to an uint8_t diff --git a/Marlin/src/feature/babystep.cpp b/Marlin/src/feature/babystep.cpp index bf9e9a78b5..5d2dc47bee 100644 --- a/Marlin/src/feature/babystep.cpp +++ b/Marlin/src/feature/babystep.cpp @@ -55,14 +55,7 @@ void Babystep::add_mm(const AxisEnum axis, const float &mm) { void Babystep::add_steps(const AxisEnum axis, const int16_t distance) { - #if ENABLED(BABYSTEP_WITHOUT_HOMING) - #define CAN_BABYSTEP(AXIS) true - #else - extern uint8_t axis_known_position; - #define CAN_BABYSTEP(AXIS) TEST(axis_known_position, AXIS) - #endif - - if (!CAN_BABYSTEP(axis)) return; + if (DISABLED(BABYSTEP_WITHOUT_HOMING) && !TEST(axis_known_position, axis)) return; accum += distance; // Count up babysteps for the UI #if ENABLED(BABYSTEP_DISPLAY_TOTAL) diff --git a/Marlin/src/feature/bedlevel/abl/abl.cpp b/Marlin/src/feature/bedlevel/abl/abl.cpp index 74821ba2ec..33c9cbdfde 100644 --- a/Marlin/src/feature/bedlevel/abl/abl.cpp +++ b/Marlin/src/feature/bedlevel/abl/abl.cpp @@ -32,7 +32,7 @@ #include "../../../core/debug_out.h" #if ENABLED(EXTENSIBLE_UI) - #include "../../../lcd/extensible_ui/ui_api.h" + #include "../../../lcd/extui/ui_api.h" #endif xy_pos_t bilinear_grid_spacing, bilinear_start; @@ -115,8 +115,8 @@ void extrapolate_unprobed_bed_level() { ylen = ctry1; #endif - for (uint8_t xo = 0; xo <= xlen; xo++) - for (uint8_t yo = 0; yo <= ylen; yo++) { + LOOP_LE_N(xo, xlen) + LOOP_LE_N(yo, ylen) { uint8_t x2 = ctrx2 + xo, y2 = ctry2 + yo; #ifndef HALF_IN_X const uint8_t x1 = ctrx1 - xo; @@ -209,8 +209,8 @@ void print_bilinear_leveling_grid() { static float bed_level_virt_2cmr(const uint8_t x, const uint8_t y, const float &tx, const float &ty) { float row[4], column[4]; - for (uint8_t i = 0; i < 4; i++) { - for (uint8_t j = 0; j < 4; j++) { + LOOP_L_N(i, 4) { + LOOP_L_N(j, 4) { column[j] = bed_level_virt_coord(i + x - 1, j + y - 1); } row[i] = bed_level_virt_cmr(column, 1, ty); @@ -221,11 +221,11 @@ void print_bilinear_leveling_grid() { void bed_level_virt_interpolate() { bilinear_grid_spacing_virt = bilinear_grid_spacing / (BILINEAR_SUBDIVISIONS); bilinear_grid_factor_virt = bilinear_grid_spacing_virt.reciprocal(); - for (uint8_t y = 0; y < GRID_MAX_POINTS_Y; y++) - for (uint8_t x = 0; x < GRID_MAX_POINTS_X; x++) - for (uint8_t ty = 0; ty < BILINEAR_SUBDIVISIONS; ty++) - for (uint8_t tx = 0; tx < BILINEAR_SUBDIVISIONS; tx++) { - if ((ty && y == GRID_MAX_POINTS_Y - 1) || (tx && x == GRID_MAX_POINTS_X - 1)) + LOOP_L_N(y, GRID_MAX_POINTS_Y) + LOOP_L_N(x, GRID_MAX_POINTS_X) + LOOP_L_N(ty, BILINEAR_SUBDIVISIONS) + LOOP_L_N(tx, BILINEAR_SUBDIVISIONS) { + if ((ty && y == (GRID_MAX_POINTS_Y) - 1) || (tx && x == (GRID_MAX_POINTS_X) - 1)) continue; z_values_virt[x * (BILINEAR_SUBDIVISIONS) + tx][y * (BILINEAR_SUBDIVISIONS) + ty] = bed_level_virt_2cmr( diff --git a/Marlin/src/feature/bedlevel/bedlevel.cpp b/Marlin/src/feature/bedlevel/bedlevel.cpp index f302d172bf..63493712a8 100644 --- a/Marlin/src/feature/bedlevel/bedlevel.cpp +++ b/Marlin/src/feature/bedlevel/bedlevel.cpp @@ -43,7 +43,7 @@ #include "../../core/debug_out.h" #if ENABLED(EXTENSIBLE_UI) - #include "../../lcd/extensible_ui/ui_api.h" + #include "../../lcd/extui/ui_api.h" #endif bool leveling_is_valid() { @@ -143,13 +143,12 @@ void reset_bed_level() { #elif ENABLED(AUTO_BED_LEVELING_BILINEAR) bilinear_start.reset(); bilinear_grid_spacing.reset(); - for (uint8_t x = 0; x < GRID_MAX_POINTS_X; x++) - for (uint8_t y = 0; y < GRID_MAX_POINTS_Y; y++) { - z_values[x][y] = NAN; - #if ENABLED(EXTENSIBLE_UI) - ExtUI::onMeshUpdate(x, y, 0); - #endif - } + GRID_LOOP(x, y) { + z_values[x][y] = NAN; + #if ENABLED(EXTENSIBLE_UI) + ExtUI::onMeshUpdate(x, y, 0); + #endif + } #elif ABL_PLANAR planner.bed_level_matrix.set_to_identity(); #endif @@ -173,7 +172,7 @@ void reset_bed_level() { */ void print_2d_array(const uint8_t sx, const uint8_t sy, const uint8_t precision, element_2d_fn fn) { #ifndef SCAD_MESH_OUTPUT - for (uint8_t x = 0; x < sx; x++) { + LOOP_L_N(x, sx) { serial_spaces(precision + (x < 10 ? 3 : 2)); SERIAL_ECHO(int(x)); } @@ -182,14 +181,14 @@ void reset_bed_level() { #ifdef SCAD_MESH_OUTPUT SERIAL_ECHOLNPGM("measured_z = ["); // open 2D array #endif - for (uint8_t y = 0; y < sy; y++) { + LOOP_L_N(y, sy) { #ifdef SCAD_MESH_OUTPUT SERIAL_ECHOPGM(" ["); // open sub-array #else if (y < 10) SERIAL_CHAR(' '); SERIAL_ECHO(int(y)); #endif - for (uint8_t x = 0; x < sx; x++) { + LOOP_L_N(x, sx) { SERIAL_CHAR(' '); const float offset = fn(x, y); if (!isnan(offset)) { @@ -202,7 +201,7 @@ void reset_bed_level() { SERIAL_CHAR(' '); SERIAL_ECHOPGM("NAN"); #else - for (uint8_t i = 0; i < precision + 3; i++) + LOOP_L_N(i, precision + 3) SERIAL_CHAR(i ? '=' : ' '); #endif } diff --git a/Marlin/src/feature/bedlevel/mbl/mesh_bed_leveling.cpp b/Marlin/src/feature/bedlevel/mbl/mesh_bed_leveling.cpp index e80b9e9d2f..7439c3fcd3 100644 --- a/Marlin/src/feature/bedlevel/mbl/mesh_bed_leveling.cpp +++ b/Marlin/src/feature/bedlevel/mbl/mesh_bed_leveling.cpp @@ -29,7 +29,7 @@ #include "../../../module/motion.h" #if ENABLED(EXTENSIBLE_UI) - #include "../../../lcd/extensible_ui/ui_api.h" + #include "../../../lcd/extui/ui_api.h" #endif mesh_bed_leveling mbl; @@ -40,9 +40,9 @@ mesh_bed_leveling::index_to_ypos[GRID_MAX_POINTS_Y]; mesh_bed_leveling::mesh_bed_leveling() { - for (uint8_t i = 0; i < GRID_MAX_POINTS_X; ++i) + LOOP_L_N(i, GRID_MAX_POINTS_X) index_to_xpos[i] = MESH_MIN_X + i * (MESH_X_DIST); - for (uint8_t i = 0; i < GRID_MAX_POINTS_Y; ++i) + LOOP_L_N(i, GRID_MAX_POINTS_Y) index_to_ypos[i] = MESH_MIN_Y + i * (MESH_Y_DIST); reset(); } @@ -51,9 +51,7 @@ z_offset = 0; ZERO(z_values); #if ENABLED(EXTENSIBLE_UI) - for (uint8_t x = 0; x < GRID_MAX_POINTS_X; x++) - for (uint8_t y = 0; y < GRID_MAX_POINTS_Y; y++) - ExtUI::onMeshUpdate(x, y, 0); + GRID_LOOP(x, y) ExtUI::onMeshUpdate(x, y, 0); #endif } diff --git a/Marlin/src/feature/bedlevel/mbl/mesh_bed_leveling.h b/Marlin/src/feature/bedlevel/mbl/mesh_bed_leveling.h index 4c8773107f..3a1cbaccb0 100644 --- a/Marlin/src/feature/bedlevel/mbl/mesh_bed_leveling.h +++ b/Marlin/src/feature/bedlevel/mbl/mesh_bed_leveling.h @@ -52,9 +52,7 @@ public: static void reset(); FORCE_INLINE static bool has_mesh() { - for (uint8_t x = 0; x < GRID_MAX_POINTS_X; x++) - for (uint8_t y = 0; y < GRID_MAX_POINTS_Y; y++) - if (z_values[x][y]) return true; + GRID_LOOP(x, y) if (z_values[x][y]) return true; return false; } diff --git a/Marlin/src/feature/bedlevel/ubl/ubl.cpp b/Marlin/src/feature/bedlevel/ubl/ubl.cpp index f1a6706133..8ef2ad564c 100644 --- a/Marlin/src/feature/bedlevel/ubl/ubl.cpp +++ b/Marlin/src/feature/bedlevel/ubl/ubl.cpp @@ -37,7 +37,7 @@ #include "../../../module/probe.h" #if ENABLED(EXTENSIBLE_UI) - #include "../../../lcd/extensible_ui/ui_api.h" + #include "../../../lcd/extui/ui_api.h" #endif #include "math.h" @@ -49,7 +49,7 @@ void unified_bed_leveling::report_current_mesh() { if (!leveling_is_valid()) return; SERIAL_ECHO_MSG(" G29 I99"); - for (uint8_t x = 0; x < GRID_MAX_POINTS_X; x++) + LOOP_L_N(x, GRID_MAX_POINTS_X) for (uint8_t y = 0; y < GRID_MAX_POINTS_Y; y++) if (!isnan(z_values[x][y])) { SERIAL_ECHO_START(); @@ -101,9 +101,7 @@ storage_slot = -1; ZERO(z_values); #if ENABLED(EXTENSIBLE_UI) - for (uint8_t x = 0; x < GRID_MAX_POINTS_X; x++) - for (uint8_t y = 0; y < GRID_MAX_POINTS_Y; y++) - ExtUI::onMeshUpdate(x, y, 0); + GRID_LOOP(x, y) ExtUI::onMeshUpdate(x, y, 0); #endif if (was_enabled) report_current_position(); } @@ -114,13 +112,11 @@ } void unified_bed_leveling::set_all_mesh_points_to_value(const float value) { - for (uint8_t x = 0; x < GRID_MAX_POINTS_X; x++) { - for (uint8_t y = 0; y < GRID_MAX_POINTS_Y; y++) { - z_values[x][y] = value; - #if ENABLED(EXTENSIBLE_UI) - ExtUI::onMeshUpdate(x, y, value); - #endif - } + GRID_LOOP(x, y) { + z_values[x][y] = value; + #if ENABLED(EXTENSIBLE_UI) + ExtUI::onMeshUpdate(x, y, value); + #endif } } @@ -190,7 +186,7 @@ } // Row Values (I indexes) - for (uint8_t i = 0; i < GRID_MAX_POINTS_X; i++) { + LOOP_L_N(i, GRID_MAX_POINTS_X) { // Opening Brace or Space const bool is_current = i == curr.x && j == curr.y; diff --git a/Marlin/src/feature/bedlevel/ubl/ubl.h b/Marlin/src/feature/bedlevel/ubl/ubl.h index 370d792fc5..9e227f02d9 100644 --- a/Marlin/src/feature/bedlevel/ubl/ubl.h +++ b/Marlin/src/feature/bedlevel/ubl/ubl.h @@ -298,9 +298,7 @@ class unified_bed_leveling { #endif static inline bool mesh_is_valid() { - for (uint8_t x = 0; x < GRID_MAX_POINTS_X; x++) - for (uint8_t y = 0; y < GRID_MAX_POINTS_Y; y++) - if (isnan(z_values[x][y])) return false; + GRID_LOOP(x, y) if (isnan(z_values[x][y])) return false; return true; } diff --git a/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp b/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp index a0a12ea621..1aad462f16 100644 --- a/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp +++ b/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp @@ -46,7 +46,7 @@ #include "../../../core/debug_out.h" #if ENABLED(EXTENSIBLE_UI) - #include "../../../lcd/extensible_ui/ui_api.h" + #include "../../../lcd/extui/ui_api.h" #endif #include @@ -365,25 +365,23 @@ #endif case 0: - for (uint8_t x = 0; x < GRID_MAX_POINTS_X; x++) { // Create a bowl shape - similar to - for (uint8_t y = 0; y < GRID_MAX_POINTS_Y; y++) { // a poorly calibrated Delta. - const float p1 = 0.5f * (GRID_MAX_POINTS_X) - x, - p2 = 0.5f * (GRID_MAX_POINTS_Y) - y; - z_values[x][y] += 2.0f * HYPOT(p1, p2); - #if ENABLED(EXTENSIBLE_UI) - ExtUI::onMeshUpdate(x, y, z_values[x][y]); - #endif - } + GRID_LOOP(x, y) { // Create a bowl shape similar to a poorly-calibrated Delta + const float p1 = 0.5f * (GRID_MAX_POINTS_X) - x, + p2 = 0.5f * (GRID_MAX_POINTS_Y) - y; + z_values[x][y] += 2.0f * HYPOT(p1, p2); + #if ENABLED(EXTENSIBLE_UI) + ExtUI::onMeshUpdate(x, y, z_values[x][y]); + #endif } break; case 1: - for (uint8_t x = 0; x < GRID_MAX_POINTS_X; x++) { // Create a diagonal line several Mesh cells thick that is raised + LOOP_L_N(x, GRID_MAX_POINTS_X) { // Create a diagonal line several Mesh cells thick that is raised z_values[x][x] += 9.999f; - z_values[x][x + (x < GRID_MAX_POINTS_Y - 1) ? 1 : -1] += 9.999f; // We want the altered line several mesh points thick + z_values[x][x + (x < (GRID_MAX_POINTS_Y) - 1) ? 1 : -1] += 9.999f; // We want the altered line several mesh points thick #if ENABLED(EXTENSIBLE_UI) ExtUI::onMeshUpdate(x, x, z_values[x][x]); - ExtUI::onMeshUpdate(x, (x + (x < GRID_MAX_POINTS_Y - 1) ? 1 : -1), z_values[x][x + (x < GRID_MAX_POINTS_Y - 1) ? 1 : -1]); + ExtUI::onMeshUpdate(x, (x + (x < (GRID_MAX_POINTS_Y) - 1) ? 1 : -1), z_values[x][x + (x < (GRID_MAX_POINTS_Y) - 1) ? 1 : -1]); #endif } @@ -467,7 +465,7 @@ // // Manually Probe Mesh in areas that can't be reached by the probe // - SERIAL_ECHOLNPGM("Manually probing unreachable mesh locations."); + SERIAL_ECHOLNPGM("Manually probing unreachable points."); do_blocking_move_to_z(Z_CLEARANCE_BETWEEN_PROBES); if (parser.seen('C') && !xy_seen) { @@ -537,9 +535,7 @@ if (cpos.x < 0) { // No more REAL INVALID mesh points to populate, so we ASSUME // user meant to populate ALL INVALID mesh points to value - for (uint8_t x = 0; x < GRID_MAX_POINTS_X; x++) - for (uint8_t y = 0; y < GRID_MAX_POINTS_Y; y++) - if (isnan(z_values[x][y])) z_values[x][y] = g29_constant; + GRID_LOOP(x, y) if (isnan(z_values[x][y])) z_values[x][y] = g29_constant; break; // No more invalid Mesh Points to populate } else { @@ -696,12 +692,11 @@ void unified_bed_leveling::adjust_mesh_to_mean(const bool cflag, const float value) { float sum = 0; int n = 0; - for (uint8_t x = 0; x < GRID_MAX_POINTS_X; x++) - for (uint8_t y = 0; y < GRID_MAX_POINTS_Y; y++) - if (!isnan(z_values[x][y])) { - sum += z_values[x][y]; - n++; - } + GRID_LOOP(x, y) + if (!isnan(z_values[x][y])) { + sum += z_values[x][y]; + n++; + } const float mean = sum / n; @@ -709,10 +704,9 @@ // Sum the squares of difference from mean // float sum_of_diff_squared = 0; - for (uint8_t x = 0; x < GRID_MAX_POINTS_X; x++) - for (uint8_t y = 0; y < GRID_MAX_POINTS_Y; y++) - if (!isnan(z_values[x][y])) - sum_of_diff_squared += sq(z_values[x][y] - mean); + GRID_LOOP(x, y) + if (!isnan(z_values[x][y])) + sum_of_diff_squared += sq(z_values[x][y] - mean); SERIAL_ECHOLNPAIR("# of samples: ", n); SERIAL_ECHOLNPAIR_F("Mean Mesh Height: ", mean, 6); @@ -721,27 +715,25 @@ SERIAL_ECHOLNPAIR_F("Standard Deviation: ", sigma, 6); if (cflag) - for (uint8_t x = 0; x < GRID_MAX_POINTS_X; x++) - for (uint8_t y = 0; y < GRID_MAX_POINTS_Y; y++) - if (!isnan(z_values[x][y])) { - z_values[x][y] -= mean + value; - #if ENABLED(EXTENSIBLE_UI) - ExtUI::onMeshUpdate(x, y, z_values[x][y]); - #endif - } - } - - void unified_bed_leveling::shift_mesh_height() { - for (uint8_t x = 0; x < GRID_MAX_POINTS_X; x++) - for (uint8_t y = 0; y < GRID_MAX_POINTS_Y; y++) + GRID_LOOP(x, y) if (!isnan(z_values[x][y])) { - z_values[x][y] += g29_constant; + z_values[x][y] -= mean + value; #if ENABLED(EXTENSIBLE_UI) ExtUI::onMeshUpdate(x, y, z_values[x][y]); #endif } } + void unified_bed_leveling::shift_mesh_height() { + GRID_LOOP(x, y) + if (!isnan(z_values[x][y])) { + z_values[x][y] += g29_constant; + #if ENABLED(EXTENSIBLE_UI) + ExtUI::onMeshUpdate(x, y, z_values[x][y]); + #endif + } + } + #if HAS_BED_PROBE /** * Probe all invalidated locations of the mesh that can be reached by the probe. @@ -1243,52 +1235,46 @@ mesh_index_pair farthest { -1, -1, -99999.99 }; - for (int8_t i = 0; i < GRID_MAX_POINTS_X; i++) { - for (int8_t j = 0; j < GRID_MAX_POINTS_Y; j++) { + GRID_LOOP(i, j) { + if (!isnan(z_values[i][j])) continue; // Skip valid mesh points - if (isnan(z_values[i][j])) { // Invalid mesh point? + // Skip unreachable points + if (!probe.can_reach(mesh_index_to_xpos(i), mesh_index_to_ypos(j))) + continue; - // Skip points the probe can't reach - if (!position_is_reachable_by_probe(mesh_index_to_xpos(i), mesh_index_to_ypos(j))) - continue; + found_a_NAN = true; - found_a_NAN = true; + xy_int8_t near { -1, -1 }; + float d1, d2 = 99999.9f; + GRID_LOOP(k, l) { + if (isnan(z_values[k][l])) continue; - xy_int8_t near { -1, -1 }; - float d1, d2 = 99999.9f; - for (int8_t k = 0; k < GRID_MAX_POINTS_X; k++) { - for (int8_t l = 0; l < GRID_MAX_POINTS_Y; l++) { - if (!isnan(z_values[k][l])) { - found_a_real = true; + found_a_real = true; - // Add in a random weighting factor that scrambles the probing of the - // last half of the mesh (when every unprobed mesh point is one index - // from a probed location). + // Add in a random weighting factor that scrambles the probing of the + // last half of the mesh (when every unprobed mesh point is one index + // from a probed location). - d1 = HYPOT(i - k, j - l) + (1.0f / ((millis() % 47) + 13)); + d1 = HYPOT(i - k, j - l) + (1.0f / ((millis() % 47) + 13)); - if (d1 < d2) { // Invalid mesh point (i,j) is closer to the defined point (k,l) - d2 = d1; - near.set(i, j); - } - } - } - } - - // - // At this point d2 should have the near defined mesh point to invalid mesh point (i,j) - // - - if (found_a_real && near.x >= 0 && d2 > farthest.distance) { - farthest.pos = near; // Found an invalid location farther from the defined mesh point - farthest.distance = d2; - } + if (d1 < d2) { // Invalid mesh point (i,j) is closer to the defined point (k,l) + d2 = d1; + near.set(i, j); } - } // for j - } // for i + } + + // + // At this point d2 should have the near defined mesh point to invalid mesh point (i,j) + // + + if (found_a_real && near.x >= 0 && d2 > farthest.distance) { + farthest.pos = near; // Found an invalid location farther from the defined mesh point + farthest.distance = d2; + } + } // GRID_LOOP if (!found_a_real && found_a_NAN) { // if the mesh is totally unpopulated, start the probing - farthest.pos.set(GRID_MAX_POINTS_X / 2, GRID_MAX_POINTS_Y / 2); + farthest.pos.set((GRID_MAX_POINTS_X) / 2, (GRID_MAX_POINTS_Y) / 2); farthest.distance = 1; } return farthest; @@ -1304,36 +1290,34 @@ float best_so_far = 99999.99f; - for (int8_t i = 0; i < GRID_MAX_POINTS_X; i++) { - for (int8_t j = 0; j < GRID_MAX_POINTS_Y; j++) { - if ( (type == (isnan(z_values[i][j]) ? INVALID : REAL)) - || (type == SET_IN_BITMAP && !done_flags->marked(i, j)) - ) { - // Found a Mesh Point of the specified type! - const xy_pos_t mpos = { mesh_index_to_xpos(i), mesh_index_to_ypos(j) }; + GRID_LOOP(i, j) { + if ( (type == (isnan(z_values[i][j]) ? INVALID : REAL)) + || (type == SET_IN_BITMAP && !done_flags->marked(i, j)) + ) { + // Found a Mesh Point of the specified type! + const xy_pos_t mpos = { mesh_index_to_xpos(i), mesh_index_to_ypos(j) }; - // If using the probe as the reference there are some unreachable locations. - // Also for round beds, there are grid points outside the bed the nozzle can't reach. - // Prune them from the list and ignore them till the next Phase (manual nozzle probing). + // If using the probe as the reference there are some unreachable locations. + // Also for round beds, there are grid points outside the bed the nozzle can't reach. + // Prune them from the list and ignore them till the next Phase (manual nozzle probing). - if (probe_relative ? !position_is_reachable_by_probe(mpos) : !position_is_reachable(mpos)) - continue; + if (!(probe_relative ? probe.can_reach(mpos) : position_is_reachable(mpos))) + continue; - // Reachable. Check if it's the best_so_far location to the nozzle. + // Reachable. Check if it's the best_so_far location to the nozzle. - const xy_pos_t diff = current_position - mpos; - const float distance = (ref - mpos).magnitude() + diff.magnitude() * 0.1f; + const xy_pos_t diff = current_position - mpos; + const float distance = (ref - mpos).magnitude() + diff.magnitude() * 0.1f; - // factor in the distance from the current location for the normal case - // so the nozzle isn't running all over the bed. - if (distance < best_so_far) { - best_so_far = distance; // Found a closer location with the desired value type. - closest.pos.set(i, j); - closest.distance = best_so_far; - } + // factor in the distance from the current location for the normal case + // so the nozzle isn't running all over the bed. + if (distance < best_so_far) { + best_so_far = distance; // Found a closer location with the desired value type. + closest.pos.set(i, j); + closest.distance = best_so_far; } - } // for j - } // for i + } + } // GRID_LOOP return closest; } @@ -1373,7 +1357,7 @@ info3 PROGMEM = { GRID_MAX_POINTS_X - 1, 0, 0, GRID_MAX_POINTS_Y, true }; // Right side of the mesh looking left static const smart_fill_info * const info[] PROGMEM = { &info0, &info1, &info2, &info3 }; - for (uint8_t i = 0; i < COUNT(info); ++i) { + LOOP_L_N(i, COUNT(info)) { const smart_fill_info *f = (smart_fill_info*)pgm_read_ptr(&info[i]); const int8_t sx = pgm_read_byte(&f->sx), sy = pgm_read_byte(&f->sy), ex = pgm_read_byte(&f->ex), ey = pgm_read_byte(&f->ey); @@ -1496,12 +1480,13 @@ bool zig_zag = false; - uint16_t total_points = g29_grid_size * g29_grid_size, point_num = 1; + const uint16_t total_points = sq(g29_grid_size); + uint16_t point_num = 1; xy_pos_t rpos; - for (uint8_t ix = 0; ix < g29_grid_size; ix++) { + LOOP_L_N(ix, g29_grid_size) { rpos.x = x_min + ix * dx; - for (int8_t iy = 0; iy < g29_grid_size; iy++) { + LOOP_L_N(iy, g29_grid_size) { rpos.y = y_min + dy * (zig_zag ? g29_grid_size - 1 - iy : iy); if (!abort_flag) { @@ -1569,39 +1554,37 @@ matrix_3x3 rotation = matrix_3x3::create_look_at(vector_3(lsf_results.A, lsf_results.B, 1)); - for (uint8_t i = 0; i < GRID_MAX_POINTS_X; i++) { - for (uint8_t j = 0; j < GRID_MAX_POINTS_Y; j++) { - float mx = mesh_index_to_xpos(i), - my = mesh_index_to_ypos(j), - mz = z_values[i][j]; + GRID_LOOP(i, j) { + float mx = mesh_index_to_xpos(i), + my = mesh_index_to_ypos(j), + mz = z_values[i][j]; - if (DEBUGGING(LEVELING)) { - DEBUG_ECHOPAIR_F("before rotation = [", mx, 7); - DEBUG_CHAR(','); - DEBUG_ECHO_F(my, 7); - DEBUG_CHAR(','); - DEBUG_ECHO_F(mz, 7); - DEBUG_ECHOPGM("] ---> "); - DEBUG_DELAY(20); - } - - apply_rotation_xyz(rotation, mx, my, mz); - - if (DEBUGGING(LEVELING)) { - DEBUG_ECHOPAIR_F("after rotation = [", mx, 7); - DEBUG_CHAR(','); - DEBUG_ECHO_F(my, 7); - DEBUG_CHAR(','); - DEBUG_ECHO_F(mz, 7); - DEBUG_ECHOLNPGM("]"); - DEBUG_DELAY(20); - } - - z_values[i][j] = mz - lsf_results.D; - #if ENABLED(EXTENSIBLE_UI) - ExtUI::onMeshUpdate(i, j, z_values[i][j]); - #endif + if (DEBUGGING(LEVELING)) { + DEBUG_ECHOPAIR_F("before rotation = [", mx, 7); + DEBUG_CHAR(','); + DEBUG_ECHO_F(my, 7); + DEBUG_CHAR(','); + DEBUG_ECHO_F(mz, 7); + DEBUG_ECHOPGM("] ---> "); + DEBUG_DELAY(20); } + + apply_rotation_xyz(rotation, mx, my, mz); + + if (DEBUGGING(LEVELING)) { + DEBUG_ECHOPAIR_F("after rotation = [", mx, 7); + DEBUG_CHAR(','); + DEBUG_ECHO_F(my, 7); + DEBUG_CHAR(','); + DEBUG_ECHO_F(mz, 7); + DEBUG_ECHOLNPGM("]"); + DEBUG_DELAY(20); + } + + z_values[i][j] = mz - lsf_results.D; + #if ENABLED(EXTENSIBLE_UI) + ExtUI::onMeshUpdate(i, j, z_values[i][j]); + #endif } if (DEBUGGING(LEVELING)) { @@ -1661,7 +1644,7 @@ // being extrapolated so that nearby points will have greater influence on // the point being extrapolated. Then extrapolate the mesh point from WLSF. - static_assert(GRID_MAX_POINTS_Y <= 16, "GRID_MAX_POINTS_Y too big"); + static_assert((GRID_MAX_POINTS_Y) <= 16, "GRID_MAX_POINTS_Y too big"); uint16_t bitmap[GRID_MAX_POINTS_X] = { 0 }; struct linear_fit_data lsf_results; @@ -1669,23 +1652,20 @@ const float weight_scaled = weight_factor * _MAX(MESH_X_DIST, MESH_Y_DIST); - for (uint8_t jx = 0; jx < GRID_MAX_POINTS_X; jx++) - for (uint8_t jy = 0; jy < GRID_MAX_POINTS_Y; jy++) - if (!isnan(z_values[jx][jy])) - SBI(bitmap[jx], jy); + GRID_LOOP(jx, jy) if (!isnan(z_values[jx][jy])) SBI(bitmap[jx], jy); xy_pos_t ppos; - for (uint8_t ix = 0; ix < GRID_MAX_POINTS_X; ix++) { + LOOP_L_N(ix, GRID_MAX_POINTS_X) { ppos.x = mesh_index_to_xpos(ix); - for (uint8_t iy = 0; iy < GRID_MAX_POINTS_Y; iy++) { + LOOP_L_N(iy, GRID_MAX_POINTS_Y) { ppos.y = mesh_index_to_ypos(iy); if (isnan(z_values[ix][iy])) { // undefined mesh point at (ppos.x,ppos.y), compute weighted LSF from original valid mesh points. incremental_LSF_reset(&lsf_results); xy_pos_t rpos; - for (uint8_t jx = 0; jx < GRID_MAX_POINTS_X; jx++) { + LOOP_L_N(jx, GRID_MAX_POINTS_X) { rpos.x = mesh_index_to_xpos(jx); - for (uint8_t jy = 0; jy < GRID_MAX_POINTS_Y; jy++) { + LOOP_L_N(jy, GRID_MAX_POINTS_Y) { if (TEST(bitmap[jx], jy)) { rpos.y = mesh_index_to_ypos(jy); const float rz = z_values[jx][jy], @@ -1747,7 +1727,7 @@ SERIAL_ECHOLNPAIR("MESH_Y_DIST ", MESH_Y_DIST); serial_delay(50); SERIAL_ECHOPGM("X-Axis Mesh Points at: "); - for (uint8_t i = 0; i < GRID_MAX_POINTS_X; i++) { + LOOP_L_N(i, GRID_MAX_POINTS_X) { SERIAL_ECHO_F(LOGICAL_X_POSITION(mesh_index_to_xpos(i)), 3); SERIAL_ECHOPGM(" "); serial_delay(25); @@ -1755,7 +1735,7 @@ SERIAL_EOL(); SERIAL_ECHOPGM("Y-Axis Mesh Points at: "); - for (uint8_t i = 0; i < GRID_MAX_POINTS_Y; i++) { + LOOP_L_N(i, GRID_MAX_POINTS_Y) { SERIAL_ECHO_F(LOGICAL_Y_POSITION(mesh_index_to_ypos(i)), 3); SERIAL_ECHOPGM(" "); serial_delay(25); @@ -1840,13 +1820,12 @@ SERIAL_ECHOLNPAIR("Subtracting mesh in slot ", g29_storage_slot, " from current mesh."); - for (uint8_t x = 0; x < GRID_MAX_POINTS_X; x++) - for (uint8_t y = 0; y < GRID_MAX_POINTS_Y; y++) { - z_values[x][y] -= tmp_z_values[x][y]; - #if ENABLED(EXTENSIBLE_UI) - ExtUI::onMeshUpdate(x, y, z_values[x][y]); - #endif - } + GRID_LOOP(x, y) { + z_values[x][y] -= tmp_z_values[x][y]; + #if ENABLED(EXTENSIBLE_UI) + ExtUI::onMeshUpdate(x, y, z_values[x][y]); + #endif + } } #endif // UBL_DEVEL_DEBUGGING diff --git a/Marlin/src/feature/bltouch.cpp b/Marlin/src/feature/bltouch.cpp index 77d85c4195..efe575ec63 100644 --- a/Marlin/src/feature/bltouch.cpp +++ b/Marlin/src/feature/bltouch.cpp @@ -73,20 +73,12 @@ void BLTouch::init(const bool set_voltage/*=false*/) { ); } - const bool should_set = last_written_mode != (false - #if ENABLED(BLTOUCH_SET_5V_MODE) - || true - #endif - ); + const bool should_set = last_written_mode != ENABLED(BLTOUCH_SET_5V_MODE); #endif if (should_set && set_voltage) - mode_conv_proc((false - #if ENABLED(BLTOUCH_SET_5V_MODE) - || true - #endif - )); + mode_conv_proc(ENABLED(BLTOUCH_SET_5V_MODE)); } void BLTouch::clear() { diff --git a/Marlin/src/feature/dac/stepper_dac.cpp b/Marlin/src/feature/dac/stepper_dac.cpp index cb3856f287..c8c1cb2494 100644 --- a/Marlin/src/feature/dac/stepper_dac.cpp +++ b/Marlin/src/feature/dac/stepper_dac.cpp @@ -88,11 +88,11 @@ void dac_print_values() { SERIAL_ECHO_MSG("Stepper current values in % (Amps):"); SERIAL_ECHO_START(); - SERIAL_ECHOLNPAIR( - " X:", dac_perc(X_AXIS), " (", dac_amps(X_AXIS), ")" - " Y:", dac_perc(Y_AXIS), " (", dac_amps(Y_AXIS), ")" - " Z:", dac_perc(Z_AXIS), " (", dac_amps(Z_AXIS), ")" - " E:", dac_perc(E_AXIS), " (", dac_amps(E_AXIS), ")" + SERIAL_ECHOLNPAIR_P( + SP_X_LBL, dac_perc(X_AXIS), PSTR(" ("), dac_amps(X_AXIS), PSTR(")") + SP_Y_LBL, dac_perc(Y_AXIS), PSTR(" ("), dac_amps(Y_AXIS), PSTR(")") + SP_Z_LBL, dac_perc(Z_AXIS), PSTR(" ("), dac_amps(Z_AXIS), PSTR(")") + SP_E_LBL, dac_perc(E_AXIS), PSTR(" ("), dac_amps(E_AXIS), PSTR(")") ); } diff --git a/Marlin/src/feature/digipot/digipot_mcp4018.cpp b/Marlin/src/feature/digipot/digipot_mcp4018.cpp index 888acc55d0..e8df4a475f 100644 --- a/Marlin/src/feature/digipot/digipot_mcp4018.cpp +++ b/Marlin/src/feature/digipot/digipot_mcp4018.cpp @@ -92,11 +92,11 @@ void digipot_i2c_set_current(const uint8_t channel, const float current) { void digipot_i2c_init() { static const float digipot_motor_current[] PROGMEM = DIGIPOT_I2C_MOTOR_CURRENTS; - for (uint8_t i = 0; i < DIGIPOT_I2C_NUM_CHANNELS; i++) + LOOP_L_N(i, DIGIPOT_I2C_NUM_CHANNELS) pots[i].i2c_init(); // setup initial currents as defined in Configuration_adv.h - for (uint8_t i = 0; i < COUNT(digipot_motor_current); i++) + LOOP_L_N(i, COUNT(digipot_motor_current)) digipot_i2c_set_current(i, pgm_read_float(&digipot_motor_current[i])); } diff --git a/Marlin/src/feature/digipot/digipot_mcp4451.cpp b/Marlin/src/feature/digipot/digipot_mcp4451.cpp index e84bd28d35..1183c96aa5 100644 --- a/Marlin/src/feature/digipot/digipot_mcp4451.cpp +++ b/Marlin/src/feature/digipot/digipot_mcp4451.cpp @@ -83,7 +83,7 @@ void digipot_i2c_init() { #endif // setup initial currents as defined in Configuration_adv.h static const float digipot_motor_current[] PROGMEM = DIGIPOT_I2C_MOTOR_CURRENTS; - for (uint8_t i = 0; i < COUNT(digipot_motor_current); i++) + LOOP_L_N(i, COUNT(digipot_motor_current)) digipot_i2c_set_current(i, pgm_read_float(&digipot_motor_current[i])); } diff --git a/Marlin/src/feature/emergency_parser.cpp b/Marlin/src/feature/e_parser.cpp similarity index 97% rename from Marlin/src/feature/emergency_parser.cpp rename to Marlin/src/feature/e_parser.cpp index 60fba1f1b6..e7d79bf745 100644 --- a/Marlin/src/feature/emergency_parser.cpp +++ b/Marlin/src/feature/e_parser.cpp @@ -28,7 +28,7 @@ #if ENABLED(EMERGENCY_PARSER) -#include "emergency_parser.h" +#include "e_parser.h" // Static data members bool EmergencyParser::killed_by_M112, // = false diff --git a/Marlin/src/feature/emergency_parser.h b/Marlin/src/feature/e_parser.h similarity index 96% rename from Marlin/src/feature/emergency_parser.h rename to Marlin/src/feature/e_parser.h index 787c82407f..41261402a1 100644 --- a/Marlin/src/feature/emergency_parser.h +++ b/Marlin/src/feature/e_parser.h @@ -75,10 +75,11 @@ public: FORCE_INLINE static void disable() { enabled = false; } FORCE_INLINE static void update(State &state, const uint8_t c) { + #define ISEOL(C) ((C) == '\n' || (C) == '\r') switch (state) { case EP_RESET: switch (c) { - case ' ': break; + case ' ': case '\n': case '\r': break; case 'N': state = EP_N; break; case 'M': state = EP_M; break; default: state = EP_IGNORE; @@ -164,11 +165,11 @@ public: #endif case EP_IGNORE: - if (c == '\n') state = EP_RESET; + if (ISEOL(c)) state = EP_RESET; break; default: - if (c == '\n') { + if (ISEOL(c)) { if (enabled) switch (state) { case EP_M108: wait_for_user = wait_for_heatup = false; break; case EP_M112: killed_by_M112 = true; break; diff --git a/Marlin/src/feature/I2CPositionEncoder.cpp b/Marlin/src/feature/encoder_i2c.cpp similarity index 99% rename from Marlin/src/feature/I2CPositionEncoder.cpp rename to Marlin/src/feature/encoder_i2c.cpp index 9c1e53df74..a70227a270 100644 --- a/Marlin/src/feature/I2CPositionEncoder.cpp +++ b/Marlin/src/feature/encoder_i2c.cpp @@ -32,7 +32,7 @@ #if ENABLED(I2C_POSITION_ENCODERS) -#include "I2CPositionEncoder.h" +#include "encoder_i2c.h" #include "../module/temperature.h" #include "../module/stepper.h" diff --git a/Marlin/src/feature/I2CPositionEncoder.h b/Marlin/src/feature/encoder_i2c.h similarity index 100% rename from Marlin/src/feature/I2CPositionEncoder.h rename to Marlin/src/feature/encoder_i2c.h diff --git a/Marlin/src/feature/filwidth.cpp b/Marlin/src/feature/filwidth.cpp index ae8c43d430..4357d39fe0 100644 --- a/Marlin/src/feature/filwidth.cpp +++ b/Marlin/src/feature/filwidth.cpp @@ -42,7 +42,7 @@ int8_t FilamentWidthSensor::ratios[MAX_MEASUREMENT_DELAY + 1], // Ring void FilamentWidthSensor::init() { const int8_t ratio = sample_to_size_ratio(); - for (uint8_t i = 0; i < COUNT(ratios); ++i) ratios[i] = ratio; + LOOP_L_N(i, COUNT(ratios)) ratios[i] = ratio; index_r = index_w = 0; } diff --git a/Marlin/src/feature/fwretract.cpp b/Marlin/src/feature/fwretract.cpp index 2436170b35..7d756ac6d0 100644 --- a/Marlin/src/feature/fwretract.cpp +++ b/Marlin/src/feature/fwretract.cpp @@ -73,7 +73,7 @@ void FWRetract::reset() { settings.swap_retract_recover_feedrate_mm_s = RETRACT_RECOVER_FEEDRATE_SWAP; current_hop = 0.0; - for (uint8_t i = 0; i < EXTRUDERS; ++i) { + LOOP_L_N(i, EXTRUDERS) { retracted[i] = false; #if EXTRUDERS > 1 retracted_swap[i] = false; @@ -117,7 +117,7 @@ void FWRetract::retract(const bool retracting " swapping ", swapping, " active extruder ", active_extruder ); - for (uint8_t i = 0; i < EXTRUDERS; ++i) { + LOOP_L_N(i, EXTRUDERS) { SERIAL_ECHOLNPAIR("retracted[", i, "] ", retracted[i]); #if EXTRUDERS > 1 SERIAL_ECHOLNPAIR("retracted_swap[", i, "] ", retracted_swap[i]); @@ -201,7 +201,7 @@ void FWRetract::retract(const bool retracting SERIAL_ECHOLNPAIR("retracting ", retracting); SERIAL_ECHOLNPAIR("swapping ", swapping); SERIAL_ECHOLNPAIR("active_extruder ", active_extruder); - for (uint8_t i = 0; i < EXTRUDERS; ++i) { + LOOP_L_N(i, EXTRUDERS) { SERIAL_ECHOLNPAIR("retracted[", i, "] ", retracted[i]); #if EXTRUDERS > 1 SERIAL_ECHOLNPAIR("retracted_swap[", i, "] ", retracted_swap[i]); diff --git a/Marlin/src/feature/joystick.cpp b/Marlin/src/feature/joystick.cpp index 70c2812a37..66afb63b05 100644 --- a/Marlin/src/feature/joystick.cpp +++ b/Marlin/src/feature/joystick.cpp @@ -37,7 +37,7 @@ Joystick joystick; #if ENABLED(EXTENSIBLE_UI) - #include "../lcd/extensible_ui/ui_api.h" + #include "../lcd/extui/ui_api.h" #endif #if HAS_JOY_ADC_X @@ -173,6 +173,7 @@ Joystick joystick; if (!UNEAR_ZERO(hypot2)) { current_position += move_dist; + apply_motion_limits(current_position); const float length = sqrt(hypot2); injecting_now = true; planner.buffer_line(current_position, length / seg_time, active_extruder, length); diff --git a/Marlin/src/feature/Max7219_Debug_LEDs.cpp b/Marlin/src/feature/max7219.cpp similarity index 85% rename from Marlin/src/feature/Max7219_Debug_LEDs.cpp rename to Marlin/src/feature/max7219.cpp index 2b329db3b3..2ec23f019c 100644 --- a/Marlin/src/feature/Max7219_Debug_LEDs.cpp +++ b/Marlin/src/feature/max7219.cpp @@ -41,31 +41,23 @@ #define MAX7219_ERRORS // Disable to save 406 bytes of Program Memory -#include "Max7219_Debug_LEDs.h" +#include "max7219.h" #include "../module/planner.h" #include "../module/stepper.h" #include "../MarlinCore.h" #include "../HAL/shared/Delay.h" -#define HAS_SIDE_BY_SIDE (ENABLED(MAX7219_SIDE_BY_SIDE) && MAX7219_NUMBER_UNITS > 1) +#if ENABLED(MAX7219_SIDE_BY_SIDE) && MAX7219_NUMBER_UNITS > 1 + #define HAS_SIDE_BY_SIDE 1 +#endif #if _ROT == 0 || _ROT == 180 - #if HAS_SIDE_BY_SIDE - #define MAX7219_X_LEDS 8 - #define MAX7219_Y_LEDS MAX7219_LINES - #else - #define MAX7219_Y_LEDS 8 - #define MAX7219_X_LEDS MAX7219_LINES - #endif + #define MAX7219_X_LEDS TERN(HAS_SIDE_BY_SIDE, 8, MAX7219_LINES) + #define MAX7219_Y_LEDS TERN(HAS_SIDE_BY_SIDE, MAX7219_LINES, 8) #elif _ROT == 90 || _ROT == 270 - #if HAS_SIDE_BY_SIDE - #define MAX7219_Y_LEDS 8 - #define MAX7219_X_LEDS MAX7219_LINES - #else - #define MAX7219_X_LEDS 8 - #define MAX7219_Y_LEDS MAX7219_LINES - #endif + #define MAX7219_X_LEDS TERN(HAS_SIDE_BY_SIDE, MAX7219_LINES, 8) + #define MAX7219_Y_LEDS TERN(HAS_SIDE_BY_SIDE, 8, MAX7219_LINES) #else #error "MAX7219_ROTATE must be a multiple of +/- 90°." #endif @@ -73,6 +65,7 @@ Max7219 max7219; uint8_t Max7219::led_line[MAX7219_LINES]; // = { 0 }; +uint8_t Max7219::suspended; // = 0; #define LINE_REG(Q) (max7219_reg_digit0 + ((Q) & 0x7)) @@ -154,7 +147,7 @@ void Max7219::error(const char * const func, const int32_t v1, const int32_t v2/ */ inline uint32_t flipped(const uint32_t bits, const uint8_t n_bytes) { uint32_t mask = 1, outbits = 0; - for (uint8_t b = 0; b < n_bytes * 8; b++) { + LOOP_L_N(b, n_bytes * 8) { outbits <<= 1; if (bits & mask) outbits |= 1; mask <<= 1; @@ -212,6 +205,7 @@ void Max7219::send(const uint8_t reg, const uint8_t data) { // Send out a single native row of bits to just one unit void Max7219::refresh_unit_line(const uint8_t line) { + if (suspended) return; #if MAX7219_NUMBER_UNITS == 1 send(LINE_REG(line), led_line[line]); #else @@ -223,6 +217,7 @@ void Max7219::refresh_unit_line(const uint8_t line) { // Send out a single native row of bits to all units void Max7219::refresh_line(const uint8_t line) { + if (suspended) return; #if MAX7219_NUMBER_UNITS == 1 refresh_unit_line(line); #else @@ -241,9 +236,9 @@ void Max7219::set(const uint8_t line, const uint8_t bits) { // Draw an integer with optional leading zeros and optional decimal point void Max7219::print(const uint8_t start, int16_t value, uint8_t size, const bool leadzero=false, bool dec=false) { + if (suspended) return; constexpr uint8_t led_numeral[10] = { 0x7E, 0x60, 0x6D, 0x79, 0x63, 0x5B, 0x5F, 0x70, 0x7F, 0x7A }, led_decimal = 0x80, led_minus = 0x01; - bool blank = false, neg = value < 0; if (neg) value *= -1; while (size--) { @@ -295,6 +290,7 @@ void Max7219::led_toggle(const uint8_t x, const uint8_t y) { } void Max7219::send_row(const uint8_t row) { + if (suspended) return; #if _ROT == 0 || _ROT == 180 // Native Lines are horizontal too #if MAX7219_X_LEDS <= 8 refresh_unit_line(LED_IND(0, row)); // A single unit line @@ -308,6 +304,7 @@ void Max7219::send_row(const uint8_t row) { } void Max7219::send_column(const uint8_t col) { + if (suspended) return; #if _ROT == 90 || _ROT == 270 // Native Lines are vertical too #if MAX7219_Y_LEDS <= 8 refresh_unit_line(LED_IND(col, 0)); // A single unit line @@ -332,25 +329,25 @@ void Max7219::fill() { void Max7219::clear_row(const uint8_t row) { if (row >= MAX7219_Y_LEDS) return error(PSTR("clear_row"), row); - for (uint8_t x = 0; x < MAX7219_X_LEDS; x++) CLR_7219(x, row); + LOOP_L_N(x, MAX7219_X_LEDS) CLR_7219(x, row); send_row(row); } void Max7219::clear_column(const uint8_t col) { if (col >= MAX7219_X_LEDS) return error(PSTR("set_column"), col); - for (uint8_t y = 0; y < MAX7219_Y_LEDS; y++) CLR_7219(col, y); + LOOP_L_N(y, MAX7219_Y_LEDS) CLR_7219(col, y); send_column(col); } /** * Plot the low order bits of val to the specified row of the matrix. - * With 4 Max7219 units in the chain, it's possible to set 32 bits at once with - * one call to the function (if rotated 90° or 180°). + * With 4 Max7219 units in the chain, it's possible to set 32 bits at + * once with a single call to the function (if rotated 90° or 270°). */ void Max7219::set_row(const uint8_t row, const uint32_t val) { if (row >= MAX7219_Y_LEDS) return error(PSTR("set_row"), row); uint32_t mask = _BV32(MAX7219_X_LEDS - 1); - for (uint8_t x = 0; x < MAX7219_X_LEDS; x++) { + LOOP_L_N(x, MAX7219_X_LEDS) { if (val & mask) SET_7219(x, row); else CLR_7219(x, row); mask >>= 1; } @@ -359,13 +356,13 @@ void Max7219::set_row(const uint8_t row, const uint32_t val) { /** * Plot the low order bits of val to the specified column of the matrix. - * With 4 Max7219 units in the chain, it's possible to set 32 bits at once with - * one call to the function (if rotated 90° or 180°). + * With 4 Max7219 units in the chain, it's possible to set 32 bits at + * once with a single call to the function (if rotated 0° or 180°). */ void Max7219::set_column(const uint8_t col, const uint32_t val) { if (col >= MAX7219_X_LEDS) return error(PSTR("set_column"), col); uint32_t mask = _BV32(MAX7219_Y_LEDS - 1); - for (uint8_t y = 0; y < MAX7219_Y_LEDS; y++) { + LOOP_L_N(y, MAX7219_Y_LEDS) { if (val & mask) SET_7219(col, y); else CLR_7219(col, y); mask >>= 1; } @@ -430,58 +427,106 @@ void Max7219::set_columns_32bits(const uint8_t x, uint32_t val) { // Initialize the Max7219 void Max7219::register_setup() { - for (uint8_t i = 0; i < MAX7219_NUMBER_UNITS; i++) + LOOP_L_N(i, MAX7219_NUMBER_UNITS) send(max7219_reg_scanLimit, 0x07); pulse_load(); // Tell the chips to load the clocked out data - for (uint8_t i = 0; i < MAX7219_NUMBER_UNITS; i++) + LOOP_L_N(i, MAX7219_NUMBER_UNITS) send(max7219_reg_decodeMode, 0x00); // Using an led matrix (not digits) pulse_load(); // Tell the chips to load the clocked out data - for (uint8_t i = 0; i < MAX7219_NUMBER_UNITS; i++) + LOOP_L_N(i, MAX7219_NUMBER_UNITS) send(max7219_reg_shutdown, 0x01); // Not in shutdown mode pulse_load(); // Tell the chips to load the clocked out data - for (uint8_t i = 0; i < MAX7219_NUMBER_UNITS; i++) + LOOP_L_N(i, MAX7219_NUMBER_UNITS) send(max7219_reg_displayTest, 0x00); // No display test pulse_load(); // Tell the chips to load the clocked out data - for (uint8_t i = 0; i < MAX7219_NUMBER_UNITS; i++) + LOOP_L_N(i, MAX7219_NUMBER_UNITS) send(max7219_reg_intensity, 0x01 & 0x0F); // The first 0x0F is the value you can set // Range: 0x00 to 0x0F pulse_load(); // Tell the chips to load the clocked out data } #ifdef MAX7219_INIT_TEST -#if MAX7219_INIT_TEST == 2 - #define MAX7219_LEDS (MAX7219_X_LEDS * MAX7219_Y_LEDS) + uint8_t test_mode = 0; + millis_t next_patt_ms; + bool patt_on; - void Max7219::spiral(const bool on, const uint16_t del) { - constexpr int8_t way[][2] = { { 1, 0 }, { 0, 1 }, { -1, 0 }, { 0, -1 } }; - int8_t px = 0, py = 0, dir = 0; - for (IF<(MAX7219_LEDS > 255), uint16_t, uint8_t>::type i = MAX7219_LEDS; i--;) { - led_set(px, py, on); - delay(del); - const int8_t x = px + way[dir][0], y = py + way[dir][1]; - if (!WITHIN(x, 0, MAX7219_X_LEDS - 1) || !WITHIN(y, 0, MAX7219_Y_LEDS - 1) || BIT_7219(x, y) == on) - dir = (dir + 1) & 0x3; - px += way[dir][0]; - py += way[dir][1]; + #if MAX7219_INIT_TEST == 2 + + #define MAX7219_LEDS (MAX7219_X_LEDS * MAX7219_Y_LEDS) + + constexpr millis_t pattern_delay = 4; + + int8_t spiralx, spiraly, spiral_dir; + IF<(MAX7219_LEDS > 255), uint16_t, uint8_t>::type spiral_count; + + void Max7219::test_pattern() { + constexpr int8_t way[][2] = { { 1, 0 }, { 0, 1 }, { -1, 0 }, { 0, -1 } }; + led_set(spiralx, spiraly, patt_on); + const int8_t x = spiralx + way[spiral_dir][0], y = spiraly + way[spiral_dir][1]; + if (!WITHIN(x, 0, MAX7219_X_LEDS - 1) || !WITHIN(y, 0, MAX7219_Y_LEDS - 1) || BIT_7219(x, y) == patt_on) + spiral_dir = (spiral_dir + 1) & 0x3; + spiralx += way[spiral_dir][0]; + spiraly += way[spiral_dir][1]; + if (!spiral_count--) { + if (!patt_on) + test_mode = 0; + else { + spiral_count = MAX7219_LEDS; + spiralx = spiraly = spiral_dir = 0; + patt_on = false; + } + } } + + #else + + constexpr millis_t pattern_delay = 20; + int8_t sweep_count, sweepx, sweep_dir; + + void Max7219::test_pattern() { + set_column(sweepx, patt_on ? 0xFFFFFFFF : 0x00000000); + sweepx += sweep_dir; + if (!WITHIN(sweepx, 0, MAX7219_X_LEDS - 1)) { + if (!patt_on) { + sweep_dir *= -1; + sweepx += sweep_dir; + } + else + sweepx -= MAX7219_X_LEDS * sweep_dir; + patt_on ^= true; + next_patt_ms += 100; + if (++test_mode > 4) test_mode = 0; + } + } + + #endif + + void Max7219::run_test_pattern() { + const millis_t ms = millis(); + if (PENDING(ms, next_patt_ms)) return; + next_patt_ms = ms + pattern_delay; + test_pattern(); } -#else - - void Max7219::sweep(const int8_t dir, const uint16_t ms, const bool on) { - uint8_t x = dir > 0 ? 0 : MAX7219_X_LEDS - 1; - for (uint8_t i = MAX7219_X_LEDS; i--; x += dir) { - set_column(x, on ? 0xFFFFFFFF : 0x00000000); - delay(ms); - } + void Max7219::start_test_pattern() { + clear(); + test_mode = 1; + patt_on = true; + #if MAX7219_INIT_TEST == 2 + spiralx = spiraly = spiral_dir = 0; + spiral_count = MAX7219_LEDS; + #else + sweep_dir = 1; + sweepx = 0; + sweep_count = MAX7219_X_LEDS; + #endif } -#endif #endif // MAX7219_INIT_TEST void Max7219::init() { @@ -492,26 +537,14 @@ void Max7219::init() { register_setup(); - for (uint8_t i = 0; i <= 7; i++) { // Empty registers to turn all LEDs off + LOOP_LE_N(i, 7) { // Empty registers to turn all LEDs off led_line[i] = 0x00; send(max7219_reg_digit0 + i, 0); pulse_load(); // Tell the chips to load the clocked out data } #ifdef MAX7219_INIT_TEST - #if MAX7219_INIT_TEST == 2 - spiral(true, 8); - delay(150); - spiral(false, 8); - #else - // Do an aesthetically-pleasing pattern to fully test the Max7219 module and LEDs. - // Light up and turn off columns, both forward and backward. - sweep(1, 20, true); - sweep(1, 20, false); - delay(150); - sweep(-1, 20, true); - sweep(-1, 20, false); - #endif + start_test_pattern(); #endif } @@ -604,6 +637,13 @@ void Max7219::idle_tasks() { register_setup(); } + #ifdef MAX7219_INIT_TEST + if (test_mode) { + run_test_pattern(); + return; + } + #endif + #if ENABLED(MAX7219_DEBUG_PRINTER_ALIVE) if (do_blink) { led_toggle(MAX7219_X_LEDS - 1, MAX7219_Y_LEDS - 1); @@ -649,6 +689,12 @@ void Max7219::idle_tasks() { last_depth = current_depth; } #endif + + // After resume() automatically do a refresh() + if (suspended == 0x80) { + suspended = 0; + refresh(); + } } #endif // MAX7219_DEBUG diff --git a/Marlin/src/feature/Max7219_Debug_LEDs.h b/Marlin/src/feature/max7219.h similarity index 92% rename from Marlin/src/feature/Max7219_Debug_LEDs.h rename to Marlin/src/feature/max7219.h index d0b2424544..19170b2d59 100644 --- a/Marlin/src/feature/Max7219_Debug_LEDs.h +++ b/Marlin/src/feature/max7219.h @@ -88,6 +88,12 @@ public: // Refresh all units static inline void refresh() { for (uint8_t i = 0; i < 8; i++) refresh_line(i); } + // Suspend / resume updates to the LED unit + // Use these methods to speed up multiple changes + // or to apply updates from interrupt context. + static inline void suspend() { suspended++; } + static inline void resume() { suspended--; suspended |= 0x80; } + // Update a single native line on all units static void refresh_line(const uint8_t line); @@ -126,6 +132,7 @@ public: static void idle_tasks(); private: + static uint8_t suspended; static void error(const char * const func, const int32_t v1, const int32_t v2=-1); static void noop(); static void set(const uint8_t line, const uint8_t bits); @@ -136,11 +143,9 @@ private: static void quantity16(const uint8_t y, const uint8_t ov, const uint8_t nv); #ifdef MAX7219_INIT_TEST - #if MAX7219_INIT_TEST == 2 - static void spiral(const bool on, const uint16_t del); - #else - static void sweep(const int8_t dir, const uint16_t ms, const bool on); - #endif + static void test_pattern(); + static void run_test_pattern(); + static void start_test_pattern(); #endif }; diff --git a/Marlin/src/feature/mixing.cpp b/Marlin/src/feature/mixing.cpp index de1cda14be..d6ae2bb629 100644 --- a/Marlin/src/feature/mixing.cpp +++ b/Marlin/src/feature/mixing.cpp @@ -98,13 +98,13 @@ void Mixer::normalize(const uint8_t tool_index) { void Mixer::reset_vtools() { // Virtual Tools 0, 1, 2, 3 = Filament 1, 2, 3, 4, etc. // Every virtual tool gets a pure filament - for (uint8_t t = 0; t < MIXING_VIRTUAL_TOOLS && t < MIXING_STEPPERS; t++) + LOOP_L_N(t, MIXING_VIRTUAL_TOOLS && t < MIXING_STEPPERS) MIXER_STEPPER_LOOP(i) color[t][i] = (t == i) ? COLOR_A_MASK : 0; // Remaining virtual tools are 100% filament 1 #if MIXING_VIRTUAL_TOOLS > MIXING_STEPPERS - for (uint8_t t = MIXING_STEPPERS; t < MIXING_VIRTUAL_TOOLS; t++) + LOOP_S_L_N(t, MIXING_STEPPERS, MIXING_VIRTUAL_TOOLS) MIXER_STEPPER_LOOP(i) color[t][i] = (i == 0) ? COLOR_A_MASK : 0; #endif diff --git a/Marlin/src/feature/prusa_MMU2/mmu2.cpp b/Marlin/src/feature/mmu2/mmu2.cpp similarity index 98% rename from Marlin/src/feature/prusa_MMU2/mmu2.cpp rename to Marlin/src/feature/mmu2/mmu2.cpp index d71edbac35..2df34176da 100644 --- a/Marlin/src/feature/prusa_MMU2/mmu2.cpp +++ b/Marlin/src/feature/mmu2/mmu2.cpp @@ -43,7 +43,7 @@ MMU2 mmu2; #endif #if ENABLED(EXTENSIBLE_UI) - #include "../../lcd/extensible_ui/ui_api.h" + #include "../../lcd/extui/ui_api.h" #endif #define DEBUG_OUT ENABLED(MMU2_DEBUG) @@ -381,7 +381,7 @@ bool MMU2::rx_str_P(const char* str) { void MMU2::tx_str_P(const char* str) { clear_rx_buffer(); uint8_t len = strlen_P(str); - for (uint8_t i = 0; i < len; i++) mmuSerial.write(pgm_read_byte(str++)); + LOOP_L_N(i, len) mmuSerial.write(pgm_read_byte(str++)); rx_buffer[0] = '\0'; last_request = millis(); } @@ -392,7 +392,7 @@ void MMU2::tx_str_P(const char* str) { void MMU2::tx_printf_P(const char* format, int argument = -1) { clear_rx_buffer(); uint8_t len = sprintf_P(tx_buffer, format, argument); - for (uint8_t i = 0; i < len; i++) mmuSerial.write(tx_buffer[i]); + LOOP_L_N(i, len) mmuSerial.write(tx_buffer[i]); rx_buffer[0] = '\0'; last_request = millis(); } @@ -403,7 +403,7 @@ void MMU2::tx_printf_P(const char* format, int argument = -1) { void MMU2::tx_printf_P(const char* format, int argument1, int argument2) { clear_rx_buffer(); uint8_t len = sprintf_P(tx_buffer, format, argument1, argument2); - for (uint8_t i = 0; i < len; i++) mmuSerial.write(tx_buffer[i]); + LOOP_L_N(i, len) mmuSerial.write(tx_buffer[i]); rx_buffer[0] = '\0'; last_request = millis(); } @@ -780,7 +780,7 @@ void MMU2::filament_runout() { const E_Step* step = sequence; - for (uint8_t i = 0; i < steps; i++) { + LOOP_L_N(i, steps) { const float es = pgm_read_float(&(step->extrude)); const feedRate_t fr_mm_m = pgm_read_float(&(step->feedRate)); diff --git a/Marlin/src/feature/prusa_MMU2/mmu2.h b/Marlin/src/feature/mmu2/mmu2.h similarity index 100% rename from Marlin/src/feature/prusa_MMU2/mmu2.h rename to Marlin/src/feature/mmu2/mmu2.h diff --git a/Marlin/src/feature/prusa_MMU2/serial-protocol.md b/Marlin/src/feature/mmu2/serial-protocol.md similarity index 100% rename from Marlin/src/feature/prusa_MMU2/serial-protocol.md rename to Marlin/src/feature/mmu2/serial-protocol.md diff --git a/Marlin/src/feature/pause.cpp b/Marlin/src/feature/pause.cpp index 95b5cc953f..fb69803ee7 100644 --- a/Marlin/src/feature/pause.cpp +++ b/Marlin/src/feature/pause.cpp @@ -50,7 +50,7 @@ #endif #if ENABLED(EXTENSIBLE_UI) - #include "../lcd/extensible_ui/ui_api.h" + #include "../lcd/extui/ui_api.h" #endif #include "../core/language.h" @@ -202,7 +202,7 @@ bool load_filament(const float &slow_load_length/*=0*/, const float &fast_load_l #if HAS_BUZZER filament_change_beep(max_beep_count); #endif - idle(true); + idle_no_sleep(); } } @@ -280,7 +280,7 @@ bool load_filament(const float &slow_load_length/*=0*/, const float &fast_load_l KEEPALIVE_STATE(PAUSED_FOR_USER); wait_for_user = false; lcd_pause_show_message(PAUSE_MESSAGE_OPTION); - while (pause_menu_response == PAUSE_RESPONSE_WAIT_FOR) idle(true); + while (pause_menu_response == PAUSE_RESPONSE_WAIT_FOR) idle_no_sleep(); } #endif @@ -541,7 +541,7 @@ void wait_for_confirmation(const bool is_reload/*=false*/, const int8_t max_beep #endif // Wait for LCD click or M108 - while (wait_for_user) idle(true); + while (wait_for_user) idle_no_sleep(); #if ENABLED(HOST_PROMPT_SUPPORT) host_prompt_do(PROMPT_INFO, PSTR("Reheating")); @@ -576,8 +576,7 @@ void wait_for_confirmation(const bool is_reload/*=false*/, const int8_t max_beep filament_change_beep(max_beep_count, true); #endif } - - idle(true); + idle_no_sleep(); } #if ENABLED(DUAL_X_CARRIAGE) active_extruder = saved_ext; diff --git a/Marlin/src/feature/power.cpp b/Marlin/src/feature/power.cpp index f1979c3761..cf18e2130c 100644 --- a/Marlin/src/feature/power.cpp +++ b/Marlin/src/feature/power.cpp @@ -108,7 +108,7 @@ void Power::power_on() { if (!powersupply_on) { PSU_PIN_ON(); - #if HAS_TRINAMIC + #if HAS_TRINAMIC_CONFIG delay(PSU_POWERUP_DELAY); // Wait for power to settle restore_stepper_drivers(); #endif diff --git a/Marlin/src/feature/power_loss_recovery.cpp b/Marlin/src/feature/powerloss.cpp similarity index 98% rename from Marlin/src/feature/power_loss_recovery.cpp rename to Marlin/src/feature/powerloss.cpp index f331a9f94d..bb0062d4ec 100644 --- a/Marlin/src/feature/power_loss_recovery.cpp +++ b/Marlin/src/feature/powerloss.cpp @@ -28,7 +28,7 @@ #if ENABLED(POWER_LOSS_RECOVERY) -#include "power_loss_recovery.h" +#include "powerloss.h" #include "../core/macros.h" bool PrintJobRecovery::enabled; // Initialized by settings.load() @@ -100,13 +100,11 @@ void PrintJobRecovery::changed() { * If a saved state exists send 'M1000 S' to initiate job recovery. */ void PrintJobRecovery::check() { - if (enabled) { - if (!card.isMounted()) card.mount(); - if (card.isMounted()) { - load(); - if (!valid()) return purge(); - queue.inject_P(PSTR("M1000 S")); - } + //if (!card.isMounted()) card.mount(); + if (card.isMounted()) { + load(); + if (!valid()) return purge(); + queue.inject_P(PSTR("M1000 S")); } } @@ -393,7 +391,7 @@ void PrintJobRecovery::resume() { // Restore retract and hop state #if ENABLED(FWRETRACT) - for (uint8_t e = 0; e < EXTRUDERS; e++) { + LOOP_L_N(e, EXTRUDERS) { if (info.retract[e] != 0.0) { fwretract.current_retract[e] = info.retract[e]; fwretract.retracted[e] = true; diff --git a/Marlin/src/feature/power_loss_recovery.h b/Marlin/src/feature/powerloss.h similarity index 97% rename from Marlin/src/feature/power_loss_recovery.h rename to Marlin/src/feature/powerloss.h index 6c4b5d5c3f..0496560785 100644 --- a/Marlin/src/feature/power_loss_recovery.h +++ b/Marlin/src/feature/powerloss.h @@ -159,11 +159,7 @@ class PrintJobRecovery { static inline void cancel() { purge(); card.autostart_index = 0; } static void load(); - static void save(const bool force=false - #if ENABLED(SAVE_EACH_CMD_MODE) - || true - #endif - ); + static void save(const bool force=ENABLED(SAVE_EACH_CMD_MODE)); #if PIN_EXISTS(POWER_LOSS) static inline void outage() { diff --git a/Marlin/src/feature/probe_temp_compensation.cpp b/Marlin/src/feature/probe_temp_comp.cpp similarity index 97% rename from Marlin/src/feature/probe_temp_compensation.cpp rename to Marlin/src/feature/probe_temp_comp.cpp index edb70ff268..6b787f420a 100644 --- a/Marlin/src/feature/probe_temp_compensation.cpp +++ b/Marlin/src/feature/probe_temp_comp.cpp @@ -24,7 +24,7 @@ #if ENABLED(PROBE_TEMP_COMPENSATION) -#include "probe_temp_compensation.h" +#include "probe_temp_comp.h" #include ProbeTempComp temp_comp; @@ -54,7 +54,7 @@ uint8_t ProbeTempComp::calib_idx; // = 0 float ProbeTempComp::init_measurement; // = 0.0 void ProbeTempComp::clear_offsets(const TempSensorID tsi) { - for (uint8_t i = 0; i < cali_info[tsi].measurements; ++i) + LOOP_L_N(i, cali_info[tsi].measurements) sensor_z_offsets[tsi][i] = 0; calib_idx = 0; } @@ -66,7 +66,7 @@ bool ProbeTempComp::set_offset(const TempSensorID tsi, const uint8_t idx, const } void ProbeTempComp::print_offsets() { - for (uint8_t s = 0; s < TSI_COUNT; s++) { + LOOP_L_N(s, TSI_COUNT) { float temp = cali_info[s].start_temp; for (int16_t i = -1; i < cali_info[s].measurements; ++i) { serialprintPGM(s == TSI_BED ? PSTR("Bed") : @@ -198,7 +198,7 @@ bool ProbeTempComp::linear_regression(const TempSensorID tsi, float &k, float &d sum_x2 = sq(start_temp), sum_xy = 0, sum_y = 0; - for (uint8_t i = 0; i < calib_idx; ++i) { + LOOP_L_N(i, calib_idx) { const float xi = start_temp + (i + 1) * res_temp, yi = static_cast(data[i]); sum_x += xi; diff --git a/Marlin/src/feature/probe_temp_compensation.h b/Marlin/src/feature/probe_temp_comp.h similarity index 86% rename from Marlin/src/feature/probe_temp_compensation.h rename to Marlin/src/feature/probe_temp_comp.h index c9ab93e4a9..2ed10eeb99 100644 --- a/Marlin/src/feature/probe_temp_compensation.h +++ b/Marlin/src/feature/probe_temp_comp.h @@ -57,16 +57,16 @@ class ProbeTempComp { static const temp_calib_t cali_info[TSI_COUNT]; // Where to park nozzle to wait for probe cooldown - static constexpr xyz_pos_t park_point = xyz_pos_t({ PTC_PARK_POS_X, PTC_PARK_POS_Y, PTC_PARK_POS_Z }); + static constexpr float park_point_x = PTC_PARK_POS_X, + park_point_y = PTC_PARK_POS_Y, + park_point_z = PTC_PARK_POS_Z, + // XY coordinates of nozzle for probing the bed + measure_point_x = PTC_PROBE_POS_X, // Coordinates to probe + measure_point_y = PTC_PROBE_POS_Y; + //measure_point_x = 12.0f, // Coordinates to probe on MK52 magnetic heatbed + //measure_point_y = 7.3f; static constexpr int max_bed_temp = PTC_MAX_BED_TEMP, // Max temperature to avoid heating errors - - // XY coordinates of nozzle for probing the bed - measure_point_x = PTC_PROBE_POS_X, // X-coordinate to probe - measure_point_y = PTC_PROBE_POS_Y, // Y-coordinate to probe - //measure_point_x = 12.0f, // X-coordinate to probe on MK52 magnetic heatbed - //measure_point_y = 7.3f, // Y-coordinate to probe on MK52 magnetic heatbed - probe_calib_bed_temp = max_bed_temp, // Bed temperature while calibrating probe bed_calib_probe_temp = 30; // Probe temperature while calibrating bed diff --git a/Marlin/src/feature/runout.cpp b/Marlin/src/feature/runout.cpp index 3cf81303dd..bd4a653e99 100644 --- a/Marlin/src/feature/runout.cpp +++ b/Marlin/src/feature/runout.cpp @@ -69,7 +69,7 @@ void FilamentSensorBase::filament_present(const uint8_t extruder) { #endif #if ENABLED(EXTENSIBLE_UI) - #include "../lcd/extensible_ui/ui_api.h" + #include "../lcd/extui/ui_api.h" #endif void event_filament_runout() { diff --git a/Marlin/src/feature/runout.h b/Marlin/src/feature/runout.h index 813f44e05e..b975551c6e 100644 --- a/Marlin/src/feature/runout.h +++ b/Marlin/src/feature/runout.h @@ -34,7 +34,7 @@ #include "../inc/MarlinConfig.h" #if ENABLED(EXTENSIBLE_UI) - #include "../lcd/extensible_ui/ui_api.h" + #include "../lcd/extui/ui_api.h" #endif #if ENABLED(ADVANCED_PAUSE_FEATURE) @@ -184,7 +184,7 @@ class FilamentSensorBase { #ifdef FILAMENT_RUNOUT_SENSOR_DEBUG if (change) { SERIAL_ECHOPGM("Motion detected:"); - for (uint8_t e = 0; e < NUM_RUNOUT_SENSORS; e++) + LOOP_L_N(e, NUM_RUNOUT_SENSORS) if (TEST(change, e)) SERIAL_CHAR(' ', '0' + e); SERIAL_EOL(); } diff --git a/Marlin/src/feature/tmc_util.cpp b/Marlin/src/feature/tmc_util.cpp index a2723fd393..e5e69eed50 100644 --- a/Marlin/src/feature/tmc_util.cpp +++ b/Marlin/src/feature/tmc_util.cpp @@ -22,7 +22,7 @@ #include "../inc/MarlinConfig.h" -#if HAS_TRINAMIC +#if HAS_TRINAMIC_CONFIG #include "tmc_util.h" #include "../MarlinCore.h" @@ -954,7 +954,7 @@ static void tmc_get_ic_registers(TMC2208Stepper, const TMC_get_registers_enum) { SERIAL_CHAR('\t'); } #endif - #if HAS_TRINAMIC + #if HAS_TRINAMIC_CONFIG template static void tmc_get_registers(TMC &st, const TMC_get_registers_enum i) { switch (i) { @@ -1257,4 +1257,4 @@ void test_tmc_connection(const bool test_x, const bool test_y, const bool test_z if (axis_connection) ui.set_status_P(GET_TEXT(MSG_ERROR_TMC)); } -#endif // HAS_TRINAMIC +#endif // HAS_TRINAMIC_CONFIG diff --git a/Marlin/src/feature/tmc_util.h b/Marlin/src/feature/tmc_util.h index 5102a9d5bf..ccae8b660c 100644 --- a/Marlin/src/feature/tmc_util.h +++ b/Marlin/src/feature/tmc_util.h @@ -24,7 +24,7 @@ #include "../inc/MarlinConfig.h" #include "../lcd/ultralcd.h" -#if HAS_TRINAMIC +#if HAS_TRINAMIC_CONFIG #include #include "../module/planner.h" @@ -400,4 +400,4 @@ void test_tmc_connection(const bool test_x, const bool test_y, const bool test_z void tmc_init_cs_pins(); #endif -#endif // HAS_TRINAMIC +#endif // HAS_TRINAMIC_CONFIG diff --git a/Marlin/src/feature/twibus.cpp b/Marlin/src/feature/twibus.cpp index f0687b34b3..60d78018a2 100644 --- a/Marlin/src/feature/twibus.cpp +++ b/Marlin/src/feature/twibus.cpp @@ -104,7 +104,7 @@ void TWIBus::echodata(uint8_t bytes, const char prefix[], uint8_t adr) { void TWIBus::echobuffer(const char prefix[], uint8_t adr) { echoprefix(buffer_s, prefix, adr); - for (uint8_t i = 0; i < buffer_s; i++) SERIAL_CHAR(buffer[i]); + LOOP_L_N(i, buffer_s) SERIAL_CHAR(buffer[i]); SERIAL_EOL(); } diff --git a/Marlin/src/gcode/bedlevel/G26.cpp b/Marlin/src/gcode/bedlevel/G26.cpp index b8ec262693..28fdf581ff 100644 --- a/Marlin/src/gcode/bedlevel/G26.cpp +++ b/Marlin/src/gcode/bedlevel/G26.cpp @@ -157,7 +157,7 @@ float g26_extrusion_multiplier, g26_layer_height, g26_prime_length; -xy_pos_t g26_pos; // = { 0, 0 } +xy_pos_t g26_xy_pos; // = { 0, 0 } int16_t g26_bed_temp, g26_hotend_temp; @@ -187,29 +187,27 @@ mesh_index_pair find_closest_circle_to_print(const xy_pos_t &pos) { out_point.pos = -1; - for (uint8_t i = 0; i < GRID_MAX_POINTS_X; i++) { - for (uint8_t j = 0; j < GRID_MAX_POINTS_Y; j++) { - if (!circle_flags.marked(i, j)) { - // We found a circle that needs to be printed - const xy_pos_t m = { _GET_MESH_X(i), _GET_MESH_Y(j) }; + GRID_LOOP(i, j) { + if (!circle_flags.marked(i, j)) { + // We found a circle that needs to be printed + const xy_pos_t m = { _GET_MESH_X(i), _GET_MESH_Y(j) }; - // Get the distance to this intersection - float f = (pos - m).magnitude(); + // Get the distance to this intersection + float f = (pos - m).magnitude(); - // It is possible that we are being called with the values - // to let us find the closest circle to the start position. - // But if this is not the case, add a small weighting to the - // distance calculation to help it choose a better place to continue. - f += (g26_pos - m).magnitude() / 15.0f; + // It is possible that we are being called with the values + // to let us find the closest circle to the start position. + // But if this is not the case, add a small weighting to the + // distance calculation to help it choose a better place to continue. + f += (g26_xy_pos - m).magnitude() / 15.0f; - // Add the specified amount of Random Noise to our search - if (random_deviation > 1.0) f += random(0.0, random_deviation); + // Add the specified amount of Random Noise to our search + if (random_deviation > 1.0) f += random(0.0, random_deviation); - if (f < closest) { - closest = f; // Found a closer un-printed location - out_point.pos.set(i, j); // Save its data - out_point.distance = closest; - } + if (f < closest) { + closest = f; // Found a closer un-printed location + out_point.pos.set(i, j); // Save its data + out_point.distance = closest; } } } @@ -308,51 +306,49 @@ inline bool look_for_lines_to_connect() { xyz_pos_t s, e; s.z = e.z = g26_layer_height; - for (uint8_t i = 0; i < GRID_MAX_POINTS_X; i++) { - for (uint8_t j = 0; j < GRID_MAX_POINTS_Y; j++) { + GRID_LOOP(i, j) { - #if HAS_LCD_MENU - if (user_canceled()) return true; - #endif + #if HAS_LCD_MENU + if (user_canceled()) return true; + #endif - if (i < GRID_MAX_POINTS_X) { // Can't connect to anything farther to the right than GRID_MAX_POINTS_X. + if (i < (GRID_MAX_POINTS_X)) { // Can't connect to anything farther to the right than GRID_MAX_POINTS_X. // Already a half circle at the edge of the bed. - if (circle_flags.marked(i, j) && circle_flags.marked(i + 1, j)) { // Test whether a leftward line can be done - if (!horizontal_mesh_line_flags.marked(i, j)) { - // Two circles need a horizontal line to connect them - s.x = _GET_MESH_X( i ) + (INTERSECTION_CIRCLE_RADIUS - (CROSSHAIRS_SIZE)); // right edge - e.x = _GET_MESH_X(i + 1) - (INTERSECTION_CIRCLE_RADIUS - (CROSSHAIRS_SIZE)); // left edge + if (circle_flags.marked(i, j) && circle_flags.marked(i + 1, j)) { // Test whether a leftward line can be done + if (!horizontal_mesh_line_flags.marked(i, j)) { + // Two circles need a horizontal line to connect them + s.x = _GET_MESH_X( i ) + (INTERSECTION_CIRCLE_RADIUS - (CROSSHAIRS_SIZE)); // right edge + e.x = _GET_MESH_X(i + 1) - (INTERSECTION_CIRCLE_RADIUS - (CROSSHAIRS_SIZE)); // left edge - LIMIT(s.x, X_MIN_POS + 1, X_MAX_POS - 1); - s.y = e.y = constrain(_GET_MESH_Y(j), Y_MIN_POS + 1, Y_MAX_POS - 1); - LIMIT(e.x, X_MIN_POS + 1, X_MAX_POS - 1); + LIMIT(s.x, X_MIN_POS + 1, X_MAX_POS - 1); + s.y = e.y = constrain(_GET_MESH_Y(j), Y_MIN_POS + 1, Y_MAX_POS - 1); + LIMIT(e.x, X_MIN_POS + 1, X_MAX_POS - 1); + + if (position_is_reachable(s.x, s.y) && position_is_reachable(e.x, e.y)) + print_line_from_here_to_there(s, e); + + horizontal_mesh_line_flags.mark(i, j); // Mark done, even if skipped + } + } + + if (j < (GRID_MAX_POINTS_Y)) { // Can't connect to anything further back than GRID_MAX_POINTS_Y. + // Already a half circle at the edge of the bed. + + if (circle_flags.marked(i, j) && circle_flags.marked(i, j + 1)) { // Test whether a downward line can be done + if (!vertical_mesh_line_flags.marked(i, j)) { + // Two circles that need a vertical line to connect them + s.y = _GET_MESH_Y( j ) + (INTERSECTION_CIRCLE_RADIUS - (CROSSHAIRS_SIZE)); // top edge + e.y = _GET_MESH_Y(j + 1) - (INTERSECTION_CIRCLE_RADIUS - (CROSSHAIRS_SIZE)); // bottom edge + + s.x = e.x = constrain(_GET_MESH_X(i), X_MIN_POS + 1, X_MAX_POS - 1); + LIMIT(s.y, Y_MIN_POS + 1, Y_MAX_POS - 1); + LIMIT(e.y, Y_MIN_POS + 1, Y_MAX_POS - 1); if (position_is_reachable(s.x, s.y) && position_is_reachable(e.x, e.y)) print_line_from_here_to_there(s, e); - horizontal_mesh_line_flags.mark(i, j); // Mark done, even if skipped - } - } - - if (j < GRID_MAX_POINTS_Y) { // Can't connect to anything further back than GRID_MAX_POINTS_Y. - // Already a half circle at the edge of the bed. - - if (circle_flags.marked(i, j) && circle_flags.marked(i, j + 1)) { // Test whether a downward line can be done - if (!vertical_mesh_line_flags.marked(i, j)) { - // Two circles that need a vertical line to connect them - s.y = _GET_MESH_Y( j ) + (INTERSECTION_CIRCLE_RADIUS - (CROSSHAIRS_SIZE)); // top edge - e.y = _GET_MESH_Y(j + 1) - (INTERSECTION_CIRCLE_RADIUS - (CROSSHAIRS_SIZE)); // bottom edge - - s.x = e.x = constrain(_GET_MESH_X(i), X_MIN_POS + 1, X_MAX_POS - 1); - LIMIT(s.y, Y_MIN_POS + 1, Y_MAX_POS - 1); - LIMIT(e.y, Y_MIN_POS + 1, Y_MAX_POS - 1); - - if (position_is_reachable(s.x, s.y) && position_is_reachable(e.x, e.y)) - print_line_from_here_to_there(s, e); - - vertical_mesh_line_flags.mark(i, j); // Mark done, even if skipped - } + vertical_mesh_line_flags.mark(i, j); // Mark done, even if skipped } } } @@ -628,9 +624,9 @@ void GcodeSuite::G26() { return; } - g26_pos.set(parser.seenval('X') ? RAW_X_POSITION(parser.value_linear_units()) : current_position.x, - parser.seenval('Y') ? RAW_Y_POSITION(parser.value_linear_units()) : current_position.y); - if (!position_is_reachable(g26_pos.x, g26_pos.y)) { + g26_xy_pos.set(parser.seenval('X') ? RAW_X_POSITION(parser.value_linear_units()) : current_position.x, + parser.seenval('Y') ? RAW_Y_POSITION(parser.value_linear_units()) : current_position.y); + if (!position_is_reachable(g26_xy_pos)) { SERIAL_ECHOLNPGM("?Specified X,Y coordinate out of bounds."); return; } @@ -640,10 +636,8 @@ void GcodeSuite::G26() { */ set_bed_leveling_enabled(!parser.seen('D')); - if (current_position.z < Z_CLEARANCE_BETWEEN_PROBES) { + if (current_position.z < Z_CLEARANCE_BETWEEN_PROBES) do_blocking_move_to_z(Z_CLEARANCE_BETWEEN_PROBES); - current_position = destination; - } #if DISABLED(NO_VOLUMETRICS) bool volumetric_was_enabled = parser.volumetric_enabled; @@ -697,7 +691,7 @@ void GcodeSuite::G26() { #error "A_CNT must be a positive value. Please change A_INT." #endif float trig_table[A_CNT]; - for (uint8_t i = 0; i < A_CNT; i++) + LOOP_L_N(i, A_CNT) trig_table[i] = INTERSECTION_CIRCLE_RADIUS * cos(RADIANS(i * A_INT)); #endif // !ARC_SUPPORT @@ -705,7 +699,7 @@ void GcodeSuite::G26() { mesh_index_pair location; do { // Find the nearest confluence - location = find_closest_circle_to_print(g26_continue_with_closest ? xy_pos_t(current_position) : g26_pos); + location = find_closest_circle_to_print(g26_continue_with_closest ? xy_pos_t(current_position) : g26_xy_pos); if (location.valid()) { const xy_pos_t circle = _GET_MESH_POS(location.pos); @@ -836,12 +830,9 @@ void GcodeSuite::G26() { retract_filament(destination); destination.z = Z_CLEARANCE_BETWEEN_PROBES; + move_to(destination, 0); // Raise the nozzle - move_to(destination, 0); // Raise the nozzle - - destination.set(g26_pos.x, g26_pos.y); // Move back to the starting position - //destination.z = Z_CLEARANCE_BETWEEN_PROBES; // Keep the nozzle where it is - + destination = g26_xy_pos; // Move back to the starting XY position move_to(destination, 0); // Move back to the starting position #if DISABLED(NO_VOLUMETRICS) diff --git a/Marlin/src/gcode/bedlevel/M420.cpp b/Marlin/src/gcode/bedlevel/M420.cpp index b84c60a6ae..d042ace8da 100644 --- a/Marlin/src/gcode/bedlevel/M420.cpp +++ b/Marlin/src/gcode/bedlevel/M420.cpp @@ -34,7 +34,7 @@ #endif #if ENABLED(EXTENSIBLE_UI) - #include "../../lcd/extensible_ui/ui_api.h" + #include "../../lcd/extui/ui_api.h" #endif //#define M420_C_USE_MEAN @@ -71,13 +71,12 @@ void GcodeSuite::M420() { bilinear_grid_spacing.set((x_max - x_min) / (GRID_MAX_POINTS_X - 1), (y_max - y_min) / (GRID_MAX_POINTS_Y - 1)); #endif - for (uint8_t x = 0; x < GRID_MAX_POINTS_X; x++) - for (uint8_t y = 0; y < GRID_MAX_POINTS_Y; y++) { - Z_VALUES(x, y) = 0.001 * random(-200, 200); - #if ENABLED(EXTENSIBLE_UI) - ExtUI::onMeshUpdate(x, y, Z_VALUES(x, y)); - #endif - } + GRID_LOOP(x, y) { + Z_VALUES(x, y) = 0.001 * random(-200, 200); + #if ENABLED(EXTENSIBLE_UI) + ExtUI::onMeshUpdate(x, y, Z_VALUES(x, y)); + #endif + } SERIAL_ECHOPGM("Simulated " STRINGIFY(GRID_MAX_POINTS_X) "x" STRINGIFY(GRID_MAX_POINTS_Y) " mesh "); SERIAL_ECHOPAIR(" (", x_min); SERIAL_CHAR(','); SERIAL_ECHO(y_min); diff --git a/Marlin/src/gcode/bedlevel/abl/G29.cpp b/Marlin/src/gcode/bedlevel/abl/G29.cpp index 5173505164..2d782e9e33 100644 --- a/Marlin/src/gcode/bedlevel/abl/G29.cpp +++ b/Marlin/src/gcode/bedlevel/abl/G29.cpp @@ -37,7 +37,7 @@ #include "../../queue.h" #if ENABLED(PROBE_TEMP_COMPENSATION) - #include "../../../feature/probe_temp_compensation.h" + #include "../../../feature/probe_temp_comp.h" #include "../../../module/temperature.h" #endif @@ -57,7 +57,7 @@ #include "../../../core/debug_out.h" #if ENABLED(EXTENSIBLE_UI) - #include "../../../lcd/extensible_ui/ui_api.h" + #include "../../../lcd/extui/ui_api.h" #endif #if HOTENDS > 1 @@ -417,17 +417,7 @@ G29_TYPE GcodeSuite::G29() { ); } - if ( - #if IS_SCARA || ENABLED(DELTA) - !position_is_reachable_by_probe(probe_position_lf.x, 0) - || !position_is_reachable_by_probe(probe_position_rb.x, 0) - || !position_is_reachable_by_probe(0, probe_position_lf.y) - || !position_is_reachable_by_probe(0, probe_position_rb.y) - #else - !position_is_reachable_by_probe(probe_position_lf) - || !position_is_reachable_by_probe(probe_position_rb) - #endif - ) { + if (!probe.good_bounds(probe_position_lf, probe_position_rb)) { SERIAL_ECHOLNPGM("? (L,R,F,B) out of bounds."); G29_RETURN(false); } @@ -704,7 +694,7 @@ G29_TYPE GcodeSuite::G29() { #if IS_KINEMATIC // Avoid probing outside the round or hexagonal area - if (!position_is_reachable_by_probe(probePos)) continue; + if (!probe.can_reach(probePos)) continue; #endif if (verbose_level) SERIAL_ECHOLNPAIR("Probing mesh point ", int(pt_index), "/", int(GRID_MAX_POINTS), "."); @@ -756,7 +746,7 @@ G29_TYPE GcodeSuite::G29() { // Probe at 3 arbitrary points - for (uint8_t i = 0; i < 3; ++i) { + LOOP_L_N(i, 3) { if (verbose_level) SERIAL_ECHOLNPAIR("Probing point ", int(i), "/3."); #if HAS_DISPLAY ui.status_printf_P(0, PSTR(S_FMT " %i/3"), GET_TEXT(MSG_PROBING_MESH), int(i)); @@ -871,7 +861,7 @@ G29_TYPE GcodeSuite::G29() { auto print_topo_map = [&](PGM_P const title, const bool get_min) { serialprintPGM(title); for (int8_t yy = abl_grid_points.y - 1; yy >= 0; yy--) { - for (uint8_t xx = 0; xx < abl_grid_points.x; xx++) { + LOOP_L_N(xx, abl_grid_points.x) { const int ind = indexIntoAB[xx][yy]; xyz_float_t tmp = { eqnAMatrix[ind + 0 * abl_points], eqnAMatrix[ind + 1 * abl_points], 0 }; diff --git a/Marlin/src/gcode/bedlevel/abl/M421.cpp b/Marlin/src/gcode/bedlevel/abl/M421.cpp index 85ff707575..3cd2673d66 100644 --- a/Marlin/src/gcode/bedlevel/abl/M421.cpp +++ b/Marlin/src/gcode/bedlevel/abl/M421.cpp @@ -32,7 +32,7 @@ #include "../../../feature/bedlevel/bedlevel.h" #if ENABLED(EXTENSIBLE_UI) - #include "../../../lcd/extensible_ui/ui_api.h" + #include "../../../lcd/extui/ui_api.h" #endif /** diff --git a/Marlin/src/gcode/bedlevel/mbl/G29.cpp b/Marlin/src/gcode/bedlevel/mbl/G29.cpp index 0a9a7f439b..6c8fafe23f 100644 --- a/Marlin/src/gcode/bedlevel/mbl/G29.cpp +++ b/Marlin/src/gcode/bedlevel/mbl/G29.cpp @@ -39,7 +39,7 @@ #include "../../../module/stepper.h" #if ENABLED(EXTENSIBLE_UI) - #include "../../../lcd/extensible_ui/ui_api.h" + #include "../../../lcd/extui/ui_api.h" #endif // Save 130 bytes with non-duplication of PSTR diff --git a/Marlin/src/gcode/bedlevel/ubl/M421.cpp b/Marlin/src/gcode/bedlevel/ubl/M421.cpp index ca4af1e0c0..bd65c21ad3 100644 --- a/Marlin/src/gcode/bedlevel/ubl/M421.cpp +++ b/Marlin/src/gcode/bedlevel/ubl/M421.cpp @@ -32,7 +32,7 @@ #include "../../../feature/bedlevel/bedlevel.h" #if ENABLED(EXTENSIBLE_UI) - #include "../../../lcd/extensible_ui/ui_api.h" + #include "../../../lcd/extui/ui_api.h" #endif /** diff --git a/Marlin/src/gcode/calibrate/G28.cpp b/Marlin/src/gcode/calibrate/G28.cpp index 6841636cf0..4603c76967 100644 --- a/Marlin/src/gcode/calibrate/G28.cpp +++ b/Marlin/src/gcode/calibrate/G28.cpp @@ -62,13 +62,7 @@ current_position.set(0.0, 0.0); sync_plan_position(); - const int x_axis_home_dir = - #if ENABLED(DUAL_X_CARRIAGE) - x_home_dir(active_extruder) - #else - home_dir(X_AXIS) - #endif - ; + const int x_axis_home_dir = x_home_dir(active_extruder); const float mlx = max_length(X_AXIS), mly = max_length(Y_AXIS), @@ -106,8 +100,6 @@ #if AXIS_HAS_STALLGUARD(Y2) tmc_disable_stallguard(stepperY2, stealth_states.y2); #endif - do_blocking_move_to_xy(-0.5 * x_axis_home_dir, -0.5 * home_dir(Y_AXIS), fr_mm_s / 2); - safe_delay(100); #endif } @@ -210,7 +202,7 @@ * Z Home to the Z endstop * */ -void GcodeSuite::G28(const bool always_home_all) { +void GcodeSuite::G28() { if (DEBUGGING(LEVELING)) { DEBUG_ECHOLNPGM(">>> G28"); log_machine_info(); @@ -310,8 +302,9 @@ void GcodeSuite::G28(const bool always_home_all) { #if ENABLED(DELTA) + constexpr bool doZ = true; // for NANODLP_Z_SYNC if your DLP is on a DELTA + home_delta(); - UNUSED(always_home_all); #if ENABLED(IMPROVE_HOMING_RELIABILITY) end_slow_homing(slow_homing); @@ -320,7 +313,7 @@ void GcodeSuite::G28(const bool always_home_all) { #else // NOT DELTA const bool homeX = parser.seen('X'), homeY = parser.seen('Y'), homeZ = parser.seen('Z'), - home_all = always_home_all || (homeX == homeY && homeX == homeZ), + home_all = homeX == homeY && homeX == homeZ, // All or None doX = home_all || homeX, doY = home_all || homeY, doZ = home_all || homeZ; destination = current_position; @@ -331,12 +324,10 @@ void GcodeSuite::G28(const bool always_home_all) { #endif - const float z_homing_height = ( - #if ENABLED(UNKNOWN_Z_NO_RAISE) - !TEST(axis_known_position, Z_AXIS) ? 0 : - #endif - (parser.seenval('R') ? parser.value_linear_units() : Z_HOMING_HEIGHT) - ); + const float z_homing_height = + (DISABLED(UNKNOWN_Z_NO_RAISE) || TEST(axis_known_position, Z_AXIS)) + ? (parser.seenval('R') ? parser.value_linear_units() : Z_HOMING_HEIGHT) + : 0; if (z_homing_height && (doX || doY)) { // Raise Z before homing any other axes and z is not already high enough (never lower z) @@ -356,20 +347,13 @@ void GcodeSuite::G28(const bool always_home_all) { // Home Y (before X) #if ENABLED(HOME_Y_BEFORE_X) - if (doY - #if ENABLED(CODEPENDENT_XY_HOMING) - || doX - #endif - ) homeaxis(Y_AXIS); + if (doY || (doX && ENABLED(CODEPENDENT_XY_HOMING))) + homeaxis(Y_AXIS); #endif // Home X - if (doX - #if ENABLED(CODEPENDENT_XY_HOMING) && DISABLED(HOME_Y_BEFORE_X) - || doY - #endif - ) { + if (doX || (doY && ENABLED(CODEPENDENT_XY_HOMING) && DISABLED(HOME_Y_BEFORE_X))) { #if ENABLED(DUAL_X_CARRIAGE) @@ -397,9 +381,8 @@ void GcodeSuite::G28(const bool always_home_all) { } // Home Y (after X) - #if DISABLED(HOME_Y_BEFORE_X) - if (doY) homeaxis(Y_AXIS); - #endif + if (DISABLED(HOME_Y_BEFORE_X) && doY) + homeaxis(Y_AXIS); #if ENABLED(IMPROVE_HOMING_RELIABILITY) end_slow_homing(slow_homing); @@ -488,7 +471,7 @@ void GcodeSuite::G28(const bool always_home_all) { do_blocking_move_to_z(delta_clip_start_height); #endif - #if HAS_LEVELING && ENABLED(RESTORE_LEVELING_AFTER_G28) + #if ENABLED(RESTORE_LEVELING_AFTER_G28) set_bed_leveling_enabled(leveling_was_active); #endif @@ -496,12 +479,7 @@ void GcodeSuite::G28(const bool always_home_all) { // Restore the active tool after homing #if HOTENDS > 1 && (DISABLED(DELTA) || ENABLED(DELTA_HOME_TO_SAFE_ZONE)) - #if EITHER(PARKING_EXTRUDER, DUAL_X_CARRIAGE) - #define NO_FETCH false // fetch the previous toolhead - #else - #define NO_FETCH true - #endif - tool_change(old_tool_index, NO_FETCH); + tool_change(old_tool_index, NONE(PARKING_EXTRUDER, DUAL_X_CARRIAGE)); // Do move if one of these #endif #if HAS_HOMING_CURRENT @@ -524,15 +502,8 @@ void GcodeSuite::G28(const bool always_home_all) { report_current_position(); - #if ENABLED(NANODLP_Z_SYNC) - #if ENABLED(NANODLP_ALL_AXIS) - #define _HOME_SYNC true // For any axis, output sync text. - #else - #define _HOME_SYNC doZ // Only for Z-axis - #endif - if (_HOME_SYNC) - SERIAL_ECHOLNPGM(STR_Z_MOVE_COMP); - #endif + if (ENABLED(NANODLP_Z_SYNC) && (doZ || ENABLED(NANODLP_ALL_AXIS))) + SERIAL_ECHOLNPGM(STR_Z_MOVE_COMP); if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("<<< G28"); diff --git a/Marlin/src/gcode/calibrate/G34_M422.cpp b/Marlin/src/gcode/calibrate/G34_M422.cpp index e7bc63828f..672f40737a 100644 --- a/Marlin/src/gcode/calibrate/G34_M422.cpp +++ b/Marlin/src/gcode/calibrate/G34_M422.cpp @@ -64,6 +64,7 @@ inline void set_all_z_lock(const bool lock) { * I * T * A + * R points based on current probe offsets */ void GcodeSuite::G34() { if (DEBUGGING(LEVELING)) { @@ -73,8 +74,10 @@ void GcodeSuite::G34() { do { // break out on error - #if NUM_Z_STEPPER_DRIVERS >= 4 - SERIAL_ECHOLNPGM("Alignment not supported for over 3 steppers"); + #if NUM_Z_STEPPER_DRIVERS == 4 + SERIAL_ECHOLNPGM("Alignment for 4 steppers is Experimental!"); + #elif NUM_Z_STEPPER_DRIVERS > 4 + SERIAL_ECHOLNPGM("Alignment not supported for over 4 steppers"); break; #endif @@ -101,6 +104,8 @@ void GcodeSuite::G34() { } #endif + if (parser.seen('R')) z_stepper_align.reset_to_default(); + const ProbePtRaise raise_after = parser.boolval('E') ? PROBE_PT_STOW : PROBE_PT_RAISE; // Wait for planner moves to finish! @@ -139,13 +144,18 @@ void GcodeSuite::G34() { // Compute a worst-case clearance height to probe from. After the first // iteration this will be re-calculated based on the actual bed position - float z_probe = Z_BASIC_CLEARANCE + (G34_MAX_GRADE) * 0.01f * ( + auto magnitude2 = [&](const uint8_t i, const uint8_t j) { + const xy_pos_t diff = z_stepper_align.xy[i] - z_stepper_align.xy[j]; + return HYPOT2(diff.x, diff.y); + }; + float z_probe = Z_BASIC_CLEARANCE + (G34_MAX_GRADE) * 0.01f * SQRT( #if NUM_Z_STEPPER_DRIVERS == 3 - SQRT(_MAX(HYPOT2(z_stepper_align.xy[0].x - z_stepper_align.xy[0].y, z_stepper_align.xy[1].x - z_stepper_align.xy[1].y), - HYPOT2(z_stepper_align.xy[1].x - z_stepper_align.xy[1].y, z_stepper_align.xy[2].x - z_stepper_align.xy[2].y), - HYPOT2(z_stepper_align.xy[2].x - z_stepper_align.xy[2].y, z_stepper_align.xy[0].x - z_stepper_align.xy[0].y))) + _MAX(magnitude2(0, 1), magnitude2(1, 2), magnitude2(2, 0)) + #elif NUM_Z_STEPPER_DRIVERS == 4 + _MAX(magnitude2(0, 1), magnitude2(1, 2), magnitude2(2, 3), + magnitude2(3, 0), magnitude2(0, 2), magnitude2(1, 3)) #else - HYPOT(z_stepper_align.xy[0].x - z_stepper_align.xy[0].y, z_stepper_align.xy[1].x - z_stepper_align.xy[1].y) + magnitude2(0, 1) #endif ); @@ -153,31 +163,42 @@ void GcodeSuite::G34() { if (!all_axes_known()) home_all_axes(); // Move the Z coordinate realm towards the positive - dirty trick - current_position.z -= z_probe * 0.5f; + current_position.z += z_probe * 0.5f; + sync_plan_position(); + // Now, the Z origin lies below the build plate. That allows to probe deeper, before run_z_probe throws an error. + // This hack is un-done at the end of G34 - either by re-homing, or by using the probed heights of the last iteration. - float last_z_align_move[NUM_Z_STEPPER_DRIVERS] = ARRAY_N(NUM_Z_STEPPER_DRIVERS, 10000.0f, 10000.0f, 10000.0f), - z_measured[NUM_Z_STEPPER_DRIVERS] = { 0 }, + #if DISABLED(Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS) + float last_z_align_move[NUM_Z_STEPPER_DRIVERS] = ARRAY_N(NUM_Z_STEPPER_DRIVERS, 10000.0f, 10000.0f, 10000.0f, 10000.0f); + #else + float last_z_align_level_indicator = 10000.0f; + #endif + float z_measured[NUM_Z_STEPPER_DRIVERS] = { 0 }, z_maxdiff = 0.0f, amplification = z_auto_align_amplification; + // These are needed after the for-loop uint8_t iteration; bool err_break = false; + float z_measured_min; #if DISABLED(Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS) bool adjustment_reverse = false; #endif + // 'iteration' is declared above and is also used after the for-loop. + // *not* the same as LOOP_L_N(iteration, z_auto_align_iterations) for (iteration = 0; iteration < z_auto_align_iterations; ++iteration) { if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("> probing all positions."); SERIAL_ECHOLNPAIR("\nITERATION: ", int(iteration + 1)); // Initialize minimum value - float z_measured_min = 100000.0f, - z_measured_max = -100000.0f; + z_measured_min = 100000.0f; + float z_measured_max = -100000.0f; // Probe all positions (one per Z-Stepper) - for (uint8_t i = 0; i < NUM_Z_STEPPER_DRIVERS; ++i) { + LOOP_L_N(i, NUM_Z_STEPPER_DRIVERS) { // iteration odd/even --> downward / upward stepper sequence const uint8_t iprobe = (iteration & 1) ? NUM_Z_STEPPER_DRIVERS - 1 - i : i; @@ -188,7 +209,9 @@ void GcodeSuite::G34() { DEBUG_ECHOLNPAIR_P(PSTR("Probing X"), z_stepper_align.xy[iprobe].x, SP_Y_STR, z_stepper_align.xy[iprobe].y); // Probe a Z height for each stepper. - const float z_probed_height = probe.probe_at_point(z_stepper_align.xy[iprobe], raise_after, 0, true); + // Probing sanity check is disabled, as it would trigger even in normal cases because + // current_position.z has been manually altered in the "dirty trick" above. + const float z_probed_height = probe.probe_at_point(z_stepper_align.xy[iprobe], raise_after, 0, true, false); if (isnan(z_probed_height)) { SERIAL_ECHOLNPGM("Probing failed."); err_break = true; @@ -227,15 +250,15 @@ void GcodeSuite::G34() { // This allows the actual adjustment logic to be shared by both algorithms. linear_fit_data lfd; incremental_LSF_reset(&lfd); - for (uint8_t i = 0; i < NUM_Z_STEPPER_DRIVERS; ++i) { - SERIAL_ECHOLNPAIR("PROBEPT_", i + '1', ": ", z_measured[i]); + LOOP_L_N(i, NUM_Z_STEPPER_DRIVERS) { + SERIAL_ECHOLNPAIR("PROBEPT_", int(i), ": ", z_measured[i]); incremental_LSF(&lfd, z_stepper_align.xy[i], z_measured[i]); } finish_incremental_LSF(&lfd); z_measured_min = 100000.0f; - for (uint8_t i = 0; i < NUM_Z_STEPPER_DRIVERS; ++i) { - z_measured[i] = -(lfd.A * z_stepper_align.stepper_xy[i].x + lfd.B * z_stepper_align.stepper_xy[i].y); + LOOP_L_N(i, NUM_Z_STEPPER_DRIVERS) { + z_measured[i] = -(lfd.A * z_stepper_align.stepper_xy[i].x + lfd.B * z_stepper_align.stepper_xy[i].y + lfd.D); z_measured_min = _MIN(z_measured_min, z_measured[i]); } @@ -250,12 +273,37 @@ void GcodeSuite::G34() { #endif ); + #if ENABLED(Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS) + // Check if the applied corrections go in the correct direction. + // Calculate the sum of the absolute deviations from the mean of the probe measurements. + // Compare to the last iteration to ensure it's getting better. + + // Calculate mean value as a reference + float z_measured_mean = 0.0f; + LOOP_L_N(zstepper, NUM_Z_STEPPER_DRIVERS) z_measured_mean += z_measured[zstepper]; + z_measured_mean /= NUM_Z_STEPPER_DRIVERS; + + // Calculate the sum of the absolute deviations from the mean value + float z_align_level_indicator = 0.0f; + LOOP_L_N(zstepper, NUM_Z_STEPPER_DRIVERS) + z_align_level_indicator += ABS(z_measured[zstepper] - z_measured_mean); + + // If it's getting worse, stop and throw an error + if (last_z_align_level_indicator < z_align_level_indicator * 0.7f) { + SERIAL_ECHOLNPGM("Decreasing accuracy detected."); + err_break = true; + break; + } + + last_z_align_level_indicator = z_align_level_indicator; + #endif + // The following correction actions are to be enabled for select Z-steppers only stepper.set_separate_multi_axis(true); bool success_break = true; // Correct the individual stepper offsets - for (uint8_t zstepper = 0; zstepper < NUM_Z_STEPPER_DRIVERS; ++zstepper) { + LOOP_L_N(zstepper, NUM_Z_STEPPER_DRIVERS) { // Calculate current stepper move float z_align_move = z_measured[zstepper] - z_measured_min; const float z_align_abs = ABS(z_align_move); @@ -263,21 +311,16 @@ void GcodeSuite::G34() { #if DISABLED(Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS) // Optimize one iteration's correction based on the first measurements if (z_align_abs) amplification = (iteration == 1) ? _MIN(last_z_align_move[zstepper] / z_align_abs, 2.0f) : z_auto_align_amplification; - #endif - // Check for less accuracy compared to last move - if (last_z_align_move[zstepper] < z_align_abs * 0.7f) { - SERIAL_ECHOLNPGM("Decreasing accuracy detected."); - #if DISABLED(Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS) + // Check for less accuracy compared to last move + if (last_z_align_move[zstepper] < z_align_abs * 0.7f) { + SERIAL_ECHOLNPGM("Decreasing accuracy detected."); adjustment_reverse = !adjustment_reverse; - #else - err_break = true; - break; - #endif - } + } - // Remember the alignment for the next iteration - last_z_align_move[zstepper] = z_align_abs; + // Remember the alignment for the next iteration + last_z_align_move[zstepper] = z_align_abs; + #endif // Stop early if all measured points achieve accuracy target if (z_align_abs > z_auto_align_accuracy) success_break = false; @@ -289,9 +332,12 @@ void GcodeSuite::G34() { switch (zstepper) { case 0: stepper.set_z_lock(false); break; case 1: stepper.set_z2_lock(false); break; - #if NUM_Z_STEPPER_DRIVERS == 3 + #if NUM_Z_STEPPER_DRIVERS >= 3 case 2: stepper.set_z3_lock(false); break; #endif + #if NUM_Z_STEPPER_DRIVERS == 4 + case 3: stepper.set_z4_lock(false); break; + #endif } #if DISABLED(Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS) @@ -315,35 +361,38 @@ void GcodeSuite::G34() { } // for (iteration) - if (err_break) { SERIAL_ECHOLNPGM("G34 aborted."); break; } - - SERIAL_ECHOLNPAIR("Did ", int(iteration + (iteration != z_auto_align_iterations)), " iterations of ", int(z_auto_align_iterations)); - SERIAL_ECHOLNPAIR_F("Accuracy: ", z_maxdiff); - - // Restore the active tool after homing - #if HOTENDS > 1 - tool_change(old_tool_index, ( - #if ENABLED(PARKING_EXTRUDER) - false // Fetch the previous toolhead - #else - true - #endif - )); - #endif - - #if HAS_LEVELING && ENABLED(RESTORE_LEVELING_AFTER_G34) - set_bed_leveling_enabled(leveling_was_active); - #endif - - // After this operation the z position needs correction - set_axis_is_not_at_home(Z_AXIS); + if (err_break) + SERIAL_ECHOLNPGM("G34 aborted."); + else { + SERIAL_ECHOLNPAIR("Did ", int(iteration + (iteration != z_auto_align_iterations)), " of ", int(z_auto_align_iterations)); + SERIAL_ECHOLNPAIR_F("Accuracy: ", z_maxdiff); + } // Stow the probe, as the last call to probe.probe_at_point(...) left // the probe deployed if it was successful. probe.stow(); - // Home Z after the alignment procedure - process_subcommands_now_P(PSTR("G28 Z")); + #if ENABLED(HOME_AFTER_G34) + // After this operation the z position needs correction + set_axis_not_trusted(Z_AXIS); + // Home Z after the alignment procedure + process_subcommands_now_P(PSTR("G28Z")); + #else + // Use the probed height from the last iteration to determine the Z height. + // z_measured_min is used, because all steppers are aligned to z_measured_min. + // Ideally, this would be equal to the 'z_probe * 0.5f' which was added earlier. + current_position.z -= z_measured_min - (float)Z_CLEARANCE_BETWEEN_PROBES; + sync_plan_position(); + #endif + + // Restore the active tool after homing + #if HOTENDS > 1 + tool_change(old_tool_index, DISABLED(PARKING_EXTRUDER)); // Fetch previous tool for parking extruder + #endif + + #if HAS_LEVELING && ENABLED(RESTORE_LEVELING_AFTER_G34) + set_bed_leveling_enabled(leveling_was_active); + #endif }while(0); @@ -363,15 +412,22 @@ void GcodeSuite::G34() { * S and W require an X and/or Y parameter * X : X position to set (Unchanged if omitted) * Y : Y position to set (Unchanged if omitted) + * + * R : Recalculate points based on current probe offsets */ void GcodeSuite::M422() { + if (parser.seen('R')) { + z_stepper_align.reset_to_default(); + return; + } + if (!parser.seen_any()) { - for (uint8_t i = 0; i < NUM_Z_STEPPER_DRIVERS; ++i) - SERIAL_ECHOLNPAIR_P(PSTR("M422 S"), i + '1', SP_X_STR, z_stepper_align.xy[i].x, SP_Y_STR, z_stepper_align.xy[i].y); + LOOP_L_N(i, NUM_Z_STEPPER_DRIVERS) + SERIAL_ECHOLNPAIR_P(PSTR("M422 S"), int(i + 1), SP_X_STR, z_stepper_align.xy[i].x, SP_Y_STR, z_stepper_align.xy[i].y); #if ENABLED(Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS) - for (uint8_t i = 0; i < NUM_Z_STEPPER_DRIVERS; ++i) - SERIAL_ECHOLNPAIR_P(PSTR("M422 W"), i + '1', SP_X_STR, z_stepper_align.stepper_xy[i].x, SP_Y_STR, z_stepper_align.stepper_xy[i].y); + LOOP_L_N(i, NUM_Z_STEPPER_DRIVERS) + SERIAL_ECHOLNPAIR_P(PSTR("M422 W"), int(i + 1), SP_X_STR, z_stepper_align.stepper_xy[i].x, SP_Y_STR, z_stepper_align.stepper_xy[i].y); #endif return; } @@ -432,11 +488,11 @@ void GcodeSuite::M422() { }; if (is_probe_point) { - if (!position_is_reachable_by_probe(pos.x, Y_CENTER)) { + if (!probe.can_reach(pos.x, Y_CENTER)) { SERIAL_ECHOLNPGM("?(X) out of bounds."); return; } - if (!position_is_reachable_by_probe(pos)) { + if (!probe.can_reach(pos)) { SERIAL_ECHOLNPGM("?(Y) out of bounds."); return; } diff --git a/Marlin/src/gcode/calibrate/G425.cpp b/Marlin/src/gcode/calibrate/G425.cpp index d2db4ce308..69fb29165d 100644 --- a/Marlin/src/gcode/calibrate/G425.cpp +++ b/Marlin/src/gcode/calibrate/G425.cpp @@ -56,8 +56,12 @@ #define CALIBRATION_MEASUREMENT_CERTAIN 0.5 // mm #endif -#define HAS_X_CENTER BOTH(CALIBRATION_MEASURE_LEFT, CALIBRATION_MEASURE_RIGHT) -#define HAS_Y_CENTER BOTH(CALIBRATION_MEASURE_FRONT, CALIBRATION_MEASURE_BACK) +#if BOTH(CALIBRATION_MEASURE_LEFT, CALIBRATION_MEASURE_RIGHT) + #define HAS_X_CENTER 1 +#endif +#if BOTH(CALIBRATION_MEASURE_FRONT, CALIBRATION_MEASURE_BACK) + #define HAS_Y_CENTER 1 +#endif enum side_t : uint8_t { TOP, RIGHT, FRONT, LEFT, BACK, NUM_SIDES }; @@ -120,7 +124,7 @@ inline void park_above_object(measurements_t &m, const float uncertainty) { #if HAS_HOTEND_OFFSET inline void normalize_hotend_offsets() { - for (uint8_t e = 1; e < HOTENDS; e++) + LOOP_S_L_N(e, 1, HOTENDS) hotend_offset[e] -= hotend_offset[0]; hotend_offset[0].reset(); } @@ -389,7 +393,7 @@ inline void probe_sides(measurements_t &m, const float uncertainty) { // This function requires normalize_hotend_offsets() to be called // inline void report_hotend_offsets() { - for (uint8_t e = 1; e < HOTENDS; e++) + LOOP_S_L_N(e, 1, HOTENDS) SERIAL_ECHOLNPAIR_P(PSTR("T"), int(e), PSTR(" Hotend Offset X"), hotend_offset[e].x, SP_Y_STR, hotend_offset[e].y, SP_Z_STR, hotend_offset[e].z); } #endif diff --git a/Marlin/src/gcode/calibrate/G76_M871.cpp b/Marlin/src/gcode/calibrate/G76_M871.cpp index 4340084ec6..c878f83a17 100644 --- a/Marlin/src/gcode/calibrate/G76_M871.cpp +++ b/Marlin/src/gcode/calibrate/G76_M871.cpp @@ -35,7 +35,7 @@ #include "../../feature/bedlevel/bedlevel.h" #include "../../module/temperature.h" #include "../../module/probe.h" -#include "../../feature/probe_temp_compensation.h" +#include "../../feature/probe_temp_comp.h" /** * G76: calibrate probe and/or bed temperature offsets @@ -86,142 +86,115 @@ void GcodeSuite::G76() { return; #endif + auto report_temps = [](millis_t &ntr, millis_t timeout=0) { + idle_no_sleep(); + const millis_t ms = millis(); + if (ELAPSED(ms, ntr)) { + ntr = ms + 1000; + thermalManager.print_heater_states(active_extruder); + } + return (timeout && ELAPSED(ms, timeout)); + }; + + auto wait_for_temps = [&](const float tb, const float tp, millis_t &ntr, const millis_t timeout=0) { + SERIAL_ECHOLNPGM("Waiting for bed and probe temperature."); + while (fabs(thermalManager.degBed() - tb) > 0.1f || thermalManager.degProbe() > tp) + if (report_temps(ntr, timeout)) return true; + return false; + }; + + auto g76_probe = [](const xy_pos_t &xypos) { + do_blocking_move_to_z(5.0); // Raise nozzle before probing + const float measured_z = probe.probe_at_point(xypos, PROBE_PT_NONE, 0, false); // verbose=0, probe_relative=false + if (isnan(measured_z)) + SERIAL_ECHOLNPGM("!Received NAN. Aborting."); + else + SERIAL_ECHOLNPAIR_F("Measured: ", measured_z); + return measured_z; + }; + #if ENABLED(BLTOUCH) // Make sure any BLTouch error condition is cleared bltouch_command(BLTOUCH_RESET, BLTOUCH_RESET_DELAY); set_bltouch_deployed(false); #endif - bool do_bed_cal = parser.boolval('B'), - do_probe_cal = parser.boolval('P'); - if (!do_bed_cal && !do_probe_cal) - do_bed_cal = do_probe_cal = true; + bool do_bed_cal = parser.boolval('B'), do_probe_cal = parser.boolval('P'); + if (!do_bed_cal && !do_probe_cal) do_bed_cal = do_probe_cal = true; // Synchronize with planner planner.synchronize(); - // Report temperatures every second and handle heating timeouts - millis_t next_temp_report = millis() + 1000; + const xyz_pos_t parkpos = { temp_comp.park_point_x, temp_comp.park_point_y, temp_comp.park_point_z }; + const xy_pos_t ppos = { temp_comp.measure_point_x, temp_comp.measure_point_y }; if (do_bed_cal || do_probe_cal) { // Ensure park position is reachable - if (!position_is_reachable(ProbeTempComp::park_point.x, ProbeTempComp::park_point.y) - || !(WITHIN(ProbeTempComp::park_point.z, Z_MIN_POS - 0.001f, Z_MAX_POS + 0.001f)) - ) { - SERIAL_ECHOLNPGM("!Park position unreachable - aborting."); - return; + bool reachable = position_is_reachable(parkpos) || WITHIN(parkpos.z, Z_MIN_POS - fslop, Z_MAX_POS + fslop); + if (!reachable) + SERIAL_ECHOLNPGM("!Park"); + else { + // Ensure probe position is reachable + reachable = probe.can_reach(ppos); + if (!reachable) SERIAL_ECHOLNPGM("!Probe"); } - // Ensure probe position is reachable - destination.set( - temp_comp.measure_point_x - probe.offset_xy.x, - temp_comp.measure_point_y - probe.offset_xy.y - ); - if (!position_is_reachable_by_probe(destination)) { - SERIAL_ECHOLNPGM("!Probe position unreachable - aborting."); + + if (!reachable) { + SERIAL_ECHOLNPGM(" position unreachable - aborting."); return; } - G28(true); + process_subcommands_now_P(PSTR("G28")); } + remember_feedrate_scaling_off(); + + // Nozzle position based on probe position + const xy_pos_t noz_pos = ppos - probe.offset_xy; + /****************************************** * Calibrate bed temperature offsets ******************************************/ + // Report temperatures every second and handle heating timeouts + millis_t next_temp_report = millis() + 1000; + if (do_bed_cal) { uint16_t target_bed = temp_comp.cali_info_init[TSI_BED].start_temp, target_probe = temp_comp.bed_calib_probe_temp; - SERIAL_ECHOLNPGM("Waiting for printer to cool down."); - while (thermalManager.degBed() > target_bed - || thermalManager.degProbe() > target_probe - ) { - idle( - #if ENABLED(ADVANCED_PAUSE_FEATURE) - true - #endif - ); - const millis_t ms = millis(); - if (ELAPSED(ms, next_temp_report)) { - thermalManager.print_heater_states(active_extruder); - next_temp_report = ms + 1000; - } - } + SERIAL_ECHOLNPGM("Waiting for cooling."); + while (thermalManager.degBed() > target_bed || thermalManager.degProbe() > target_probe) + report_temps(next_temp_report); // Disable leveling so it won't mess with us #if HAS_LEVELING set_bed_leveling_enabled(false); #endif - bool timeout = false; - while (true) { + for (;;) { thermalManager.setTargetBed(target_bed); - SERIAL_ECHOLNPAIR("Target Bed: ", target_bed, "; Probe: ", target_probe); + SERIAL_ECHOLNPAIR("Target Bed:", target_bed, " Probe:", target_probe); // Park nozzle - do_blocking_move_to(ProbeTempComp::park_point.x, ProbeTempComp::park_point.y, ProbeTempComp::park_point.z); + do_blocking_move_to(parkpos); // Wait for heatbed to reach target temp and probe to cool below target temp - SERIAL_ECHOLNPGM("Waiting for bed and probe to reach target temp."); - const millis_t probe_timeout_ms = millis() + 900UL * 1000UL; - while (fabs(thermalManager.degBed() - float(target_bed)) > 0.1 || thermalManager.degProbe() > target_probe) { - idle( - #if ENABLED(ADVANCED_PAUSE_FEATURE) - true - #endif - ); - const millis_t ms = millis(); - if (ELAPSED(ms, next_temp_report)) { - thermalManager.print_heater_states(active_extruder); - next_temp_report = ms + 1000; - } - if (ELAPSED(ms, probe_timeout_ms)) { - SERIAL_ECHOLNPGM("!Bed heating timeout."); - timeout = true; - break; - } - } - - if (timeout) break; - - // Move probe to probing point and wait for probe to reach target temp - destination.set(temp_comp.measure_point_x, temp_comp.measure_point_y, 0.5); - do_blocking_move_to(destination.x, destination.y, destination.z); - SERIAL_ECHOLNPGM("Waiting for probe heating."); - while (thermalManager.degProbe() < target_probe) { - idle( - #if ENABLED(ADVANCED_PAUSE_FEATURE) - true - #endif - ); - const millis_t ms = millis(); - if (ELAPSED(ms, next_temp_report)) { - thermalManager.print_heater_states(active_extruder); - next_temp_report = ms + 1000; - } - } - - // Raise nozzle before probing - destination.z = 5.0; - do_blocking_move_to_z(destination.z); - - // Do a single probe - remember_feedrate_scaling_off(); - const float measured_z = probe.probe_at_point( - destination.x + probe.offset_xy.x, - destination.y + probe.offset_xy.y, - PROBE_PT_NONE - ); - restore_feedrate_and_scaling(); - - if (isnan(measured_z)) { - SERIAL_ECHOLNPGM("!Received NAN measurement - aborting."); + if (wait_for_temps(target_bed, target_probe, next_temp_report, millis() + 900UL * 1000UL)) { + SERIAL_ECHOLNPGM("!Bed heating timeout."); break; } - else - SERIAL_ECHOLNPAIR_F("Measured: ", measured_z); + + // Move the nozzle to the probing point and wait for the probe to reach target temp + do_blocking_move_to_xy(noz_pos); + SERIAL_ECHOLNPGM("Waiting for probe heating."); + while (thermalManager.degProbe() < target_probe) + report_temps(next_temp_report); + + const float measured_z = g76_probe(noz_pos); + if (isnan(measured_z)) break; if (target_bed == temp_comp.cali_info_init[TSI_BED].start_temp) temp_comp.prepare_new_calibration(measured_z); @@ -236,7 +209,7 @@ void GcodeSuite::G76() { if (temp_comp.finish_calibration(TSI_BED)) SERIAL_ECHOLNPGM("Successfully calibrated bed."); else - SERIAL_ECHOLNPGM("!Failed to calibrated bed - reset calibration values."); + SERIAL_ECHOLNPGM("!Failed to calibrate bed. Values reset."); // Cleanup thermalManager.setTargetBed(0); @@ -252,27 +225,16 @@ void GcodeSuite::G76() { if (do_probe_cal) { // Park nozzle - do_blocking_move_to(ProbeTempComp::park_point.x, ProbeTempComp::park_point.y, ProbeTempComp::park_point.z); + do_blocking_move_to(parkpos); // Initialize temperatures - uint16_t target_bed = temp_comp.probe_calib_bed_temp, - target_probe = temp_comp.cali_info_init[TSI_PROBE].start_temp; + const uint16_t target_bed = temp_comp.probe_calib_bed_temp; thermalManager.setTargetBed(target_bed); - SERIAL_ECHOLNPGM("Waiting for bed and probe temperature."); - while (fabs(thermalManager.degBed() - float(target_bed)) > 0.1f - || thermalManager.degProbe() > target_probe - ) { - idle( - #if ENABLED(ADVANCED_PAUSE_FEATURE) - true - #endif - ); - const millis_t ms = millis(); - if (ELAPSED(ms, next_temp_report)) { - thermalManager.print_heater_states(active_extruder); - next_temp_report = ms + 1000; - } - } + + uint16_t target_probe = temp_comp.cali_info_init[TSI_PROBE].start_temp; + + // Wait for heatbed to reach target temp and probe to cool below target temp + wait_for_temps(target_bed, target_probe, next_temp_report); // Disable leveling so it won't mess with us #if HAS_LEVELING @@ -280,57 +242,23 @@ void GcodeSuite::G76() { #endif bool timeout = false; - while (true) { + for (;;) { // Move probe to probing point and wait for it to reach target temperature - destination.set(temp_comp.measure_point_x, temp_comp.measure_point_y, 0.5); - do_blocking_move_to(destination); - - SERIAL_ECHOLNPAIR( - "Bed temp: ", target_bed, - "; Probe temp: ", target_probe, - " Waiting for probe heating." - ); + do_blocking_move_to_xy(noz_pos); + SERIAL_ECHOLNPAIR("Waiting for probe heating. Bed:", target_bed, " Probe:", target_probe); const millis_t probe_timeout_ms = millis() + 900UL * 1000UL; while (thermalManager.degProbe() < target_probe) { - idle( - #if ENABLED(ADVANCED_PAUSE_FEATURE) - true - #endif - ); - const millis_t ms = millis(); - if (ELAPSED(ms, next_temp_report)) { - thermalManager.print_heater_states(active_extruder); - next_temp_report = ms + 1000; - } - if (ELAPSED(ms, probe_timeout_ms)) { - SERIAL_ECHOLNPGM("!Probe heating aborted due to timeout."); + if (report_temps(next_temp_report, probe_timeout_ms)) { + SERIAL_ECHOLNPGM("!Probe heating timed out."); timeout = true; break; } } - if (timeout) break; - // Raise nozzle before probing - destination.z = 5.0; - do_blocking_move_to_z(destination.z); - - // Do a single probe - remember_feedrate_scaling_off(); - const float measured_z = probe.probe_at_point( - destination.x + probe.offset_xy.x, - destination.y + probe.offset_xy.y, - PROBE_PT_NONE - ); - restore_feedrate_and_scaling(); - - if (isnan(measured_z)) { - SERIAL_ECHOLNPGM("!Received NAN measurement - aborting."); - break; - } - else - SERIAL_ECHOLNPAIR_F("Measured: ", measured_z); + const float measured_z = g76_probe(noz_pos); + if (isnan(measured_z)) break; if (target_probe == temp_comp.cali_info_init[TSI_PROBE].start_temp) temp_comp.prepare_new_calibration(measured_z); @@ -343,9 +271,10 @@ void GcodeSuite::G76() { SERIAL_ECHOLNPAIR("Retrieved measurements: ", temp_comp.get_index()); if (temp_comp.finish_calibration(TSI_PROBE)) - SERIAL_ECHOLNPGM("Successfully calibrated probe."); + SERIAL_ECHOPGM("Successfully calibrated"); else - SERIAL_ECHOLNPGM("!Failed to calibrated probe."); + SERIAL_ECHOPGM("!Failed to calibrate"); + SERIAL_ECHOLNPGM(" probe."); // Cleanup thermalManager.setTargetBed(0); @@ -356,6 +285,8 @@ void GcodeSuite::G76() { SERIAL_ECHOLNPGM("Final compensation values:"); temp_comp.print_offsets(); } // do_probe_cal + + restore_feedrate_and_scaling(); } /** diff --git a/Marlin/src/gcode/calibrate/M100.cpp b/Marlin/src/gcode/calibrate/M100.cpp index 274caeec1d..6b8a0de528 100644 --- a/Marlin/src/gcode/calibrate/M100.cpp +++ b/Marlin/src/gcode/calibrate/M100.cpp @@ -158,14 +158,14 @@ inline int32_t count_test_bytes(const char * const start_free_memory) { while (start_free_memory < end_free_memory) { print_hex_address(start_free_memory); // Print the address SERIAL_CHAR(':'); - for (uint8_t i = 0; i < 16; i++) { // and 16 data bytes + LOOP_L_N(i, 16) { // and 16 data bytes if (i == 8) SERIAL_CHAR('-'); print_hex_byte(start_free_memory[i]); SERIAL_CHAR(' '); } serial_delay(25); SERIAL_CHAR('|'); // Point out non test bytes - for (uint8_t i = 0; i < 16; i++) { + LOOP_L_N(i, 16) { char ccc = (char)start_free_memory[i]; // cast to char before automatically casting to char on assignment, in case the compiler is broken ccc = (ccc == TEST_BYTE) ? ' ' : '?'; SERIAL_CHAR(ccc); diff --git a/Marlin/src/gcode/calibrate/M425.cpp b/Marlin/src/gcode/calibrate/M425.cpp index a54c7cf746..41c80daf7c 100644 --- a/Marlin/src/gcode/calibrate/M425.cpp +++ b/Marlin/src/gcode/calibrate/M425.cpp @@ -47,7 +47,7 @@ void GcodeSuite::M425() { bool noArgs = true; LOOP_XYZ(a) { - if (parser.seen(axis_codes[a])) { + if (parser.seen(XYZ_CHAR(a))) { planner.synchronize(); backlash.distance_mm[a] = parser.has_value() ? parser.value_linear_units() : backlash.get_measurement(AxisEnum(a)); noArgs = false; @@ -75,7 +75,7 @@ void GcodeSuite::M425() { SERIAL_ECHOLNPAIR(" Correction Amount/Fade-out: F", backlash.get_correction(), " (F1.0 = full, F0.0 = none)"); SERIAL_ECHOPGM(" Backlash Distance (mm): "); LOOP_XYZ(a) { - SERIAL_CHAR(' ', axis_codes[a]); + SERIAL_CHAR(' ', XYZ_CHAR(a)); SERIAL_ECHO(backlash.distance_mm[a]); SERIAL_EOL(); } @@ -88,7 +88,7 @@ void GcodeSuite::M425() { SERIAL_ECHOPGM(" Average measured backlash (mm):"); if (backlash.has_any_measurement()) { LOOP_XYZ(a) if (backlash.has_measurement(AxisEnum(a))) { - SERIAL_CHAR(' ', axis_codes[a]); + SERIAL_CHAR(' ', XYZ_CHAR(a)); SERIAL_ECHO(backlash.get_measurement(AxisEnum(a))); } } diff --git a/Marlin/src/gcode/calibrate/M48.cpp b/Marlin/src/gcode/calibrate/M48.cpp index 8fba7a646f..c1e8b0e9f8 100644 --- a/Marlin/src/gcode/calibrate/M48.cpp +++ b/Marlin/src/gcode/calibrate/M48.cpp @@ -80,11 +80,11 @@ void GcodeSuite::M48() { xy_float_t next_pos = current_position; const xy_pos_t probe_pos = { - parser.linearval('X', next_pos.x + probe.offset_xy.x), - parser.linearval('Y', next_pos.y + probe.offset_xy.y) + parser.linearval('X', next_pos.x + probe.offset_xy.x), // If no X use the probe's current X position + parser.linearval('Y', next_pos.y + probe.offset_xy.y) // If no Y, ditto }; - if (!position_is_reachable_by_probe(probe_pos)) { + if (!probe.can_reach(probe_pos)) { SERIAL_ECHOLNPGM("? (X,Y) out of bounds."); return; } @@ -126,7 +126,7 @@ void GcodeSuite::M48() { if (probing_good) { randomSeed(millis()); - for (uint8_t n = 0; n < n_samples; n++) { + LOOP_L_N(n, n_samples) { #if HAS_SPI_LCD // Display M48 progress in the status bar ui.status_printf_P(0, PSTR(S_FMT ": %d/%d"), GET_TEXT(MSG_M48_POINT), int(n + 1), int(n_samples)); @@ -149,7 +149,7 @@ void GcodeSuite::M48() { SERIAL_ECHOLNPGM("CW"); } - for (uint8_t l = 0; l < n_legs - 1; l++) { + LOOP_L_N(l, n_legs - 1) { float delta_angle; if (schizoid_flag) { @@ -179,7 +179,7 @@ void GcodeSuite::M48() { #else // If we have gone out too far, we can do a simple fix and scale the numbers // back in closer to the origin. - while (!position_is_reachable_by_probe(next_pos)) { + while (!probe.can_reach(next_pos)) { next_pos *= 0.8f; if (verbose_level > 3) SERIAL_ECHOLNPAIR_P(PSTR("Moving inward: X"), next_pos.x, SP_Y_STR, next_pos.y); @@ -204,7 +204,7 @@ void GcodeSuite::M48() { * Get the current mean for the data points we have so far */ float sum = 0.0; - for (uint8_t j = 0; j <= n; j++) sum += sample_set[j]; + LOOP_LE_N(j, n) sum += sample_set[j]; mean = sum / (n + 1); NOMORE(min, sample_set[n]); @@ -215,7 +215,7 @@ void GcodeSuite::M48() { * data points we have so far */ sum = 0.0; - for (uint8_t j = 0; j <= n; j++) + LOOP_LE_N(j, n) sum += sq(sample_set[j] - mean); sigma = SQRT(sum / (n + 1)); diff --git a/Marlin/src/gcode/calibrate/M666.cpp b/Marlin/src/gcode/calibrate/M666.cpp index 094b32708b..721cbcfaa0 100644 --- a/Marlin/src/gcode/calibrate/M666.cpp +++ b/Marlin/src/gcode/calibrate/M666.cpp @@ -40,10 +40,10 @@ void GcodeSuite::M666() { if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM(">>> M666"); LOOP_XYZ(i) { - if (parser.seen(axis_codes[i])) { + if (parser.seen(XYZ_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[", axis_codes[i], "] = ", delta_endstop_adj[i]); + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("delta_endstop_adj[", XYZ_CHAR(i), "] = ", delta_endstop_adj[i]); } } if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("<<< M666"); diff --git a/Marlin/src/gcode/config/M220.cpp b/Marlin/src/gcode/config/M220.cpp index e09a5f7534..5ea75c09c6 100644 --- a/Marlin/src/gcode/config/M220.cpp +++ b/Marlin/src/gcode/config/M220.cpp @@ -29,6 +29,8 @@ * Parameters * S : Set the feed rate percentage factor * + * Report the current speed percentage factor if no parameter is specified + * * With PRUSA_MMU2... * B : Flag to back up the current factor * R : Flag to restore the last-saved factor @@ -43,4 +45,9 @@ void GcodeSuite::M220() { if (parser.seenval('S')) feedrate_percentage = parser.value_int(); + if (!parser.seen_any()) { + SERIAL_ECHOPAIR("FR:", feedrate_percentage); + SERIAL_CHAR('%'); + SERIAL_EOL(); + } } diff --git a/Marlin/src/gcode/config/M305.cpp b/Marlin/src/gcode/config/M305.cpp index 47a81cdb6c..d45e18f1b3 100644 --- a/Marlin/src/gcode/config/M305.cpp +++ b/Marlin/src/gcode/config/M305.cpp @@ -71,7 +71,7 @@ void GcodeSuite::M305() { SERIAL_ECHO_MSG("!Invalid Steinhart-Hart C coeff. (-0.01 < C < +0.01)"); } // If not setting then report parameters else if (t_index < 0) { // ...all user thermistors - for (uint8_t i = 0; i < USER_THERMISTORS; i++) + LOOP_L_N(i, USER_THERMISTORS) thermalManager.log_user_thermistor(i); } else // ...one user thermistor diff --git a/Marlin/src/gcode/config/M43.cpp b/Marlin/src/gcode/config/M43.cpp index 0dd0013e05..661c413191 100644 --- a/Marlin/src/gcode/config/M43.cpp +++ b/Marlin/src/gcode/config/M43.cpp @@ -43,7 +43,7 @@ #endif #if ENABLED(EXTENSIBLE_UI) - #include "../../lcd/extensible_ui/ui_api.h" + #include "../../lcd/extui/ui_api.h" #endif #ifndef GET_PIN_MAP_PIN_M43 @@ -57,16 +57,16 @@ inline void toggle_pins() { end = PARSED_PIN_INDEX('L', NUM_DIGITAL_PINS - 1), wait = parser.intval('W', 500); - for (uint8_t i = start; i <= end; i++) { + LOOP_S_LE_N(i, start, end) { pin_t pin = GET_PIN_MAP_PIN_M43(i); if (!VALID_PIN(pin)) continue; if (M43_NEVER_TOUCH(i) || (!ignore_protection && pin_is_protected(pin))) { - report_pin_state_extended(pin, ignore_protection, true, "Untouched "); + report_pin_state_extended(pin, ignore_protection, true, PSTR("Untouched ")); SERIAL_EOL(); } else { watchdog_refresh(); - report_pin_state_extended(pin, ignore_protection, true, "Pulsing "); + report_pin_state_extended(pin, ignore_protection, true, PSTR("Pulsing ")); #if AVR_AT90USB1286_FAMILY // Teensy IDEs don't know about these pins so must use FASTIO if (pin == TEENSY_E2) { SET_OUTPUT(TEENSY_E2); @@ -313,7 +313,7 @@ void GcodeSuite::M43() { NOLESS(first_pin, 2); // Don't hijack the UART pins #endif uint8_t pin_state[last_pin - first_pin + 1]; - for (uint8_t i = first_pin; i <= last_pin; i++) { + LOOP_S_LE_N(i, first_pin, last_pin) { pin_t pin = GET_PIN_MAP_PIN_M43(i); if (!VALID_PIN(pin)) continue; if (M43_NEVER_TOUCH(i) || (!ignore_protection && pin_is_protected(pin))) continue; @@ -339,7 +339,7 @@ void GcodeSuite::M43() { #endif for (;;) { - for (uint8_t i = first_pin; i <= last_pin; i++) { + LOOP_S_LE_N(i, first_pin, last_pin) { pin_t pin = GET_PIN_MAP_PIN_M43(i); if (!VALID_PIN(pin)) continue; if (M43_NEVER_TOUCH(i) || (!ignore_protection && pin_is_protected(pin))) continue; @@ -365,7 +365,7 @@ void GcodeSuite::M43() { } else { // Report current state of selected pin(s) - for (uint8_t i = first_pin; i <= last_pin; i++) { + LOOP_S_LE_N(i, first_pin, last_pin) { pin_t pin = GET_PIN_MAP_PIN_M43(i); if (VALID_PIN(pin)) report_pin_state_extended(pin, ignore_protection, true); } diff --git a/Marlin/src/gcode/config/M672.cpp b/Marlin/src/gcode/config/M672.cpp index ca4b028dc7..cc160bde66 100644 --- a/Marlin/src/gcode/config/M672.cpp +++ b/Marlin/src/gcode/config/M672.cpp @@ -62,7 +62,7 @@ // b3 b2 b1 b0 ~b0 ... lo bits, NOT last bit // void M672_send(uint8_t b) { // bit rate requirement: 1KHz +/- 30% - for (uint8_t bits = 0; bits < 14; bits++) { + LOOP_L_N(bits, 14) { switch (bits) { default: { OUT_WRITE(SMART_EFFECTOR_MOD_PIN, !!(b & 0x80)); b <<= 1; break; } // send bit, shift next into place case 7: diff --git a/Marlin/src/gcode/config/M92.cpp b/Marlin/src/gcode/config/M92.cpp index 642de96725..bc86ff4d32 100644 --- a/Marlin/src/gcode/config/M92.cpp +++ b/Marlin/src/gcode/config/M92.cpp @@ -34,7 +34,7 @@ void report_M92(const bool echo=true, const int8_t e=-1) { SERIAL_EOL(); #if ENABLED(DISTINCT_E_FACTORS) - for (uint8_t i = 0; i < E_STEPPERS; i++) { + LOOP_L_N(i, E_STEPPERS) { if (e >= 0 && i != e) continue; if (echo) SERIAL_ECHO_START(); else SERIAL_CHAR(' '); SERIAL_ECHOLNPAIR_P(PSTR(" M92 T"), (int)i, diff --git a/Marlin/src/gcode/control/M111.cpp b/Marlin/src/gcode/control/M111.cpp index bb1a77836b..20ed44fb2e 100644 --- a/Marlin/src/gcode/control/M111.cpp +++ b/Marlin/src/gcode/control/M111.cpp @@ -49,7 +49,7 @@ void GcodeSuite::M111() { SERIAL_ECHOPGM(STR_DEBUG_PREFIX); if (marlin_debug_flags) { uint8_t comma = 0; - for (uint8_t i = 0; i < COUNT(debug_strings); i++) { + LOOP_L_N(i, COUNT(debug_strings)) { if (TEST(marlin_debug_flags, i)) { if (comma++) SERIAL_CHAR(','); serialprintPGM((char*)pgm_read_ptr(&debug_strings[i])); diff --git a/Marlin/src/gcode/control/M350_M351.cpp b/Marlin/src/gcode/control/M350_M351.cpp index ae448a63ec..54b29a21d3 100644 --- a/Marlin/src/gcode/control/M350_M351.cpp +++ b/Marlin/src/gcode/control/M350_M351.cpp @@ -33,7 +33,7 @@ * Warning: Steps-per-unit remains unchanged. */ void GcodeSuite::M350() { - if (parser.seen('S')) for (uint8_t i = 0; i <= 4; i++) stepper.microstep_mode(i, parser.value_byte()); + 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()); if (parser.seen('B')) stepper.microstep_mode(4, parser.value_byte()); stepper.microstep_readings(); diff --git a/Marlin/src/gcode/control/M605.cpp b/Marlin/src/gcode/control/M605.cpp index 99bab4ddc9..ab5efbbb48 100644 --- a/Marlin/src/gcode/control/M605.cpp +++ b/Marlin/src/gcode/control/M605.cpp @@ -138,7 +138,7 @@ HOTEND_LOOP() { DEBUG_ECHOPAIR_P(SP_T_STR, int(e)); - LOOP_XYZ(a) DEBUG_ECHOPAIR(" hotend_offset[", int(e), "].", axis_codes[a] | 0x20, "=", hotend_offset[e][a]); + LOOP_XYZ(a) DEBUG_ECHOPAIR(" hotend_offset[", int(e), "].", XYZ_CHAR(a) | 0x20, "=", hotend_offset[e][a]); DEBUG_EOL(); } DEBUG_EOL(); diff --git a/Marlin/src/gcode/control/M80_M81.cpp b/Marlin/src/gcode/control/M80_M81.cpp index f9c40a20a9..e8d9aa2fdf 100644 --- a/Marlin/src/gcode/control/M80_M81.cpp +++ b/Marlin/src/gcode/control/M80_M81.cpp @@ -44,7 +44,7 @@ // Could be moved to a feature, but this is all the data bool powersupply_on; - #if HAS_TRINAMIC + #if HAS_TRINAMIC_CONFIG #include "../../feature/tmc_util.h" #endif diff --git a/Marlin/src/gcode/control/T.cpp b/Marlin/src/gcode/control/T.cpp index cb2fce6c25..e6b3bb5d68 100644 --- a/Marlin/src/gcode/control/T.cpp +++ b/Marlin/src/gcode/control/T.cpp @@ -28,7 +28,7 @@ #endif #if ENABLED(PRUSA_MMU2) - #include "../../feature/prusa_MMU2/mmu2.h" + #include "../../feature/mmu2/mmu2.h" #endif #define DEBUG_OUT ENABLED(DEBUG_LEVELING_FEATURE) diff --git a/Marlin/src/gcode/feature/advance/M900.cpp b/Marlin/src/gcode/feature/advance/M900.cpp index fd500261b6..5a029cbf01 100644 --- a/Marlin/src/gcode/feature/advance/M900.cpp +++ b/Marlin/src/gcode/feature/advance/M900.cpp @@ -29,11 +29,10 @@ #include "../../../module/stepper.h" #if ENABLED(EXTRA_LIN_ADVANCE_K) - float saved_extruder_advance_K[EXTRUDERS]; + float other_extruder_advance_K[EXTRUDERS]; uint8_t lin_adv_slot = 0; #endif - /** * M900: Get or Set Linear Advance K-factor * T Which tool to address @@ -43,100 +42,106 @@ */ void GcodeSuite::M900() { + auto echo_value_oor = [] (const char ltr, const bool ten=true) { + SERIAL_CHAR('?'); SERIAL_CHAR(ltr); + SERIAL_ECHOPGM(" value out of range"); + if (ten) SERIAL_ECHOPGM(" (0-10)"); + SERIAL_ECHOLNPGM("."); + }; + #if EXTRUDERS < 2 constexpr uint8_t tool_index = 0; #else const uint8_t tool_index = parser.intval('T', active_extruder); if (tool_index >= EXTRUDERS) { - SERIAL_ECHOLNPGM("?T value out of range."); + echo_value_oor('T', false); return; } #endif + float &kref = planner.extruder_advance_K[tool_index], newK = kref; + const float oldK = newK; + #if ENABLED(EXTRA_LIN_ADVANCE_K) - bool ext_slot = TEST(lin_adv_slot, tool_index); + float &lref = other_extruder_advance_K[tool_index]; - if (parser.seenval('S')) { - const bool slot = parser.value_bool(); - if (ext_slot != slot) { - ext_slot = slot; - SET_BIT_TO(lin_adv_slot, tool_index, slot); - planner.synchronize(); - const float temp = planner.extruder_advance_K[tool_index]; - planner.extruder_advance_K[tool_index] = saved_extruder_advance_K[tool_index]; - saved_extruder_advance_K[tool_index] = temp; - } + const bool old_slot = TEST(lin_adv_slot, tool_index), // The tool's current slot (0 or 1) + new_slot = parser.boolval('S', old_slot); // The passed slot (default = current) + + // If a new slot is being selected swap the current and + // saved K values. Do here so K/L will apply correctly. + if (new_slot != old_slot) { // Not the same slot? + SET_BIT_TO(lin_adv_slot, tool_index, new_slot); // Update the slot for the tool + newK = lref; // Get new K value from backup + lref = oldK; // Save K to backup } + // Set the main K value. Apply if the main slot is active. if (parser.seenval('K')) { - const float newK = parser.value_float(); - if (WITHIN(newK, 0, 10)) { - if (ext_slot) - saved_extruder_advance_K[tool_index] = newK; - else { - planner.synchronize(); - planner.extruder_advance_K[tool_index] = newK; - } - } - else - SERIAL_ECHOLNPGM("?K value out of range (0-10)."); + const float K = parser.value_float(); + if (!WITHIN(K, 0, 10)) echo_value_oor('K'); + else if (new_slot) lref = K; // S1 Knn + else newK = K; // S0 Knn } + // Set the extra K value. Apply if the extra slot is active. if (parser.seenval('L')) { - const float newL = parser.value_float(); - if (WITHIN(newL, 0, 10)) { - if (!ext_slot) - saved_extruder_advance_K[tool_index] = newL; - else { - planner.synchronize(); - planner.extruder_advance_K[tool_index] = newL; - } - } - else - SERIAL_ECHOLNPGM("?L value out of range (0-10)."); - } - - if (!parser.seen_any()) { - #if EXTRUDERS < 2 - SERIAL_ECHOLNPAIR("Advance S", ext_slot, " K", planner.extruder_advance_K[0], - "(Slot ", 1 - ext_slot, " K", saved_extruder_advance_K[0], ")"); - #else - LOOP_L_N(i, EXTRUDERS) { - const int slot = (int)TEST(lin_adv_slot, i); - SERIAL_ECHOLNPAIR("Advance T", int(i), " S", slot, " K", planner.extruder_advance_K[i], - "(Slot ", 1 - slot, " K", saved_extruder_advance_K[i], ")"); - SERIAL_EOL(); - } - #endif + const float L = parser.value_float(); + if (!WITHIN(L, 0, 10)) echo_value_oor('L'); + else if (!new_slot) lref = L; // S0 Lnn + else newK = L; // S1 Lnn } #else if (parser.seenval('K')) { - const float newK = parser.value_float(); - if (WITHIN(newK, 0, 10)) { - planner.synchronize(); - planner.extruder_advance_K[tool_index] = newK; - } + const float K = parser.value_float(); + if (WITHIN(K, 0, 10)) + newK = K; else - SERIAL_ECHOLNPGM("?K value out of range (0-10)."); + echo_value_oor('K'); } - else { + + #endif + + if (newK != oldK) { + planner.synchronize(); + kref = newK; + } + + if (!parser.seen_any()) { + + #if ENABLED(EXTRA_LIN_ADVANCE_K) + + #if EXTRUDERS < 2 + SERIAL_ECHOLNPAIR("Advance S", int(new_slot), " K", kref, "(S", int(!new_slot), " K", lref, ")"); + #else + LOOP_L_N(i, EXTRUDERS) { + const bool slot = TEST(lin_adv_slot, i); + SERIAL_ECHOLNPAIR("Advance T", int(i), " S", int(slot), " K", planner.extruder_advance_K[i], + "(S", int(!slot), " K", other_extruder_advance_K[i], ")"); + SERIAL_EOL(); + } + #endif + + #else + SERIAL_ECHO_START(); #if EXTRUDERS < 2 SERIAL_ECHOLNPAIR("Advance K=", planner.extruder_advance_K[0]); #else SERIAL_ECHOPGM("Advance K"); LOOP_L_N(i, EXTRUDERS) { - SERIAL_CHAR(' '); SERIAL_ECHO(int(i)); - SERIAL_CHAR('='); SERIAL_ECHO(planner.extruder_advance_K[i]); + SERIAL_CHAR(' ', '0' + i, ':'); + SERIAL_ECHO(planner.extruder_advance_K[i]); } SERIAL_EOL(); #endif - } - #endif + #endif + } + } #endif // LIN_ADVANCE diff --git a/Marlin/src/gcode/feature/camera/M240.cpp b/Marlin/src/gcode/feature/camera/M240.cpp index 804eec205f..3c045a7e68 100644 --- a/Marlin/src/gcode/feature/camera/M240.cpp +++ b/Marlin/src/gcode/feature/camera/M240.cpp @@ -90,7 +90,7 @@ inline void spin_photo_pin() { static constexpr uint32_t sequence[] = PHOTO_PULSES_US; - for (uint8_t i = 0; i < COUNT(sequence); i++) + LOOP_L_N(i, COUNT(sequence)) pulse_photo_pin(sequence[i], !(i & 1)); } diff --git a/Marlin/src/gcode/feature/digipot/M907-M910.cpp b/Marlin/src/gcode/feature/digipot/M907-M910.cpp index a8ded07d77..fe8e37ebdd 100644 --- a/Marlin/src/gcode/feature/digipot/M907-M910.cpp +++ b/Marlin/src/gcode/feature/digipot/M907-M910.cpp @@ -46,7 +46,7 @@ void GcodeSuite::M907() { LOOP_XYZE(i) if (parser.seenval(axis_codes[i])) stepper.digipot_current(i, parser.value_int()); if (parser.seenval('B')) stepper.digipot_current(4, parser.value_int()); - if (parser.seenval('S')) for (uint8_t i = 0; i <= 4; i++) stepper.digipot_current(i, parser.value_int()); + if (parser.seenval('S')) LOOP_LE_N(i, 4) stepper.digipot_current(i, parser.value_int()); #elif HAS_MOTOR_CURRENT_PWM @@ -74,7 +74,7 @@ void GcodeSuite::M907() { #if ENABLED(DAC_STEPPER_CURRENT) if (parser.seenval('S')) { const float dac_percent = parser.value_float(); - for (uint8_t i = 0; i <= 4; i++) dac_current_percent(i, dac_percent); + LOOP_LE_N(i, 4) dac_current_percent(i, dac_percent); } LOOP_XYZE(i) if (parser.seenval(axis_codes[i])) dac_current_percent(i, parser.value_float()); #endif diff --git a/Marlin/src/gcode/feature/leds/M7219.cpp b/Marlin/src/gcode/feature/leds/M7219.cpp index a02ea0cc30..acbd55957f 100644 --- a/Marlin/src/gcode/feature/leds/M7219.cpp +++ b/Marlin/src/gcode/feature/leds/M7219.cpp @@ -25,7 +25,7 @@ #if ENABLED(MAX7219_GCODE) #include "../../gcode.h" -#include "../../../feature/Max7219_Debug_LEDs.h" +#include "../../../feature/max7219.h" /** * M7219: Control the Max7219 LED matrix @@ -79,7 +79,7 @@ void GcodeSuite::M7219() { } if (parser.seen('P')) { - for (uint8_t r = 0; r < MAX7219_LINES; r++) { + LOOP_L_N(r, MAX7219_LINES) { SERIAL_ECHOPGM("led_line["); if (r < 10) SERIAL_CHAR(' '); SERIAL_ECHO(int(r)); diff --git a/Marlin/src/gcode/feature/pause/G61.cpp b/Marlin/src/gcode/feature/pause/G61.cpp index e6e5180192..60e6bcf040 100644 --- a/Marlin/src/gcode/feature/pause/G61.cpp +++ b/Marlin/src/gcode/feature/pause/G61.cpp @@ -56,16 +56,16 @@ void GcodeSuite::G61(void) { SERIAL_ECHOPAIR(STR_RESTORING_POS " S", int(slot)); LOOP_XYZ(i) { - destination[i] = parser.seen(axis_codes[i]) + destination[i] = parser.seen(XYZ_CHAR(i)) ? stored_position[slot][i] + parser.value_axis_units((AxisEnum)i) : current_position[i]; - SERIAL_CHAR(' ', axis_codes[i]); + SERIAL_CHAR(' ', XYZ_CHAR(i)); SERIAL_ECHO_F(destination[i]); } SERIAL_EOL(); // Move to the saved position - prepare_move_to_destination(); + prepare_line_to_destination(); } #endif // SAVED_POSITIONS diff --git a/Marlin/src/gcode/feature/pause/M125.cpp b/Marlin/src/gcode/feature/pause/M125.cpp index 6cf0847a9d..206815a200 100644 --- a/Marlin/src/gcode/feature/pause/M125.cpp +++ b/Marlin/src/gcode/feature/pause/M125.cpp @@ -36,7 +36,7 @@ #endif #if ENABLED(POWER_LOSS_RECOVERY) - #include "../../../feature/power_loss_recovery.h" + #include "../../../feature/powerloss.h" #endif /** diff --git a/Marlin/src/gcode/feature/pause/M701_M702.cpp b/Marlin/src/gcode/feature/pause/M701_M702.cpp index be76814c0d..aa3c3c4c30 100644 --- a/Marlin/src/gcode/feature/pause/M701_M702.cpp +++ b/Marlin/src/gcode/feature/pause/M701_M702.cpp @@ -39,7 +39,7 @@ #endif #if ENABLED(PRUSA_MMU2) - #include "../../../feature/prusa_MMU2/mmu2.h" + #include "../../../feature/mmu2/mmu2.h" #endif #if ENABLED(MIXING_EXTRUDER) diff --git a/Marlin/src/gcode/feature/powerloss/M1000.cpp b/Marlin/src/gcode/feature/powerloss/M1000.cpp index 546fea9bde..ea2c6e3dab 100644 --- a/Marlin/src/gcode/feature/powerloss/M1000.cpp +++ b/Marlin/src/gcode/feature/powerloss/M1000.cpp @@ -25,11 +25,11 @@ #if ENABLED(POWER_LOSS_RECOVERY) #include "../../gcode.h" -#include "../../../feature/power_loss_recovery.h" +#include "../../../feature/powerloss.h" #include "../../../module/motion.h" #include "../../../lcd/ultralcd.h" #if ENABLED(EXTENSIBLE_UI) - #include "../../../lcd/extensible_ui/ui_api.h" + #include "../../../lcd/extui/ui_api.h" #endif #define DEBUG_OUT ENABLED(DEBUG_POWER_LOSS_RECOVERY) diff --git a/Marlin/src/gcode/feature/powerloss/M413.cpp b/Marlin/src/gcode/feature/powerloss/M413.cpp index 2b3f478b20..67e756d5d2 100644 --- a/Marlin/src/gcode/feature/powerloss/M413.cpp +++ b/Marlin/src/gcode/feature/powerloss/M413.cpp @@ -25,7 +25,7 @@ #if ENABLED(POWER_LOSS_RECOVERY) #include "../../gcode.h" -#include "../../../feature/power_loss_recovery.h" +#include "../../../feature/powerloss.h" #include "../../../module/motion.h" #include "../../../lcd/ultralcd.h" diff --git a/Marlin/src/gcode/feature/prusa_MMU2/M403.cpp b/Marlin/src/gcode/feature/prusa_MMU2/M403.cpp index b9b74ebf71..0a9c519451 100644 --- a/Marlin/src/gcode/feature/prusa_MMU2/M403.cpp +++ b/Marlin/src/gcode/feature/prusa_MMU2/M403.cpp @@ -25,7 +25,7 @@ #if ENABLED(PRUSA_MMU2) #include "../../gcode.h" -#include "../../../feature/prusa_MMU2/mmu2.h" +#include "../../../feature/mmu2/mmu2.h" /** * M403: Set filament type for MMU2 diff --git a/Marlin/src/gcode/feature/trinamic/M122.cpp b/Marlin/src/gcode/feature/trinamic/M122.cpp index bba6e7e752..0eb93a8006 100644 --- a/Marlin/src/gcode/feature/trinamic/M122.cpp +++ b/Marlin/src/gcode/feature/trinamic/M122.cpp @@ -22,7 +22,7 @@ #include "../../../inc/MarlinConfig.h" -#if HAS_TRINAMIC +#if HAS_TRINAMIC_CONFIG #include "../../gcode.h" #include "../../../feature/tmc_util.h" @@ -53,4 +53,4 @@ void GcodeSuite::M122() { test_tmc_connection(print_axis.x, print_axis.y, print_axis.z, print_axis.e); } -#endif // HAS_TRINAMIC +#endif // HAS_TRINAMIC_CONFIG diff --git a/Marlin/src/gcode/feature/trinamic/M906.cpp b/Marlin/src/gcode/feature/trinamic/M906.cpp index bb2659913a..95ad310ed0 100644 --- a/Marlin/src/gcode/feature/trinamic/M906.cpp +++ b/Marlin/src/gcode/feature/trinamic/M906.cpp @@ -22,7 +22,7 @@ #include "../../../inc/MarlinConfig.h" -#if HAS_TRINAMIC +#if HAS_TRINAMIC_CONFIG #include "../../gcode.h" #include "../../../feature/tmc_util.h" @@ -170,4 +170,4 @@ void GcodeSuite::M906() { } } -#endif // HAS_TRINAMIC +#endif // HAS_TRINAMIC_CONFIG diff --git a/Marlin/src/gcode/feature/trinamic/M911-M914.cpp b/Marlin/src/gcode/feature/trinamic/M911-M914.cpp index 505ac14d87..582e779cc2 100644 --- a/Marlin/src/gcode/feature/trinamic/M911-M914.cpp +++ b/Marlin/src/gcode/feature/trinamic/M911-M914.cpp @@ -22,7 +22,7 @@ #include "../../../inc/MarlinConfig.h" -#if HAS_TRINAMIC +#if HAS_TRINAMIC_CONFIG #include "../../gcode.h" #include "../../../feature/tmc_util.h" @@ -348,7 +348,7 @@ bool report = true; const uint8_t index = parser.byteval('I'); - LOOP_XYZ(i) if (parser.seen(axis_codes[i])) { + LOOP_XYZ(i) if (parser.seen(XYZ_CHAR(i))) { const int16_t value = parser.value_int(); report = false; switch (i) { @@ -426,4 +426,4 @@ } #endif // USE_SENSORLESS -#endif // HAS_TRINAMIC +#endif // HAS_TRINAMIC_CONFIG diff --git a/Marlin/src/gcode/gcode.cpp b/Marlin/src/gcode/gcode.cpp index 0d2b656dd6..266361a099 100644 --- a/Marlin/src/gcode/gcode.cpp +++ b/Marlin/src/gcode/gcode.cpp @@ -46,7 +46,7 @@ GcodeSuite gcode; #if ENABLED(POWER_LOSS_RECOVERY) #include "../sd/cardreader.h" - #include "../feature/power_loss_recovery.h" + #include "../feature/powerloss.h" #endif #if ENABLED(CANCEL_OBJECTS) @@ -135,7 +135,7 @@ void GcodeSuite::get_destination_from_command() { // Get new XYZ position, whether absolute or relative LOOP_XYZ(i) { - if ( (seen[i] = parser.seenval(axis_codes[i])) ) { + if ( (seen[i] = parser.seenval(XYZ_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::process_parsed_command(const bool no_ok/*=false*/) { case 27: G27(); break; // G27: Nozzle Park #endif - case 28: G28(false); break; // G28: Home all axes, one at a time + case 28: G28(); break; // G28: Home one or more axes #if HAS_LEVELING case 29: // G29: Bed leveling calibration @@ -785,7 +785,7 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) { #endif #endif - #if HAS_TRINAMIC + #if HAS_TRINAMIC_CONFIG case 122: M122(); break; // M122: Report driver configuration and status case 906: M906(); break; // M906: Set motor current in milliamps using axis codes X, Y, Z, E #if HAS_STEALTHCHOP @@ -930,6 +930,7 @@ void GcodeSuite::process_subcommands_now(char * gcode) { char * const delim = strchr(gcode, '\n'); // Get address of next newline if (delim) *delim = '\0'; // Replace with nul parser.parse(gcode); // Parse the current command + if (delim) *delim = '\n'; // Put back the newline process_parsed_command(true); // Process it if (!delim) break; // Last command? gcode = delim + 1; // Get the next command diff --git a/Marlin/src/gcode/gcode.h b/Marlin/src/gcode/gcode.h index c44c170811..27a038dde9 100644 --- a/Marlin/src/gcode/gcode.h +++ b/Marlin/src/gcode/gcode.h @@ -287,7 +287,7 @@ #include "parser.h" #if ENABLED(I2C_POSITION_ENCODERS) - #include "../feature/I2CPositionEncoder.h" + #include "../feature/encoder_i2c.h" #endif enum AxisRelative : uint8_t { REL_X, REL_Y, REL_Z, REL_E, E_MODE_ABS, E_MODE_REL }; @@ -434,7 +434,7 @@ private: static void G27(); #endif - static void G28(const bool always_home_all); + static void G28(); #if HAS_LEVELING #if ENABLED(G29_RETRY_AND_RECOVER) @@ -912,7 +912,7 @@ private: static void M900(); #endif - #if HAS_TRINAMIC + #if HAS_TRINAMIC_CONFIG static void M122(); static void M906(); #if HAS_STEALTHCHOP diff --git a/Marlin/src/gcode/geometry/G92.cpp b/Marlin/src/gcode/geometry/G92.cpp index 0ed10beb54..91a746dd76 100644 --- a/Marlin/src/gcode/geometry/G92.cpp +++ b/Marlin/src/gcode/geometry/G92.cpp @@ -25,7 +25,7 @@ #include "../../module/stepper.h" #if ENABLED(I2C_POSITION_ENCODERS) - #include "../../feature/I2CPositionEncoder.h" + #include "../../feature/encoder_i2c.h" #endif /** diff --git a/Marlin/src/gcode/geometry/M206_M428.cpp b/Marlin/src/gcode/geometry/M206_M428.cpp index e4cac5174b..13e82a0c73 100644 --- a/Marlin/src/gcode/geometry/M206_M428.cpp +++ b/Marlin/src/gcode/geometry/M206_M428.cpp @@ -38,7 +38,7 @@ */ void GcodeSuite::M206() { LOOP_XYZ(i) - if (parser.seen(axis_codes[i])) + if (parser.seen(XYZ_CHAR(i))) set_home_offset((AxisEnum)i, parser.value_linear_units()); #if ENABLED(MORGAN_SCARA) diff --git a/Marlin/src/gcode/host/M114.cpp b/Marlin/src/gcode/host/M114.cpp index acdd925301..ec5b950b64 100644 --- a/Marlin/src/gcode/host/M114.cpp +++ b/Marlin/src/gcode/host/M114.cpp @@ -34,18 +34,9 @@ #include "../../core/debug_out.h" #endif - void report_xyze(const xyze_pos_t &pos, const uint8_t n=4, const uint8_t precision=3) { + void report_xyze(const xyze_pos_t &pos, const uint8_t n=XYZE, const uint8_t precision=3) { char str[12]; - for (uint8_t a = 0; a < n; a++) { - SERIAL_CHAR(' ', axis_codes[a], ':'); - SERIAL_ECHO(dtostrf(pos[a], 1, precision, str)); - } - SERIAL_EOL(); - } - - void report_xyz(const xyz_pos_t &pos, const uint8_t precision=3) { - char str[12]; - for (uint8_t a = X_AXIS; a <= Z_AXIS; a++) { + LOOP_L_N(a, n) { SERIAL_CHAR(' ', axis_codes[a], ':'); SERIAL_ECHO(dtostrf(pos[a], 1, precision, str)); } @@ -53,21 +44,34 @@ } inline void report_xyz(const xyze_pos_t &pos) { report_xyze(pos, 3); } + void report_xyz(const xyz_pos_t &pos, const uint8_t precision=3) { + char str[12]; + LOOP_XYZ(a) { + SERIAL_CHAR(' ', XYZ_CHAR(a), ':'); + SERIAL_ECHO(dtostrf(pos[a], 1, precision, str)); + } + SERIAL_EOL(); + } + void report_current_position_detail() { + // Position as sent by G-code SERIAL_ECHOPGM("\nLogical:"); report_xyz(current_position.asLogical()); + // Cartesian position in native machine space SERIAL_ECHOPGM("Raw: "); report_xyz(current_position); xyze_pos_t leveled = current_position; #if HAS_LEVELING + // Current position with leveling applied SERIAL_ECHOPGM("Leveled:"); planner.apply_leveling(leveled); report_xyz(leveled); + // Test planner un-leveling. This should match the Raw result. SERIAL_ECHOPGM("UnLevel:"); xyze_pos_t unleveled = leveled; planner.unapply_leveling(unleveled); @@ -75,6 +79,7 @@ #endif #if IS_KINEMATIC + // Kinematics applied to the leveled position #if IS_SCARA SERIAL_ECHOPGM("ScaraK: "); #else @@ -180,12 +185,21 @@ #endif // M114_DETAIL /** - * M114: Report current position to host + * M114: Report the current position to host. + * Since steppers are moving, the count positions are + * projected by using planner calculations. + * D - Report more detail. This syncs the planner. (Requires M114_DETAIL) + * E - Report E stepper position (Requires M114_DETAIL) + * R - Report the realtime position instead of projected. */ void GcodeSuite::M114() { #if ENABLED(M114_DETAIL) if (parser.seen('D')) { + #if DISABLED(M114_LEGACY) + planner.synchronize(); + #endif + report_current_position(); report_current_position_detail(); return; } @@ -195,6 +209,12 @@ void GcodeSuite::M114() { } #endif - planner.synchronize(); - report_current_position(); + #if ENABLED(M114_REALTIME) + if (parser.seen('R')) { report_real_position(); return; } + #endif + + #if ENABLED(M114_LEGACY) + planner.synchronize(); + #endif + report_current_position_projected(); } diff --git a/Marlin/src/gcode/host/M115.cpp b/Marlin/src/gcode/host/M115.cpp index 4d2c5d5d69..d74f909c47 100644 --- a/Marlin/src/gcode/host/M115.cpp +++ b/Marlin/src/gcode/host/M115.cpp @@ -54,39 +54,19 @@ void GcodeSuite::M115() { #endif // SERIAL_XON_XOFF - cap_line(PSTR("SERIAL_XON_XOFF") - #if ENABLED(SERIAL_XON_XOFF) - , true - #endif - ); + cap_line(PSTR("SERIAL_XON_XOFF"), ENABLED(SERIAL_XON_XOFF)); // BINARY_FILE_TRANSFER (M28 B1) - cap_line(PSTR("BINARY_FILE_TRANSFER") - #if ENABLED(BINARY_FILE_TRANSFER) - , true - #endif - ); + cap_line(PSTR("BINARY_FILE_TRANSFER"), ENABLED(BINARY_FILE_TRANSFER)); // EEPROM (M500, M501) - cap_line(PSTR("EEPROM") - #if ENABLED(EEPROM_SETTINGS) - , true - #endif - ); + cap_line(PSTR("EEPROM"), ENABLED(EEPROM_SETTINGS)); // Volumetric Extrusion (M200) - cap_line(PSTR("VOLUMETRIC") - #if DISABLED(NO_VOLUMETRICS) - , true - #endif - ); + cap_line(PSTR("VOLUMETRIC"), DISABLED(NO_VOLUMETRICS)); // AUTOREPORT_TEMP (M155) - cap_line(PSTR("AUTOREPORT_TEMP") - #if ENABLED(AUTO_REPORT_TEMPERATURES) - , true - #endif - ); + cap_line(PSTR("AUTOREPORT_TEMP"), ENABLED(AUTO_REPORT_TEMPERATURES)); // PROGRESS (M530 S L, M531 , M532 X L) cap_line(PSTR("PROGRESS")); @@ -95,93 +75,42 @@ void GcodeSuite::M115() { cap_line(PSTR("PRINT_JOB"), true); // AUTOLEVEL (G29) - cap_line(PSTR("AUTOLEVEL") - #if HAS_AUTOLEVEL - , true - #endif - ); + cap_line(PSTR("AUTOLEVEL"), ENABLED(HAS_AUTOLEVEL)); // Z_PROBE (G30) - cap_line(PSTR("Z_PROBE") - #if HAS_BED_PROBE - , true - #endif - ); + cap_line(PSTR("Z_PROBE"), ENABLED(HAS_BED_PROBE)); // MESH_REPORT (M420 V) - cap_line(PSTR("LEVELING_DATA") - #if HAS_LEVELING - , true - #endif - ); + cap_line(PSTR("LEVELING_DATA"), ENABLED(HAS_LEVELING)); // BUILD_PERCENT (M73) - cap_line(PSTR("BUILD_PERCENT") - #if ENABLED(LCD_SET_PROGRESS_MANUALLY) - , true - #endif - ); + cap_line(PSTR("BUILD_PERCENT"), ENABLED(LCD_SET_PROGRESS_MANUALLY)); // SOFTWARE_POWER (M80, M81) - cap_line(PSTR("SOFTWARE_POWER") - #if ENABLED(PSU_CONTROL) - , true - #endif - ); + cap_line(PSTR("SOFTWARE_POWER"), ENABLED(PSU_CONTROL)); // CASE LIGHTS (M355) - cap_line(PSTR("TOGGLE_LIGHTS") - #if HAS_CASE_LIGHT - , true - #endif - ); - cap_line(PSTR("CASE_LIGHT_BRIGHTNESS") - #if HAS_CASE_LIGHT - , PWM_PIN(CASE_LIGHT_PIN) - #endif - ); + cap_line(PSTR("TOGGLE_LIGHTS"), ENABLED(HAS_CASE_LIGHT)); + + cap_line(PSTR("CASE_LIGHT_BRIGHTNESS"), TERN(HAS_CASE_LIGHT, PWM_PIN(CASE_LIGHT_PIN), 0)); // EMERGENCY_PARSER (M108, M112, M410, M876) - cap_line(PSTR("EMERGENCY_PARSER") - #if ENABLED(EMERGENCY_PARSER) - , true - #endif - ); + cap_line(PSTR("EMERGENCY_PARSER"), ENABLED(EMERGENCY_PARSER)); // PROMPT SUPPORT (M876) - cap_line(PSTR("PROMPT_SUPPORT") - #if ENABLED(HOST_PROMPT_SUPPORT) - , true - #endif - ); + cap_line(PSTR("PROMPT_SUPPORT"), ENABLED(HOST_PROMPT_SUPPORT)); // AUTOREPORT_SD_STATUS (M27 extension) - cap_line(PSTR("AUTOREPORT_SD_STATUS") - #if ENABLED(AUTO_REPORT_SD_STATUS) - , true - #endif - ); + cap_line(PSTR("AUTOREPORT_SD_STATUS"), ENABLED(AUTO_REPORT_SD_STATUS)); // THERMAL_PROTECTION - cap_line(PSTR("THERMAL_PROTECTION") - #if (ENABLED(THERMAL_PROTECTION_HOTENDS) || !EXTRUDERS) && (ENABLED(THERMAL_PROTECTION_BED) || !HAS_HEATED_BED) && (ENABLED(THERMAL_PROTECTION_CHAMBER) || !HAS_HEATED_CHAMBER) - , true - #endif - ); + cap_line(PSTR("THERMAL_PROTECTION"), ENABLED(THERMALLY_SAFE)); // MOTION_MODES (M80-M89) - cap_line(PSTR("MOTION_MODES") - #if ENABLED(GCODE_MOTION_MODES) - , true - #endif - ); + cap_line(PSTR("MOTION_MODES"), ENABLED(GCODE_MOTION_MODES)); // CHAMBER_TEMPERATURE (M141, M191) - cap_line(PSTR("CHAMBER_TEMPERATURE") - #if HAS_HEATED_CHAMBER - , true - #endif - ); + cap_line(PSTR("CHAMBER_TEMPERATURE"), ENABLED(HAS_HEATED_CHAMBER)); #endif // EXTENDED_CAPABILITIES_REPORT } diff --git a/Marlin/src/gcode/lcd/M0_M1.cpp b/Marlin/src/gcode/lcd/M0_M1.cpp index 2b35ddf3ff..2176693209 100644 --- a/Marlin/src/gcode/lcd/M0_M1.cpp +++ b/Marlin/src/gcode/lcd/M0_M1.cpp @@ -34,7 +34,7 @@ #endif #if ENABLED(EXTENSIBLE_UI) - #include "../../lcd/extensible_ui/ui_api.h" + #include "../../lcd/extui/ui_api.h" #endif #if HAS_LEDS_OFF_FLAG @@ -50,33 +50,22 @@ * M1: Conditional stop - Wait for user button press on LCD */ void GcodeSuite::M0_M1() { - const char * const args = parser.string_arg; - millis_t ms = 0; - bool hasP = false, hasS = false; - if (parser.seenval('P')) { - ms = parser.value_millis(); // milliseconds to wait - hasP = ms > 0; - } - if (parser.seenval('S')) { - ms = parser.value_millis_from_seconds(); // seconds to wait - hasS = ms > 0; - } - - const bool has_message = !hasP && !hasS && args && *args; + if (parser.seenval('P')) ms = parser.value_millis(); // Milliseconds to wait + if (parser.seenval('S')) ms = parser.value_millis_from_seconds(); // Seconds to wait planner.synchronize(); + const bool seenQ = parser.seen('Q'); #if HAS_LEDS_OFF_FLAG - if (parser.seen('Q')) - printerEventLEDs.onPrintCompleted(); // Change LED color for Print Completed + if (seenQ) printerEventLEDs.onPrintCompleted(); // Change LED color for Print Completed #endif #if HAS_LCD_MENU - if (has_message) - ui.set_status(args, true); - else { + if (parser.string_arg) + ui.set_status(parser.string_arg, true); + else if (!seenQ) { LCD_MESSAGEPGM(MSG_USERWAIT); #if ENABLED(LCD_PROGRESS_BAR) && PROGRESS_MSG_EXPIRE > 0 ui.reset_progress_bar_timeout(); @@ -85,16 +74,16 @@ void GcodeSuite::M0_M1() { #elif ENABLED(EXTENSIBLE_UI) - if (has_message) - ExtUI::onUserConfirmRequired(args); // Can this take an SRAM string?? + if (parser.string_arg) + ExtUI::onUserConfirmRequired(parser.string_arg); // Can this take an SRAM string?? else ExtUI::onUserConfirmRequired_P(GET_TEXT(MSG_USERWAIT)); #else - if (has_message) { + if (parser.string_arg) { SERIAL_ECHO_START(); - SERIAL_ECHOLN(args); + SERIAL_ECHOLN(parser.string_arg); } #endif @@ -114,7 +103,7 @@ void GcodeSuite::M0_M1() { #endif #if HAS_LCD_MENU - ui.reset_status(); + if (!seenQ) ui.reset_status(); #endif wait_for_user = false; diff --git a/Marlin/src/gcode/motion/G0_G1.cpp b/Marlin/src/gcode/motion/G0_G1.cpp index 8f0dfc71b2..069d76fdad 100644 --- a/Marlin/src/gcode/motion/G0_G1.cpp +++ b/Marlin/src/gcode/motion/G0_G1.cpp @@ -100,9 +100,9 @@ void GcodeSuite::G0_G1( #endif // FWRETRACT #if IS_SCARA - fast_move ? prepare_fast_move_to_destination() : prepare_move_to_destination(); + fast_move ? prepare_fast_move_to_destination() : prepare_line_to_destination(); #else - prepare_move_to_destination(); + prepare_line_to_destination(); #endif #ifdef G0_FEEDRATE diff --git a/Marlin/src/gcode/motion/M290.cpp b/Marlin/src/gcode/motion/M290.cpp index 4f6489d3b9..5fef948fa4 100644 --- a/Marlin/src/gcode/motion/M290.cpp +++ b/Marlin/src/gcode/motion/M290.cpp @@ -76,8 +76,8 @@ */ void GcodeSuite::M290() { #if ENABLED(BABYSTEP_XY) - for (uint8_t a = X_AXIS; a <= Z_AXIS; a++) - if (parser.seenval(axis_codes[a]) || (a == Z_AXIS && parser.seenval('S'))) { + LOOP_XYZ(a) + if (parser.seenval(XYZ_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 0fac65300f..4ece6ede46 100644 --- a/Marlin/src/gcode/parser.cpp +++ b/Marlin/src/gcode/parser.cpp @@ -312,7 +312,9 @@ void GCodeParser::parse(char *p) { char * const valptr = has_val ? is_str ? unescape_string(p) : p : nullptr; #else const bool has_val = valid_float(p); - char * const valptr = has_val ? p : nullptr; + #if ENABLED(FASTER_GCODE_PARSER) + char * const valptr = has_val ? p : nullptr; + #endif #endif #if ENABLED(DEBUG_GCODE_PARSER) diff --git a/Marlin/src/gcode/probe/G30.cpp b/Marlin/src/gcode/probe/G30.cpp index 8b2ada9cec..21d56b3fd4 100644 --- a/Marlin/src/gcode/probe/G30.cpp +++ b/Marlin/src/gcode/probe/G30.cpp @@ -43,7 +43,7 @@ void GcodeSuite::G30() { const xy_pos_t pos = { parser.linearval('X', current_position.x + probe.offset_xy.x), parser.linearval('Y', current_position.y + probe.offset_xy.y) }; - if (!position_is_reachable_by_probe(pos)) return; + if (!probe.can_reach(pos)) return; // Disable leveling so the planner won't mess with us #if HAS_LEVELING diff --git a/Marlin/src/gcode/probe/G38.cpp b/Marlin/src/gcode/probe/G38.cpp index 11b7ce5af7..512e1ff89f 100644 --- a/Marlin/src/gcode/probe/G38.cpp +++ b/Marlin/src/gcode/probe/G38.cpp @@ -34,7 +34,7 @@ inline void G38_single_probe(const uint8_t move_value) { endstops.enable(true); G38_move = move_value; - prepare_move_to_destination(); + prepare_line_to_destination(); planner.synchronize(); G38_move = 0; endstops.hit_on_purpose(); @@ -77,7 +77,7 @@ inline bool G38_run_probe() { // Move away by the retract distance destination = current_position + retract_mm; endstops.enable(false); - prepare_move_to_destination(); + prepare_line_to_destination(); planner.synchronize(); REMEMBER(fr, feedrate_mm_s, feedrate_mm_s * 0.25); diff --git a/Marlin/src/gcode/queue.cpp b/Marlin/src/gcode/queue.cpp index 7d17ca602b..abb50b960d 100644 --- a/Marlin/src/gcode/queue.cpp +++ b/Marlin/src/gcode/queue.cpp @@ -44,7 +44,7 @@ GCodeQueue queue; #endif #if ENABLED(POWER_LOSS_RECOVERY) - #include "../feature/power_loss_recovery.h" + #include "../feature/powerloss.h" #endif /** @@ -94,7 +94,7 @@ static PGM_P injected_commands_P = nullptr; GCodeQueue::GCodeQueue() { // Send "ok" after commands by default - for (uint8_t i = 0; i < COUNT(send_ok); i++) send_ok[i] = true; + LOOP_L_N(i, COUNT(send_ok)) send_ok[i] = true; } /** @@ -150,6 +150,8 @@ bool GCodeQueue::_enqueue(const char* cmd, bool say_ok/*=false*/ return true; } +#define ISEOL(C) ((C) == '\n' || (C) == '\r') + /** * Enqueue with Serial Echo * Return true if the command was consumed @@ -160,7 +162,7 @@ bool GCodeQueue::enqueue_one(const char* cmd) { //SERIAL_ECHO(cmd); //SERIAL_ECHOPGM("\") \n"); - if (*cmd == 0 || *cmd == '\n' || *cmd == '\r') return true; + if (*cmd == 0 || ISEOL(*cmd)) return true; if (_enqueue(cmd)) { SERIAL_ECHO_MSG(STR_ENQUEUEING, cmd, "\""); @@ -209,6 +211,21 @@ void GCodeQueue::inject_P(PGM_P const pgcode) { injected_commands_P = pgcode; } */ void GCodeQueue::enqueue_one_now(const char* cmd) { while (!enqueue_one(cmd)) idle(); } +/** + * Attempt to enqueue a single G-code command + * and return 'true' if successful. + */ +bool GCodeQueue::enqueue_one_P(PGM_P const pgcode) { + size_t i = 0; + PGM_P p = pgcode; + char c; + while ((c = pgm_read_byte(&p[i])) && c != '\n') i++; + char cmd[i + 1]; + memcpy_P(cmd, p, i); + cmd[i] = '\0'; + return _enqueue(cmd); +} + /** * Enqueue from program memory and return only when commands are actually enqueued * Never call this from a G-code handler! @@ -361,6 +378,10 @@ inline void process_stream_char(const char c, uint8_t &sis, char (&buff)[MAX_CMD sis = PS_EOL; // Skip the rest on overflow } +/** + * Handle a line being completed. For an empty line + * keep sensor readings going and watchdog alive. + */ inline bool process_line_done(uint8_t &sis, char (&buff)[MAX_CMD_SIZE], int &ind) { sis = PS_NORMAL; buff[ind] = 0; @@ -406,14 +427,14 @@ void GCodeQueue::get_serial_commands() { * Loop while serial characters are incoming and the queue is not full */ while (length < BUFSIZE && serial_data_available()) { - for (uint8_t i = 0; i < NUM_SERIAL; ++i) { + LOOP_L_N(i, NUM_SERIAL) { const int c = read_serial(i); if (c < 0) continue; const char serial_char = c; - if (serial_char == '\n' || serial_char == '\r') { + if (ISEOL(serial_char)) { // Reset our state, continue if the line was empty if (process_line_done(serial_input_state[i], serial_line_buffer[i], serial_count[i])) @@ -530,7 +551,7 @@ void GCodeQueue::get_serial_commands() { if (n < 0 && !card_eof) { SERIAL_ERROR_MSG(STR_SD_ERR_READ); continue; } const char sd_char = (char)n; - const bool is_eol = sd_char == '\n' || sd_char == '\r'; + const bool is_eol = ISEOL(sd_char); if (is_eol || card_eof) { // Reset stream state, terminate the buffer, and commit a non-empty command diff --git a/Marlin/src/gcode/queue.h b/Marlin/src/gcode/queue.h index 1ce64590c3..6a87d47ac8 100644 --- a/Marlin/src/gcode/queue.h +++ b/Marlin/src/gcode/queue.h @@ -77,6 +77,12 @@ public: */ static void enqueue_one_now(const char* cmd); + /** + * Attempt to enqueue a single G-code command + * and return 'true' if successful. + */ + static bool enqueue_one_P(PGM_P const pgcode); + /** * Enqueue from program memory and return only when commands are actually enqueued */ @@ -117,12 +123,6 @@ public: */ static void flush_and_request_resend(); - /** - * Attempt to enqueue a single G-code command - * and return 'true' if successful. - */ - FORCE_INLINE static bool enqueue_P(const char* cmd) { return _enqueue(cmd); } - private: static uint8_t index_w; // Ring buffer write position diff --git a/Marlin/src/gcode/sdcard/M20.cpp b/Marlin/src/gcode/sd/M20.cpp similarity index 100% rename from Marlin/src/gcode/sdcard/M20.cpp rename to Marlin/src/gcode/sd/M20.cpp diff --git a/Marlin/src/gcode/sdcard/M21_M22.cpp b/Marlin/src/gcode/sd/M21_M22.cpp similarity index 100% rename from Marlin/src/gcode/sdcard/M21_M22.cpp rename to Marlin/src/gcode/sd/M21_M22.cpp diff --git a/Marlin/src/gcode/sdcard/M23.cpp b/Marlin/src/gcode/sd/M23.cpp similarity index 100% rename from Marlin/src/gcode/sdcard/M23.cpp rename to Marlin/src/gcode/sd/M23.cpp diff --git a/Marlin/src/gcode/sdcard/M24_M25.cpp b/Marlin/src/gcode/sd/M24_M25.cpp similarity index 98% rename from Marlin/src/gcode/sdcard/M24_M25.cpp rename to Marlin/src/gcode/sd/M24_M25.cpp index db1a671fe4..c1e6dde8de 100644 --- a/Marlin/src/gcode/sdcard/M24_M25.cpp +++ b/Marlin/src/gcode/sd/M24_M25.cpp @@ -39,7 +39,7 @@ #endif #if ENABLED(POWER_LOSS_RECOVERY) - #include "../../feature/power_loss_recovery.h" + #include "../../feature/powerloss.h" #endif #include "../../MarlinCore.h" // for startOrResumeJob diff --git a/Marlin/src/gcode/sdcard/M26.cpp b/Marlin/src/gcode/sd/M26.cpp similarity index 100% rename from Marlin/src/gcode/sdcard/M26.cpp rename to Marlin/src/gcode/sd/M26.cpp diff --git a/Marlin/src/gcode/sdcard/M27.cpp b/Marlin/src/gcode/sd/M27.cpp similarity index 100% rename from Marlin/src/gcode/sdcard/M27.cpp rename to Marlin/src/gcode/sd/M27.cpp diff --git a/Marlin/src/gcode/sdcard/M28_M29.cpp b/Marlin/src/gcode/sd/M28_M29.cpp similarity index 100% rename from Marlin/src/gcode/sdcard/M28_M29.cpp rename to Marlin/src/gcode/sd/M28_M29.cpp diff --git a/Marlin/src/gcode/sdcard/M30.cpp b/Marlin/src/gcode/sd/M30.cpp similarity index 100% rename from Marlin/src/gcode/sdcard/M30.cpp rename to Marlin/src/gcode/sd/M30.cpp diff --git a/Marlin/src/gcode/sdcard/M32.cpp b/Marlin/src/gcode/sd/M32.cpp similarity index 100% rename from Marlin/src/gcode/sdcard/M32.cpp rename to Marlin/src/gcode/sd/M32.cpp diff --git a/Marlin/src/gcode/sdcard/M33.cpp b/Marlin/src/gcode/sd/M33.cpp similarity index 100% rename from Marlin/src/gcode/sdcard/M33.cpp rename to Marlin/src/gcode/sd/M33.cpp diff --git a/Marlin/src/gcode/sdcard/M34.cpp b/Marlin/src/gcode/sd/M34.cpp similarity index 100% rename from Marlin/src/gcode/sdcard/M34.cpp rename to Marlin/src/gcode/sd/M34.cpp diff --git a/Marlin/src/gcode/sdcard/M524.cpp b/Marlin/src/gcode/sd/M524.cpp similarity index 100% rename from Marlin/src/gcode/sdcard/M524.cpp rename to Marlin/src/gcode/sd/M524.cpp diff --git a/Marlin/src/gcode/sdcard/M928.cpp b/Marlin/src/gcode/sd/M928.cpp similarity index 100% rename from Marlin/src/gcode/sdcard/M928.cpp rename to Marlin/src/gcode/sd/M928.cpp diff --git a/Marlin/src/gcode/temperature/M104_M109.cpp b/Marlin/src/gcode/temp/M104_M109.cpp similarity index 99% rename from Marlin/src/gcode/temperature/M104_M109.cpp rename to Marlin/src/gcode/temp/M104_M109.cpp index ab99ea940c..434c6c9663 100644 --- a/Marlin/src/gcode/temperature/M104_M109.cpp +++ b/Marlin/src/gcode/temp/M104_M109.cpp @@ -21,7 +21,7 @@ */ /** - * gcode/temperature/M104_M109.cpp + * gcode/temp/M104_M109.cpp * * Hotend target temperature control */ diff --git a/Marlin/src/gcode/temperature/M105.cpp b/Marlin/src/gcode/temp/M105.cpp similarity index 100% rename from Marlin/src/gcode/temperature/M105.cpp rename to Marlin/src/gcode/temp/M105.cpp diff --git a/Marlin/src/gcode/temperature/M106_M107.cpp b/Marlin/src/gcode/temp/M106_M107.cpp similarity index 100% rename from Marlin/src/gcode/temperature/M106_M107.cpp rename to Marlin/src/gcode/temp/M106_M107.cpp diff --git a/Marlin/src/gcode/temperature/M140_M190.cpp b/Marlin/src/gcode/temp/M140_M190.cpp similarity index 98% rename from Marlin/src/gcode/temperature/M140_M190.cpp rename to Marlin/src/gcode/temp/M140_M190.cpp index ad7608705a..2da438707b 100644 --- a/Marlin/src/gcode/temperature/M140_M190.cpp +++ b/Marlin/src/gcode/temp/M140_M190.cpp @@ -21,7 +21,7 @@ */ /** - * gcode/temperature/M140_M190.cpp + * gcode/temp/M140_M190.cpp * * Bed target temperature control */ diff --git a/Marlin/src/gcode/temperature/M141_M191.cpp b/Marlin/src/gcode/temp/M141_M191.cpp similarity index 98% rename from Marlin/src/gcode/temperature/M141_M191.cpp rename to Marlin/src/gcode/temp/M141_M191.cpp index 66849b99e6..3f02836476 100644 --- a/Marlin/src/gcode/temperature/M141_M191.cpp +++ b/Marlin/src/gcode/temp/M141_M191.cpp @@ -21,7 +21,7 @@ */ /** - * gcode/temperature/M141_M191.cpp + * gcode/temp/M141_M191.cpp * * Chamber target temperature control */ diff --git a/Marlin/src/gcode/temperature/M155.cpp b/Marlin/src/gcode/temp/M155.cpp similarity index 100% rename from Marlin/src/gcode/temperature/M155.cpp rename to Marlin/src/gcode/temp/M155.cpp diff --git a/Marlin/src/gcode/temperature/M303.cpp b/Marlin/src/gcode/temp/M303.cpp similarity index 97% rename from Marlin/src/gcode/temperature/M303.cpp rename to Marlin/src/gcode/temp/M303.cpp index 31f7bf3501..63dcc3f4c4 100644 --- a/Marlin/src/gcode/temperature/M303.cpp +++ b/Marlin/src/gcode/temp/M303.cpp @@ -28,7 +28,7 @@ #include "../../module/temperature.h" #if ENABLED(EXTENSIBLE_UI) - #include "../../lcd/extensible_ui/ui_api.h" + #include "../../lcd/extui/ui_api.h" #endif /** diff --git a/Marlin/src/inc/Conditionals_LCD.h b/Marlin/src/inc/Conditionals_LCD.h index 9227f2c81a..2907694fb4 100644 --- a/Marlin/src/inc/Conditionals_LCD.h +++ b/Marlin/src/inc/Conditionals_LCD.h @@ -26,6 +26,15 @@ * Conditionals that need to be set before Configuration_adv.h or pins.h */ +#if ENABLED(MORGAN_SCARA) + #define IS_SCARA 1 + #define IS_KINEMATIC 1 +#elif ENABLED(DELTA) + #define IS_KINEMATIC 1 +#else + #define IS_CARTESIAN 1 +#endif + #if ENABLED(CARTESIO_UI) #define DOGLCD @@ -65,7 +74,6 @@ #define U8GLIB_ST7565_64128N #elif ENABLED(ELB_FULL_GRAPHIC_CONTROLLER) #define U8GLIB_LM6059_AF - #define SD_DETECT_INVERTED #elif ENABLED(AZSMZ_12864) #define U8GLIB_ST7565_64128N #endif @@ -193,7 +201,9 @@ #endif // 128x64 I2C OLED LCDs - SSD1306/SSD1309/SH1106 -#define HAS_SSD1306_OLED_I2C ANY(U8GLIB_SSD1306, U8GLIB_SSD1309, U8GLIB_SH1106) +#if ANY(U8GLIB_SSD1306, U8GLIB_SSD1309, U8GLIB_SH1106) + #define HAS_SSD1306_OLED_I2C 1 +#endif #if HAS_SSD1306_OLED_I2C #define IS_ULTRA_LCD #define DOGLCD @@ -346,20 +356,36 @@ #endif #endif +// Aliases for LCD features +#if ANY(DGUS_LCD_UI_ORIGIN, DGUS_LCD_UI_FYSETC, DGUS_LCD_UI_HIPRECY) + #define HAS_DGUS_LCD 1 +#endif + // Extensible UI serial touch screens. (See src/lcd/extensible_ui) -#if ANY(MALYAN_LCD, DGUS_LCD, TOUCH_UI_FTDI_EVE) +#if ANY(HAS_DGUS_LCD, MALYAN_LCD, TOUCH_UI_FTDI_EVE) #define IS_EXTUI #define EXTENSIBLE_UI #endif // Aliases for LCD features -#define HAS_SPI_LCD ENABLED(ULTRA_LCD) -#define HAS_DISPLAY (HAS_SPI_LCD || ENABLED(EXTENSIBLE_UI)) -#define HAS_GRAPHICAL_LCD ENABLED(DOGLCD) -#define HAS_CHARACTER_LCD (HAS_SPI_LCD && !HAS_GRAPHICAL_LCD) -#define HAS_LCD_MENU (ENABLED(ULTIPANEL) && DISABLED(NO_LCD_MENUS)) -#define HAS_ADC_BUTTONS ENABLED(ADC_KEYPAD) -#define HAS_DGUS_LCD ANY(DGUS_LCD_UI_ORIGIN, DGUS_LCD_UI_FYSETC, DGUS_LCD_UI_HIPRECY) +#if EITHER(ULTRA_LCD, EXTENSIBLE_UI) + #define HAS_DISPLAY 1 + #if ENABLED(ULTRA_LCD) + #define HAS_SPI_LCD 1 + #if ENABLED(DOGLCD) + #define HAS_GRAPHICAL_LCD 1 + #else + #define HAS_CHARACTER_LCD 1 + #endif + #endif +#endif + +#if ENABLED(ULTIPANEL) && DISABLED(NO_LCD_MENUS) + #define HAS_LCD_MENU 1 +#endif +#if ENABLED(ADC_KEYPAD) + #define HAS_ADC_BUTTONS 1 +#endif #if HAS_GRAPHICAL_LCD #ifndef LCD_PIXEL_WIDTH @@ -433,22 +459,46 @@ #ifndef HOTENDS #define HOTENDS EXTRUDERS #endif - #ifndef E_STEPPERS #define E_STEPPERS EXTRUDERS #endif - #ifndef E_MANUAL #define E_MANUAL EXTRUDERS #endif +// Helper macros for extruder and hotend arrays #define HOTEND_LOOP() for (int8_t e = 0; e < HOTENDS; e++) +#define ARRAY_BY_EXTRUDERS(V...) ARRAY_N(EXTRUDERS, V) +#define ARRAY_BY_EXTRUDERS1(v1) ARRAY_BY_EXTRUDERS(v1, v1, v1, v1, v1, v1, v1, v1) +#define ARRAY_BY_HOTENDS(V...) ARRAY_N(HOTENDS, V) +#define ARRAY_BY_HOTENDS1(v1) ARRAY_BY_HOTENDS(v1, v1, v1, v1, v1, v1, v1, v1) -#define DO_SWITCH_EXTRUDER (ENABLED(SWITCHING_EXTRUDER) && (DISABLED(SWITCHING_NOZZLE) || SWITCHING_EXTRUDER_SERVO_NR != SWITCHING_NOZZLE_SERVO_NR)) -#define SWITCHING_NOZZLE_TWO_SERVOS defined(SWITCHING_NOZZLE_E1_SERVO_NR) +#if ENABLED(SWITCHING_EXTRUDER) && (DISABLED(SWITCHING_NOZZLE) || SWITCHING_EXTRUDER_SERVO_NR != SWITCHING_NOZZLE_SERVO_NR) + #define DO_SWITCH_EXTRUDER 1 +#endif -#define HAS_HOTEND_OFFSET (HOTENDS > 1) -#define HAS_DUPLICATION_MODE EITHER(DUAL_X_CARRIAGE, MULTI_NOZZLE_DUPLICATION) +#ifdef SWITCHING_NOZZLE_E1_SERVO_NR + #define SWITCHING_NOZZLE_TWO_SERVOS 1 +#endif + +#if HOTENDS > 1 + #define HAS_HOTEND_OFFSET 1 +#endif + +/** + * Default hotend offsets, if not defined + */ +#if HAS_HOTEND_OFFSET + #ifndef HOTEND_OFFSET_X + #define HOTEND_OFFSET_X { 0 } // X offsets for each extruder + #endif + #ifndef HOTEND_OFFSET_Y + #define HOTEND_OFFSET_Y { 0 } // Y offsets for each extruder + #endif + #ifndef HOTEND_OFFSET_Z + #define HOTEND_OFFSET_Z { 0 } // Z offsets for each extruder + #endif +#endif /** * DISTINCT_E_FACTORS affects how some E factors are accessed @@ -490,6 +540,10 @@ #endif #endif +#ifndef NUM_SERVOS + #define NUM_SERVOS 0 +#endif + #ifndef PREHEAT_1_LABEL #define PREHEAT_1_LABEL "PLA" #endif @@ -501,8 +555,12 @@ /** * Set a flag for a servo probe (or BLTouch) */ -#define HAS_Z_SERVO_PROBE (defined(Z_PROBE_SERVO_NR) && Z_PROBE_SERVO_NR >= 0) -#define HAS_SERVO_ANGLES (HAS_Z_SERVO_PROBE || EITHER(SWITCHING_EXTRUDER, SWITCHING_NOZZLE)) +#if defined(Z_PROBE_SERVO_NR) && Z_PROBE_SERVO_NR >= 0 + #define HAS_Z_SERVO_PROBE 1 +#endif +#if HAS_Z_SERVO_PROBE || EITHER(SWITCHING_EXTRUDER, SWITCHING_NOZZLE) + #define HAS_SERVO_ANGLES 1 +#endif #if !HAS_SERVO_ANGLES #undef EDITABLE_SERVO_ANGLES #endif @@ -510,20 +568,31 @@ /** * Set flags for enabled probes */ -#define HAS_BED_PROBE (HAS_Z_SERVO_PROBE || ANY(FIX_MOUNTED_PROBE, NOZZLE_AS_PROBE, TOUCH_MI_PROBE, Z_PROBE_ALLEN_KEY, Z_PROBE_SLED, SOLENOID_PROBE, SENSORLESS_PROBING, RACK_AND_PINION_PROBE)) -#define PROBE_SELECTED (HAS_BED_PROBE || EITHER(PROBE_MANUALLY, MESH_BED_LEVELING)) +#if ANY(HAS_Z_SERVO_PROBE, FIX_MOUNTED_PROBE, NOZZLE_AS_PROBE, TOUCH_MI_PROBE, Z_PROBE_ALLEN_KEY, Z_PROBE_SLED, SOLENOID_PROBE, SENSORLESS_PROBING, RACK_AND_PINION_PROBE) + #define HAS_BED_PROBE 1 +#endif + +#if HAS_BED_PROBE || EITHER(PROBE_MANUALLY, MESH_BED_LEVELING) + #define PROBE_SELECTED 1 +#endif #if HAS_BED_PROBE - #define HAS_PROBE_XY_OFFSET DISABLED(NOZZLE_AS_PROBE) - #define HAS_CUSTOM_PROBE_PIN DISABLED(Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN) - #define HOMING_Z_WITH_PROBE (Z_HOME_DIR < 0 && !HAS_CUSTOM_PROBE_PIN) + #if DISABLED(NOZZLE_AS_PROBE) + #define HAS_PROBE_XY_OFFSET 1 + #endif + #if DISABLED(Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN) + #define HAS_CUSTOM_PROBE_PIN 1 + #endif + #if Z_HOME_DIR < 0 && !HAS_CUSTOM_PROBE_PIN + #define HOMING_Z_WITH_PROBE 1 + #endif #ifndef Z_PROBE_LOW_POINT #define Z_PROBE_LOW_POINT -5 #endif #if ENABLED(Z_PROBE_ALLEN_KEY) - #define PROBE_TRIGGERED_WHEN_STOWED_TEST // Extra test for Allen Key Probe + #define PROBE_TRIGGERED_WHEN_STOWED_TEST 1 // Extra test for Allen Key Probe #endif - #ifdef MULTIPLE_PROBING + #if MULTIPLE_PROBING > 1 #if EXTRA_PROBING #define TOTAL_PROBING (MULTIPLE_PROBING + EXTRA_PROBING) #else @@ -535,26 +604,53 @@ #undef Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN #endif -#ifdef GRID_MAX_POINTS_X - #define GRID_MAX_POINTS ((GRID_MAX_POINTS_X) * (GRID_MAX_POINTS_Y)) +/** + * Set granular options based on the specific type of leveling + */ +#if ENABLED(AUTO_BED_LEVELING_UBL) + #undef LCD_BED_LEVELING + #if ENABLED(DELTA) + #define UBL_SEGMENTED 1 + #endif +#endif +#if EITHER(AUTO_BED_LEVELING_LINEAR, AUTO_BED_LEVELING_3POINT) + #define ABL_PLANAR 1 +#endif +#if EITHER(AUTO_BED_LEVELING_LINEAR, AUTO_BED_LEVELING_BILINEAR) + #define ABL_GRID 1 +#endif +#if ANY(AUTO_BED_LEVELING_LINEAR, AUTO_BED_LEVELING_BILINEAR, AUTO_BED_LEVELING_3POINT) + #define HAS_ABL_NOT_UBL 1 +#endif +#if ANY(AUTO_BED_LEVELING_BILINEAR, AUTO_BED_LEVELING_UBL, MESH_BED_LEVELING) + #define HAS_MESH 1 +#endif +#if EITHER(AUTO_BED_LEVELING_UBL, AUTO_BED_LEVELING_3POINT) + #define NEEDS_THREE_PROBE_POINTS 1 +#endif +#if EITHER(HAS_ABL_NOT_UBL, AUTO_BED_LEVELING_UBL) + #define HAS_ABL_OR_UBL 1 + #if DISABLED(PROBE_MANUALLY) + #define HAS_AUTOLEVEL 1 + #endif +#endif +#if EITHER(HAS_ABL_OR_UBL, MESH_BED_LEVELING) + #define HAS_LEVELING 1 + #if DISABLED(AUTO_BED_LEVELING_UBL) + #define PLANNER_LEVELING 1 + #endif +#endif +#if EITHER(HAS_ABL_OR_UBL, Z_MIN_PROBE_REPEATABILITY_TEST) + #define HAS_PROBING_PROCEDURE 1 +#endif +#if !HAS_LEVELING + #undef RESTORE_LEVELING_AFTER_G28 #endif -#define HAS_EXTRA_ENDSTOPS ANY(X_DUAL_ENDSTOPS, Y_DUAL_ENDSTOPS, Z_MULTI_ENDSTOPS) -#define HAS_SOFTWARE_ENDSTOPS EITHER(MIN_SOFTWARE_ENDSTOPS, MAX_SOFTWARE_ENDSTOPS) -#define HAS_RESUME_CONTINUE ANY(EXTENSIBLE_UI, NEWPANEL, EMERGENCY_PARSER) -#define HAS_COLOR_LEDS ANY(BLINKM, RGB_LED, RGBW_LED, PCA9632, PCA9533, NEOPIXEL_LED) -#define HAS_LEDS_OFF_FLAG (BOTH(PRINTER_EVENT_LEDS, SDSUPPORT) && HAS_RESUME_CONTINUE) -#define HAS_PRINT_PROGRESS EITHER(SDSUPPORT, LCD_SET_PROGRESS_MANUALLY) -#define HAS_PRINT_PROGRESS_PERMYRIAD (HAS_PRINT_PROGRESS && EITHER(PRINT_PROGRESS_SHOW_DECIMALS, SHOW_REMAINING_TIME)) -#define HAS_SERVICE_INTERVALS (ENABLED(PRINTCOUNTER) && (SERVICE_INTERVAL_1 > 0 || SERVICE_INTERVAL_2 > 0 || SERVICE_INTERVAL_3 > 0)) -#define HAS_FILAMENT_SENSOR ENABLED(FILAMENT_RUNOUT_SENSOR) - -#define HAS_GAMES ANY(MARLIN_BRICKOUT, MARLIN_INVADERS, MARLIN_SNAKE, MARLIN_MAZE) -#define HAS_GAME_MENU (1 < ENABLED(MARLIN_BRICKOUT) + ENABLED(MARLIN_INVADERS) + ENABLED(MARLIN_SNAKE) + ENABLED(MARLIN_MAZE)) - -#define IS_SCARA ENABLED(MORGAN_SCARA) -#define IS_KINEMATIC (ENABLED(DELTA) || IS_SCARA) -#define IS_CARTESIAN !IS_KINEMATIC +#ifdef GRID_MAX_POINTS_X + #define GRID_MAX_POINTS ((GRID_MAX_POINTS_X) * (GRID_MAX_POINTS_Y)) + #define GRID_LOOP(A,B) LOOP_L_N(A, GRID_MAX_POINTS_X) LOOP_L_N(B, GRID_MAX_POINTS_Y) +#endif #ifndef INVERT_X_DIR #define INVERT_X_DIR false @@ -573,10 +669,24 @@ #define BOOT_MARLIN_LOGO_SMALL #endif -#define IS_RE_ARM_BOARD MB(RAMPS_14_RE_ARM_EFB, RAMPS_14_RE_ARM_EEB, RAMPS_14_RE_ARM_EFF, RAMPS_14_RE_ARM_EEF, RAMPS_14_RE_ARM_SF) +// This flag indicates some kind of jerk storage is needed +#if ENABLED(CLASSIC_JERK) || IS_KINEMATIC + #define HAS_CLASSIC_JERK 1 +#endif -#define HAS_LINEAR_E_JERK (DISABLED(CLASSIC_JERK) && ENABLED(LIN_ADVANCE)) +// E jerk exists with JD disabled (of course) but also when Linear Advance is disabled on Delta/SCARA +#if ENABLED(CLASSIC_JERK) || (IS_KINEMATIC && DISABLED(LIN_ADVANCE)) + #define HAS_CLASSIC_E_JERK 1 +#endif #ifndef SPI_SPEED #define SPI_SPEED SPI_FULL_SPEED #endif + +/** + * This setting is also used by M109 when trying to calculate + * a ballpark safe margin to prevent wait-forever situation. + */ +#ifndef EXTRUDE_MINTEMP + #define EXTRUDE_MINTEMP 170 +#endif diff --git a/Marlin/src/inc/Conditionals_adv.h b/Marlin/src/inc/Conditionals_adv.h index e5cb00c112..09de5d89d7 100644 --- a/Marlin/src/inc/Conditionals_adv.h +++ b/Marlin/src/inc/Conditionals_adv.h @@ -56,11 +56,66 @@ #undef SHOW_TEMP_ADC_VALUES #endif +#if EITHER(DUAL_X_CARRIAGE, MULTI_NOZZLE_DUPLICATION) + #define HAS_DUPLICATION_MODE 1 +#endif + +#if ENABLED(PRINTCOUNTER) && (SERVICE_INTERVAL_1 > 0 || SERVICE_INTERVAL_2 > 0 || SERVICE_INTERVAL_3 > 0) + #define HAS_SERVICE_INTERVALS 1 +#endif + +#if ENABLED(FILAMENT_RUNOUT_SENSOR) + #define HAS_FILAMENT_SENSOR 1 +#endif + +#if EITHER(SDSUPPORT, LCD_SET_PROGRESS_MANUALLY) + #define HAS_PRINT_PROGRESS 1 +#endif + +#if HAS_PRINT_PROGRESS && EITHER(PRINT_PROGRESS_SHOW_DECIMALS, SHOW_REMAINING_TIME) + #define HAS_PRINT_PROGRESS_PERMYRIAD 1 +#endif + +#if ANY(MARLIN_BRICKOUT, MARLIN_INVADERS, MARLIN_SNAKE, MARLIN_MAZE) + #define HAS_GAMES 1 + #if (1 < ENABLED(MARLIN_BRICKOUT) + ENABLED(MARLIN_INVADERS) + ENABLED(MARLIN_SNAKE) + ENABLED(MARLIN_MAZE)) + #define HAS_GAME_MENU 1 + #endif +#endif + +#if ANY(FWRETRACT, HAS_LEVELING, SKEW_CORRECTION) + #define HAS_POSITION_MODIFIERS 1 +#endif + +#if ANY(X_DUAL_ENDSTOPS, Y_DUAL_ENDSTOPS, Z_MULTI_ENDSTOPS) + #define HAS_EXTRA_ENDSTOPS 1 +#endif +#if EITHER(MIN_SOFTWARE_ENDSTOPS, MAX_SOFTWARE_ENDSTOPS) + #define HAS_SOFTWARE_ENDSTOPS 1 +#endif +#if ANY(EXTENSIBLE_UI, NEWPANEL, EMERGENCY_PARSER) + #define HAS_RESUME_CONTINUE 1 +#endif + +#if ANY(BLINKM, RGB_LED, RGBW_LED, PCA9632, PCA9533, NEOPIXEL_LED) + #define HAS_COLOR_LEDS 1 +#endif +#if ALL(HAS_RESUME_CONTINUE, PRINTER_EVENT_LEDS, SDSUPPORT) + #define HAS_LEDS_OFF_FLAG 1 +#endif + // Multiple Z steppers #ifndef NUM_Z_STEPPER_DRIVERS #define NUM_Z_STEPPER_DRIVERS 1 #endif +#if ENABLED(Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS) + #undef Z_STEPPER_ALIGN_AMP +#endif +#ifndef Z_STEPPER_ALIGN_AMP + #define Z_STEPPER_ALIGN_AMP 1.0 +#endif + #define HAS_CUTTER EITHER(SPINDLE_FEATURE, LASER_FEATURE) #if !defined(__AVR__) || !defined(USBCON) @@ -121,9 +176,6 @@ #define LED_CONTROL_MENU #define LED_USER_PRESET_STARTUP #define LED_COLOR_PRESETS - #ifndef LED_USER_PRESET_RED - #define LED_USER_PRESET_RED 255 - #endif #ifndef LED_USER_PRESET_GREEN #define LED_USER_PRESET_GREEN 128 #endif @@ -135,15 +187,106 @@ #endif #endif +// Set defaults for unspecified LED user colors +#if ENABLED(LED_CONTROL_MENU) + #ifndef LED_USER_PRESET_RED + #define LED_USER_PRESET_RED 255 + #endif + #ifndef LED_USER_PRESET_GREEN + #define LED_USER_PRESET_GREEN 255 + #endif + #ifndef LED_USER_PRESET_BLUE + #define LED_USER_PRESET_BLUE 255 + #endif + #ifndef LED_USER_PRESET_WHITE + #define LED_USER_PRESET_WHITE 0 + #endif + #ifndef LED_USER_PRESET_BRIGHTNESS + #ifdef NEOPIXEL_BRIGHTNESS + #define LED_USER_PRESET_BRIGHTNESS NEOPIXEL_BRIGHTNESS + #else + #define LED_USER_PRESET_BRIGHTNESS 255 + #endif + #endif +#endif + +// If platform requires early initialization of watchdog to properly boot +#if ENABLED(USE_WATCHDOG) && defined(ARDUINO_ARCH_SAM) + #define EARLY_WATCHDOG 1 +#endif + // Extensible UI pin mapping for RepRapDiscount -#define TOUCH_UI_ULTIPANEL ENABLED(TOUCH_UI_FTDI_EVE) && ANY(AO_EXP1_PINMAP, AO_EXP2_PINMAP, CR10_TFT_PINMAP) +#if ENABLED(TOUCH_UI_FTDI_EVE) && ANY(AO_EXP1_PINMAP, AO_EXP2_PINMAP, CR10_TFT_PINMAP) + #define TOUCH_UI_ULTIPANEL 1 +#endif // Poll-based jogging for joystick and other devices #if ENABLED(JOYSTICK) #define POLL_JOG #endif -// G60/G61 Position Save -#if SAVED_POSITIONS > 256 - #error "SAVED_POSITIONS must be an integer from 0 to 256." +/** + * Driver Timings + * NOTE: Driver timing order is longest-to-shortest duration. + * Preserve this ordering when adding new drivers. + */ + +#ifndef MINIMUM_STEPPER_POST_DIR_DELAY + #if HAS_DRIVER(TB6560) + #define MINIMUM_STEPPER_POST_DIR_DELAY 15000 + #elif HAS_DRIVER(TB6600) + #define MINIMUM_STEPPER_POST_DIR_DELAY 1500 + #elif HAS_DRIVER(DRV8825) + #define MINIMUM_STEPPER_POST_DIR_DELAY 650 + #elif HAS_DRIVER(LV8729) + #define MINIMUM_STEPPER_POST_DIR_DELAY 500 + #elif HAS_DRIVER(A5984) + #define MINIMUM_STEPPER_POST_DIR_DELAY 400 + #elif HAS_DRIVER(A4988) + #define MINIMUM_STEPPER_POST_DIR_DELAY 200 + #elif HAS_TRINAMIC_CONFIG || HAS_TRINAMIC_STANDALONE + #define MINIMUM_STEPPER_POST_DIR_DELAY 20 + #else + #define MINIMUM_STEPPER_POST_DIR_DELAY 0 // Expect at least 10µS since one Stepper ISR must transpire + #endif +#endif + +#ifndef MINIMUM_STEPPER_PRE_DIR_DELAY + #define MINIMUM_STEPPER_PRE_DIR_DELAY MINIMUM_STEPPER_POST_DIR_DELAY +#endif + +#ifndef MINIMUM_STEPPER_PULSE + #if HAS_DRIVER(TB6560) + #define MINIMUM_STEPPER_PULSE 30 + #elif HAS_DRIVER(TB6600) + #define MINIMUM_STEPPER_PULSE 3 + #elif HAS_DRIVER(DRV8825) + #define MINIMUM_STEPPER_PULSE 2 + #elif HAS_DRIVER(A4988) || HAS_DRIVER(A5984) + #define MINIMUM_STEPPER_PULSE 1 + #elif HAS_TRINAMIC_CONFIG || HAS_TRINAMIC_STANDALONE + #define MINIMUM_STEPPER_PULSE 0 + #elif HAS_DRIVER(LV8729) + #define MINIMUM_STEPPER_PULSE 0 + #else + #define MINIMUM_STEPPER_PULSE 2 + #endif +#endif + +#ifndef MAXIMUM_STEPPER_RATE + #if HAS_DRIVER(TB6560) + #define MAXIMUM_STEPPER_RATE 15000 + #elif HAS_DRIVER(TB6600) + #define MAXIMUM_STEPPER_RATE 150000 + #elif HAS_DRIVER(DRV8825) + #define MAXIMUM_STEPPER_RATE 250000 + #elif HAS_DRIVER(A4988) + #define MAXIMUM_STEPPER_RATE 500000 + #elif HAS_DRIVER(LV8729) + #define MAXIMUM_STEPPER_RATE 1000000 + #elif HAS_TRINAMIC_CONFIG || HAS_TRINAMIC_STANDALONE + #define MAXIMUM_STEPPER_RATE 5000000 + #else + #define MAXIMUM_STEPPER_RATE 250000 + #endif #endif diff --git a/Marlin/src/inc/Conditionals_post.h b/Marlin/src/inc/Conditionals_post.h index 159aefa5d5..97090d4775 100644 --- a/Marlin/src/inc/Conditionals_post.h +++ b/Marlin/src/inc/Conditionals_post.h @@ -30,6 +30,28 @@ // Extras for CI testing #endif +// Linear advance uses Jerk since E is an isolated axis +#if DISABLED(CLASSIC_JERK) && ENABLED(LIN_ADVANCE) + #define HAS_LINEAR_E_JERK 1 +#endif + +#if ENABLED(EEPROM_SETTINGS) + #if NONE(FLASH_EEPROM_EMULATION, SRAM_EEPROM_EMULATION, SDCARD_EEPROM_EMULATION) && EITHER(I2C_EEPROM, SPI_EEPROM) + #define USE_REAL_EEPROM 1 + #else + #define USE_EMULATED_EEPROM 1 + #endif + #if NONE(USE_REAL_EEPROM, FLASH_EEPROM_EMULATION, SRAM_EEPROM_EMULATION) + #define SDCARD_EEPROM_EMULATION 1 + #endif +#else + #undef I2C_EEPROM + #undef SPI_EEPROM + #undef SDCARD_EEPROM_EMULATION + #undef SRAM_EEPROM_EMULATION + #undef FLASH_EEPROM_EMULATION +#endif + #ifdef TEENSYDUINO #undef max #define max(a,b) ((a)>(b)?(a):(b)) @@ -40,9 +62,6 @@ #define NOT_A_PIN 0 // For PINS_DEBUGGING #endif -#define HAS_CLASSIC_JERK (ENABLED(CLASSIC_JERK) || IS_KINEMATIC) -#define HAS_CLASSIC_E_JERK (ENABLED(CLASSIC_JERK) || DISABLED(LIN_ADVANCE)) - /** * Axis lengths and center */ @@ -66,13 +85,8 @@ // Define center values for future use #define _X_HALF_BED ((X_BED_SIZE) / 2) #define _Y_HALF_BED ((Y_BED_SIZE) / 2) -#if ENABLED(BED_CENTER_AT_0_0) - #define X_CENTER 0 - #define Y_CENTER 0 -#else - #define X_CENTER _X_HALF_BED - #define Y_CENTER _Y_HALF_BED -#endif +#define X_CENTER TERN(BED_CENTER_AT_0_0, 0, _X_HALF_BED) +#define Y_CENTER TERN(BED_CENTER_AT_0_0, 0, _Y_HALF_BED) // Get the linear boundaries of the bed #define X_MIN_BED (X_CENTER - _X_HALF_BED) @@ -95,10 +109,18 @@ /** * CoreXY, CoreXZ, and CoreYZ - and their reverse */ -#define CORE_IS_XY EITHER(COREXY, COREYX) -#define CORE_IS_XZ EITHER(COREXZ, COREZX) -#define CORE_IS_YZ EITHER(COREYZ, COREZY) -#define IS_CORE (CORE_IS_XY || CORE_IS_XZ || CORE_IS_YZ) +#if EITHER(COREXY, COREYX) + #define CORE_IS_XY 1 +#endif +#if EITHER(COREXZ, COREZX) + #define CORE_IS_XZ 1 +#endif +#if EITHER(COREYZ, COREZY) + #define CORE_IS_YZ 1 +#endif +#if CORE_IS_XY || CORE_IS_XZ || CORE_IS_YZ + #define IS_CORE 1 +#endif #if IS_CORE #if CORE_IS_XY #define CORE_AXIS_1 A_AXIS @@ -113,11 +135,7 @@ #define CORE_AXIS_1 B_AXIS #define CORE_AXIS_2 C_AXIS #endif - #if ANY(COREYX, COREZX, COREZY) - #define CORESIGN(n) (-(n)) - #else - #define CORESIGN(n) (n) - #endif + #define CORESIGN(n) (ANY(COREYX, COREZX, COREZY) ? (-(n)) : (n)) #endif /** @@ -142,33 +160,23 @@ */ #ifdef MANUAL_X_HOME_POS #define X_HOME_POS MANUAL_X_HOME_POS -#elif ENABLED(BED_CENTER_AT_0_0) - #if ENABLED(DELTA) - #define X_HOME_POS 0 - #else - #define X_HOME_POS (X_HOME_DIR < 0 ? X_MIN_POS : X_MAX_POS) - #endif #else - #if ENABLED(DELTA) - #define X_HOME_POS (X_MIN_POS + (X_BED_SIZE) * 0.5) + #define X_END_POS (X_HOME_DIR < 0 ? X_MIN_POS : X_MAX_POS) + #if ENABLED(BED_CENTER_AT_0_0) + #define X_HOME_POS TERN(DELTA, 0, X_END_POS) #else - #define X_HOME_POS (X_HOME_DIR < 0 ? X_MIN_POS : X_MAX_POS) + #define X_HOME_POS TERN(DELTA, X_MIN_POS + (X_BED_SIZE) * 0.5, X_END_POS) #endif #endif #ifdef MANUAL_Y_HOME_POS #define Y_HOME_POS MANUAL_Y_HOME_POS -#elif ENABLED(BED_CENTER_AT_0_0) - #if ENABLED(DELTA) - #define Y_HOME_POS 0 - #else - #define Y_HOME_POS (Y_HOME_DIR < 0 ? Y_MIN_POS : Y_MAX_POS) - #endif #else - #if ENABLED(DELTA) - #define Y_HOME_POS (Y_MIN_POS + (Y_BED_SIZE) * 0.5) + #define Y_END_POS (Y_HOME_DIR < 0 ? Y_MIN_POS : Y_MAX_POS) + #if ENABLED(BED_CENTER_AT_0_0) + #define Y_HOME_POS TERN(DELTA, 0, Y_END_POS) #else - #define Y_HOME_POS (Y_HOME_DIR < 0 ? Y_MIN_POS : Y_MAX_POS) + #define Y_HOME_POS TERN(DELTA, Y_MIN_POS + (Y_BED_SIZE) * 0.5, Y_END_POS) #endif #endif @@ -271,7 +279,10 @@ #define _LCD_CONTRAST_INIT 17 #endif -#define HAS_LCD_CONTRAST defined(_LCD_CONTRAST_INIT) +#ifdef _LCD_CONTRAST_INIT + #define HAS_LCD_CONTRAST 1 +#endif + #if HAS_LCD_CONTRAST #ifndef LCD_CONTRAST_MIN #ifdef _LCD_CONTRAST_MIN @@ -298,10 +309,18 @@ #endif /** - * Override here because this is set in Configuration_adv.h + * Override the SD_DETECT_STATE set in Configuration_adv.h */ -#if HAS_LCD_MENU && DISABLED(ELB_FULL_GRAPHIC_CONTROLLER) && !(defined(ARDUINO_GRAND_CENTRAL_M4) && SD_CONNECTION_IS(ONBOARD)) - #undef SD_DETECT_INVERTED +#if ENABLED(SDSUPPORT) + #if HAS_LCD_MENU && (SD_CONNECTION_IS(LCD) || !defined(SDCARD_CONNECTION)) + #undef SD_DETECT_STATE + #if ENABLED(ELB_FULL_GRAPHIC_CONTROLLER) + #define SD_DETECT_STATE HIGH + #endif + #endif + #ifndef SD_DETECT_STATE + #define SD_DETECT_STATE LOW + #endif #endif /** @@ -579,99 +598,6 @@ HEATER_0_USES_THERMISTOR, HEATER_1_USES_THERMISTOR, HEATER_2_USES_THERMISTOR, HEATER_3_USES_THERMISTOR, \ HEATER_4_USES_THERMISTOR, HEATER_5_USES_THERMISTOR, HEATER_6_USES_THERMISTOR, HEATER_7_USES_THERMISTOR ) -/** - * Default hotend offsets, if not defined - */ -#if HAS_HOTEND_OFFSET - #ifndef HOTEND_OFFSET_X - #define HOTEND_OFFSET_X { 0 } // X offsets for each extruder - #endif - #ifndef HOTEND_OFFSET_Y - #define HOTEND_OFFSET_Y { 0 } // Y offsets for each extruder - #endif - #ifndef HOTEND_OFFSET_Z - #define HOTEND_OFFSET_Z { 0 } // Z offsets for each extruder - #endif -#endif - -/** - * ARRAY_BY_EXTRUDERS based on EXTRUDERS - */ -#define ARRAY_BY_EXTRUDERS(V...) ARRAY_N(EXTRUDERS, V) -#define ARRAY_BY_EXTRUDERS1(v1) ARRAY_BY_EXTRUDERS(v1, v1, v1, v1, v1, v1) - -/** - * ARRAY_BY_HOTENDS based on HOTENDS - */ -#define ARRAY_BY_HOTENDS(V...) ARRAY_N(HOTENDS, V) -#define ARRAY_BY_HOTENDS1(v1) ARRAY_BY_HOTENDS(v1, v1, v1, v1, v1, v1) - -/** - * Driver Timings - * NOTE: Driver timing order is longest-to-shortest duration. - * Preserve this ordering when adding new drivers. - */ - -#ifndef MINIMUM_STEPPER_POST_DIR_DELAY - #if HAS_DRIVER(TB6560) - #define MINIMUM_STEPPER_POST_DIR_DELAY 15000 - #elif HAS_DRIVER(TB6600) - #define MINIMUM_STEPPER_POST_DIR_DELAY 1500 - #elif HAS_DRIVER(DRV8825) - #define MINIMUM_STEPPER_POST_DIR_DELAY 650 - #elif HAS_DRIVER(LV8729) - #define MINIMUM_STEPPER_POST_DIR_DELAY 500 - #elif HAS_DRIVER(A5984) - #define MINIMUM_STEPPER_POST_DIR_DELAY 400 - #elif HAS_DRIVER(A4988) - #define MINIMUM_STEPPER_POST_DIR_DELAY 200 - #elif HAS_TRINAMIC || HAS_TRINAMIC_STANDALONE - #define MINIMUM_STEPPER_POST_DIR_DELAY 20 - #else - #define MINIMUM_STEPPER_POST_DIR_DELAY 0 // Expect at least 10µS since one Stepper ISR must transpire - #endif -#endif - -#ifndef MINIMUM_STEPPER_PRE_DIR_DELAY - #define MINIMUM_STEPPER_PRE_DIR_DELAY MINIMUM_STEPPER_POST_DIR_DELAY -#endif - -#ifndef MINIMUM_STEPPER_PULSE - #if HAS_DRIVER(TB6560) - #define MINIMUM_STEPPER_PULSE 30 - #elif HAS_DRIVER(TB6600) - #define MINIMUM_STEPPER_PULSE 3 - #elif HAS_DRIVER(DRV8825) - #define MINIMUM_STEPPER_PULSE 2 - #elif HAS_DRIVER(A4988) || HAS_DRIVER(A5984) - #define MINIMUM_STEPPER_PULSE 1 - #elif HAS_TRINAMIC || HAS_TRINAMIC_STANDALONE - #define MINIMUM_STEPPER_PULSE 0 - #elif HAS_DRIVER(LV8729) - #define MINIMUM_STEPPER_PULSE 0 - #else - #define MINIMUM_STEPPER_PULSE 2 - #endif -#endif - -#ifndef MAXIMUM_STEPPER_RATE - #if HAS_DRIVER(TB6560) - #define MAXIMUM_STEPPER_RATE 15000 - #elif HAS_DRIVER(TB6600) - #define MAXIMUM_STEPPER_RATE 150000 - #elif HAS_DRIVER(DRV8825) - #define MAXIMUM_STEPPER_RATE 250000 - #elif HAS_DRIVER(A4988) - #define MAXIMUM_STEPPER_RATE 500000 - #elif HAS_DRIVER(LV8729) - #define MAXIMUM_STEPPER_RATE 1000000 - #elif HAS_TRINAMIC || HAS_TRINAMIC_STANDALONE - #define MAXIMUM_STEPPER_RATE 5000000 - #else - #define MAXIMUM_STEPPER_RATE 250000 - #endif -#endif - /** * X_DUAL_ENDSTOPS endstop reassignment */ @@ -1386,21 +1312,41 @@ #define HAS_SOLENOID_7 (PIN_EXISTS(SOL7)) // Trinamic Stepper Drivers -#if HAS_TRINAMIC - #define STEALTHCHOP_ENABLED ANY(STEALTHCHOP_XY, STEALTHCHOP_Z, STEALTHCHOP_E) - #define USE_SENSORLESS EITHER(SENSORLESS_HOMING, SENSORLESS_PROBING) +#if HAS_TRINAMIC_CONFIG + #if ANY(STEALTHCHOP_XY, STEALTHCHOP_Z, STEALTHCHOP_E) + #define STEALTHCHOP_ENABLED 1 + #endif + #if EITHER(SENSORLESS_HOMING, SENSORLESS_PROBING) + #define USE_SENSORLESS 1 + #endif // Disable Z axis sensorless homing if a probe is used to home the Z axis #if HOMING_Z_WITH_PROBE #undef Z_STALL_SENSITIVITY #endif - #define X_SENSORLESS (AXIS_HAS_STALLGUARD(X) && defined(X_STALL_SENSITIVITY)) - #define X2_SENSORLESS (AXIS_HAS_STALLGUARD(X2) && defined(X2_STALL_SENSITIVITY)) - #define Y_SENSORLESS (AXIS_HAS_STALLGUARD(Y) && defined(Y_STALL_SENSITIVITY)) - #define Y2_SENSORLESS (AXIS_HAS_STALLGUARD(Y2) && defined(Y2_STALL_SENSITIVITY)) - #define Z_SENSORLESS (AXIS_HAS_STALLGUARD(Z) && defined(Z_STALL_SENSITIVITY)) - #define Z2_SENSORLESS (AXIS_HAS_STALLGUARD(Z2) && defined(Z2_STALL_SENSITIVITY)) - #define Z3_SENSORLESS (AXIS_HAS_STALLGUARD(Z3) && defined(Z3_STALL_SENSITIVITY)) - #define Z4_SENSORLESS (AXIS_HAS_STALLGUARD(Z4) && defined(Z4_STALL_SENSITIVITY)) + #if defined(X_STALL_SENSITIVITY) && AXIS_HAS_STALLGUARD(X) + #define X_SENSORLESS 1 + #endif + #if defined(X2_STALL_SENSITIVITY) && AXIS_HAS_STALLGUARD(X2) + #define X2_SENSORLESS 1 + #endif + #if defined(Y_STALL_SENSITIVITY) && AXIS_HAS_STALLGUARD(Y) + #define Y_SENSORLESS 1 + #endif + #if defined(Y2_STALL_SENSITIVITY) && AXIS_HAS_STALLGUARD(Y2) + #define Y2_SENSORLESS 1 + #endif + #if defined(Z_STALL_SENSITIVITY) && AXIS_HAS_STALLGUARD(Z) + #define Z_SENSORLESS 1 + #endif + #if defined(Z2_STALL_SENSITIVITY) && AXIS_HAS_STALLGUARD(Z2) + #define Z2_SENSORLESS 1 + #endif + #if defined(Z3_STALL_SENSITIVITY) && AXIS_HAS_STALLGUARD(Z3) + #define Z3_SENSORLESS 1 + #endif + #if defined(Z4_STALL_SENSITIVITY) && AXIS_HAS_STALLGUARD(Z4) + #define Z4_SENSORLESS 1 + #endif #if ENABLED(SPI_ENDSTOPS) #define X_SPI_SENSORLESS X_SENSORLESS #define Y_SPI_SENSORLESS Y_SENSORLESS @@ -1484,23 +1430,48 @@ #define HAS_HEATER_BED (PIN_EXISTS(HEATER_BED)) // Shorthand for common combinations -#define HAS_HEATED_BED (HAS_TEMP_BED && HAS_HEATER_BED) -#define BED_OR_CHAMBER (HAS_HEATED_BED || HAS_TEMP_CHAMBER) -#define HAS_TEMP_SENSOR (HAS_TEMP_HOTEND || BED_OR_CHAMBER || HAS_TEMP_PROBE) -#define HAS_HEATED_CHAMBER (HAS_TEMP_CHAMBER && PIN_EXISTS(HEATER_CHAMBER)) +#if HAS_TEMP_BED && HAS_HEATER_BED + #define HAS_HEATED_BED 1 +#endif +#if HAS_HEATED_BED || HAS_TEMP_CHAMBER + #define BED_OR_CHAMBER 1 +#endif +#if HAS_TEMP_HOTEND || BED_OR_CHAMBER || HAS_TEMP_PROBE + #define HAS_TEMP_SENSOR 1 +#endif +#if HAS_TEMP_CHAMBER && PIN_EXISTS(HEATER_CHAMBER) + #define HAS_HEATED_CHAMBER 1 +#endif // PID heating #if !HAS_HEATED_BED #undef PIDTEMPBED #endif -#define HAS_PID_HEATING EITHER(PIDTEMP, PIDTEMPBED) -#define HAS_PID_FOR_BOTH BOTH(PIDTEMP, PIDTEMPBED) +#if EITHER(PIDTEMP, PIDTEMPBED) + #define HAS_PID_HEATING 1 +#endif +#if BOTH(PIDTEMP, PIDTEMPBED) + #define HAS_PID_FOR_BOTH 1 +#endif // Thermal protection -#define HAS_THERMALLY_PROTECTED_BED (HAS_HEATED_BED && ENABLED(THERMAL_PROTECTION_BED)) -#define WATCH_HOTENDS (ENABLED(THERMAL_PROTECTION_HOTENDS) && WATCH_TEMP_PERIOD > 0) -#define WATCH_BED (HAS_THERMALLY_PROTECTED_BED && WATCH_BED_TEMP_PERIOD > 0) -#define WATCH_CHAMBER (HAS_HEATED_CHAMBER && ENABLED(THERMAL_PROTECTION_CHAMBER) && WATCH_CHAMBER_TEMP_PERIOD > 0) +#if HAS_HEATED_BED && ENABLED(THERMAL_PROTECTION_BED) + #define HAS_THERMALLY_PROTECTED_BED 1 +#endif +#if ENABLED(THERMAL_PROTECTION_HOTENDS) && WATCH_TEMP_PERIOD > 0 + #define WATCH_HOTENDS 1 +#endif +#if HAS_THERMALLY_PROTECTED_BED && WATCH_BED_TEMP_PERIOD > 0 + #define WATCH_BED 1 +#endif +#if HAS_HEATED_CHAMBER && ENABLED(THERMAL_PROTECTION_CHAMBER) && WATCH_CHAMBER_TEMP_PERIOD > 0 + #define WATCH_CHAMBER 1 +#endif +#if (ENABLED(THERMAL_PROTECTION_HOTENDS) || !EXTRUDERS) \ + && (ENABLED(THERMAL_PROTECTION_BED) || !HAS_HEATED_BED) \ + && (ENABLED(THERMAL_PROTECTION_CHAMBER) || !HAS_HEATED_CHAMBER) + #define THERMALLY_SAFE 1 +#endif // Auto fans #define HAS_AUTO_FAN_0 (HOTENDS > 0 && PIN_EXISTS(E0_AUTO_FAN)) @@ -1522,6 +1493,7 @@ #if !HAS_TEMP_SENSOR #undef AUTO_REPORT_TEMPERATURES #endif +#define HAS_AUTO_REPORTING EITHER(AUTO_REPORT_TEMPERATURES, AUTO_REPORT_SD_STATUS) #if !HAS_AUTO_CHAMBER_FAN || AUTO_CHAMBER_IS_E #undef AUTO_POWER_CHAMBER_FAN @@ -1550,22 +1522,48 @@ #define HAS_FILAMENT_WIDTH_SENSOR (PIN_EXISTS(FILWIDTH)) // User Interface -#define HAS_HOME (PIN_EXISTS(HOME)) -#define HAS_KILL (PIN_EXISTS(KILL)) -#define HAS_SUICIDE (PIN_EXISTS(SUICIDE)) -#define HAS_PHOTOGRAPH (PIN_EXISTS(PHOTOGRAPH)) -#define HAS_BUZZER (PIN_EXISTS(BEEPER) || EITHER(LCD_USE_I2C_BUZZER, PCA9632_BUZZER)) -#define USE_BEEPER (HAS_BUZZER && DISABLED(LCD_USE_I2C_BUZZER, PCA9632_BUZZER)) -#define HAS_CASE_LIGHT (PIN_EXISTS(CASE_LIGHT) && ENABLED(CASE_LIGHT_ENABLE)) +#if PIN_EXISTS(HOME) + #define HAS_HOME 1 +#endif +#if PIN_EXISTS(KILL) + #define HAS_KILL 1 +#endif +#if PIN_EXISTS(SUICIDE) + #define HAS_SUICIDE 1 +#endif +#if PIN_EXISTS(PHOTOGRAPH) + #define HAS_PHOTOGRAPH 1 +#endif +#if PIN_EXISTS(BEEPER) || EITHER(LCD_USE_I2C_BUZZER, PCA9632_BUZZER) + #define HAS_BUZZER 1 +#endif +#if HAS_BUZZER && DISABLED(LCD_USE_I2C_BUZZER, PCA9632_BUZZER) + #define USE_BEEPER 1 +#endif +#if PIN_EXISTS(CASE_LIGHT) && ENABLED(CASE_LIGHT_ENABLE) + #define HAS_CASE_LIGHT 1 +#endif // Digital control -#define HAS_STEPPER_RESET (PIN_EXISTS(STEPPER_RESET)) -#define HAS_DIGIPOTSS (PIN_EXISTS(DIGIPOTSS)) -#define HAS_MOTOR_CURRENT_PWM ANY_PIN(MOTOR_CURRENT_PWM_X, MOTOR_CURRENT_PWM_Y, MOTOR_CURRENT_PWM_XY, MOTOR_CURRENT_PWM_Z, MOTOR_CURRENT_PWM_E) +#if PIN_EXISTS(STEPPER_RESET) + #define HAS_STEPPER_RESET 1 +#endif +#if PIN_EXISTS(DIGIPOTSS) + #define HAS_DIGIPOTSS 1 +#endif +#if ANY_PIN(MOTOR_CURRENT_PWM_X, MOTOR_CURRENT_PWM_Y, MOTOR_CURRENT_PWM_XY, MOTOR_CURRENT_PWM_Z, MOTOR_CURRENT_PWM_E) + #define HAS_MOTOR_CURRENT_PWM 1 +#endif -#define HAS_SOME_Z_MICROSTEPS (HAS_Z_MICROSTEPS || HAS_Z2_MICROSTEPS || HAS_Z3_MICROSTEPS || HAS_Z4_MICROSTEPS) -#define HAS_SOME_E_MICROSTEPS (HAS_E0_MICROSTEPS || HAS_E1_MICROSTEPS || HAS_E2_MICROSTEPS || HAS_E3_MICROSTEPS || HAS_E4_MICROSTEPS || HAS_E5_MICROSTEPS || HAS_E6_MICROSTEPS || HAS_E7_MICROSTEPS) -#define HAS_MICROSTEPS (HAS_X_MICROSTEPS || HAS_X2_MICROSTEPS || HAS_Y_MICROSTEPS || HAS_Y2_MICROSTEPS || HAS_SOME_Z_MICROSTEPS || HAS_SOME_E_MICROSTEPS) +#if HAS_Z_MICROSTEPS || HAS_Z2_MICROSTEPS || HAS_Z3_MICROSTEPS || HAS_Z4_MICROSTEPS + #define HAS_SOME_Z_MICROSTEPS 1 +#endif +#if HAS_E0_MICROSTEPS || HAS_E1_MICROSTEPS || HAS_E2_MICROSTEPS || HAS_E3_MICROSTEPS || HAS_E4_MICROSTEPS || HAS_E5_MICROSTEPS || HAS_E6_MICROSTEPS || HAS_E7_MICROSTEPS + #define HAS_SOME_E_MICROSTEPS 1 +#endif +#if HAS_X_MICROSTEPS || HAS_X2_MICROSTEPS || HAS_Y_MICROSTEPS || HAS_Y2_MICROSTEPS || HAS_SOME_Z_MICROSTEPS || HAS_SOME_E_MICROSTEPS + #define HAS_MICROSTEPS 1 +#endif #if HAS_MICROSTEPS @@ -1618,20 +1616,6 @@ #endif // HAS_MICROSTEPS -#if !HAS_TEMP_SENSOR - #undef AUTO_REPORT_TEMPERATURES -#endif - -#define HAS_AUTO_REPORTING EITHER(AUTO_REPORT_TEMPERATURES, AUTO_REPORT_SD_STATUS) - -/** - * This setting is also used by M109 when trying to calculate - * a ballpark safe margin to prevent wait-forever situation. - */ -#ifndef EXTRUDE_MINTEMP - #define EXTRUDE_MINTEMP 170 -#endif - /** * Heater signal inversion defaults */ @@ -1870,26 +1854,6 @@ #endif #endif // SKEW_CORRECTION -/** - * Set granular options based on the specific type of leveling - */ -#define UBL_SEGMENTED BOTH(AUTO_BED_LEVELING_UBL, DELTA) -#define ABL_PLANAR EITHER(AUTO_BED_LEVELING_LINEAR, AUTO_BED_LEVELING_3POINT) -#define ABL_GRID EITHER(AUTO_BED_LEVELING_LINEAR, AUTO_BED_LEVELING_BILINEAR) -#define HAS_ABL_NOT_UBL (ABL_PLANAR || ABL_GRID) -#define HAS_ABL_OR_UBL (HAS_ABL_NOT_UBL || ENABLED(AUTO_BED_LEVELING_UBL)) -#define HAS_LEVELING (HAS_ABL_OR_UBL || ENABLED(MESH_BED_LEVELING)) -#define HAS_AUTOLEVEL (HAS_ABL_OR_UBL && DISABLED(PROBE_MANUALLY)) -#define HAS_MESH ANY(AUTO_BED_LEVELING_BILINEAR, AUTO_BED_LEVELING_UBL, MESH_BED_LEVELING) -#define PLANNER_LEVELING (HAS_LEVELING && DISABLED(AUTO_BED_LEVELING_UBL)) -#define HAS_PROBING_PROCEDURE (HAS_ABL_OR_UBL || ENABLED(Z_MIN_PROBE_REPEATABILITY_TEST)) -#define HAS_POSITION_MODIFIERS (ENABLED(FWRETRACT) || HAS_LEVELING || ENABLED(SKEW_CORRECTION)) -#define NEEDS_THREE_PROBE_POINTS EITHER(AUTO_BED_LEVELING_UBL, AUTO_BED_LEVELING_3POINT) - -#if ENABLED(AUTO_BED_LEVELING_UBL) - #undef LCD_BED_LEVELING -#endif - /** * Heater, Fan, and Probe interactions */ @@ -2014,8 +1978,8 @@ #undef MESH_MAX_Y #endif -#if (defined(PROBE_PT_1_X) && defined(PROBE_PT_2_X) && defined(PROBE_PT_3_X) && defined(PROBE_PT_1_Y) && defined(PROBE_PT_2_Y) && defined(PROBE_PT_3_Y)) - #define HAS_FIXED_3POINT +#if defined(PROBE_PT_1_X) && defined(PROBE_PT_2_X) && defined(PROBE_PT_3_X) && defined(PROBE_PT_1_Y) && defined(PROBE_PT_2_Y) && defined(PROBE_PT_3_Y) + #define HAS_FIXED_3POINT 1 #endif /** @@ -2053,10 +2017,10 @@ * Z_HOMING_HEIGHT / Z_CLEARANCE_BETWEEN_PROBES */ #ifndef Z_HOMING_HEIGHT - #ifndef Z_CLEARANCE_BETWEEN_PROBES - #define Z_HOMING_HEIGHT 0 - #else + #ifdef Z_CLEARANCE_BETWEEN_PROBES #define Z_HOMING_HEIGHT Z_CLEARANCE_BETWEEN_PROBES + #else + #define Z_HOMING_HEIGHT 0 #endif #endif @@ -2084,15 +2048,16 @@ #endif // Updated G92 behavior shifts the workspace -#define HAS_POSITION_SHIFT DISABLED(NO_WORKSPACE_OFFSETS) -// The home offset also shifts the coordinate space -#define HAS_HOME_OFFSET (DISABLED(NO_WORKSPACE_OFFSETS) && IS_CARTESIAN) -// The SCARA home offset applies only on G28 -#define HAS_SCARA_OFFSET (DISABLED(NO_WORKSPACE_OFFSETS) && IS_SCARA) -// Cumulative offset to workspace to save some calculation -#define HAS_WORKSPACE_OFFSET (HAS_POSITION_SHIFT && HAS_HOME_OFFSET) -// M206 sets the home offset for Cartesian machines -#define HAS_M206_COMMAND (HAS_HOME_OFFSET && !IS_SCARA) +#if DISABLED(NO_WORKSPACE_OFFSETS) + #define HAS_POSITION_SHIFT 1 + #if IS_CARTESIAN + #define HAS_HOME_OFFSET 1 // The home offset also shifts the coordinate space + #define HAS_WORKSPACE_OFFSET 1 // Cumulative offset to workspace to save some calculation + #define HAS_M206_COMMAND 1 // M206 sets the home offset for Cartesian machines + #elif IS_SCARA + #define HAS_SCARA_OFFSET 1 // The SCARA home offset applies only on G28 + #endif +#endif // LCD timeout to status screen default is 15s #ifndef LCD_TIMEOUT_TO_STATUS @@ -2115,34 +2080,7 @@ #endif // Number of VFAT entries used. Each entry has 13 UTF-16 characters -#if ENABLED(SCROLL_LONG_FILENAMES) - #define MAX_VFAT_ENTRIES (5) -#else - #define MAX_VFAT_ENTRIES (2) -#endif - -// Set defaults for unspecified LED user colors -#if ENABLED(LED_CONTROL_MENU) - #ifndef LED_USER_PRESET_RED - #define LED_USER_PRESET_RED 255 - #endif - #ifndef LED_USER_PRESET_GREEN - #define LED_USER_PRESET_GREEN 255 - #endif - #ifndef LED_USER_PRESET_BLUE - #define LED_USER_PRESET_BLUE 255 - #endif - #ifndef LED_USER_PRESET_WHITE - #define LED_USER_PRESET_WHITE 0 - #endif - #ifndef LED_USER_PRESET_BRIGHTNESS - #ifdef NEOPIXEL_BRIGHTNESS - #define LED_USER_PRESET_BRIGHTNESS NEOPIXEL_BRIGHTNESS - #else - #define LED_USER_PRESET_BRIGHTNESS 255 - #endif - #endif -#endif +#define MAX_VFAT_ENTRIES TERN(SCROLL_LONG_FILENAMES, 5, 2) // Nozzle park for Delta #if BOTH(NOZZLE_PARK_FEATURE, DELTA) @@ -2154,9 +2092,8 @@ // on boards where SD card and LCD display share the same SPI bus // because of a bug in the shared SPI implementation. (See #8122) #if defined(TARGET_LPC1768) && ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) && (SCK_PIN == LCD_PINS_D4) - #define SDCARD_SORT_ALPHA // Keeps one directory level in RAM. Changing - // directory levels still glitches the screen, - // but the following LCD update cleans it up. + #define SDCARD_SORT_ALPHA // Keep one directory level in RAM. Changing directory levels + // may still glitch the screen, but LCD updates clean it up. #undef SDSORT_LIMIT #undef SDSORT_USES_RAM #undef SDSORT_USES_STACK @@ -2180,31 +2117,24 @@ #endif // Defined here to catch the above defines -#if ENABLED(SDCARD_SORT_ALPHA) - #define HAS_FOLDER_SORTING (FOLDER_SORTING || ENABLED(SDSORT_GCODE)) +#if ENABLED(SDCARD_SORT_ALPHA) && (FOLDER_SORTING || ENABLED(SDSORT_GCODE)) + #define HAS_FOLDER_SORTING 1 #endif -// If platform requires early initialization of watchdog to properly boot -#define EARLY_WATCHDOG (ENABLED(USE_WATCHDOG) && defined(ARDUINO_ARCH_SAM)) - #if HAS_SPI_LCD // Get LCD character width/height, which may be overridden by pins, configs, etc. #ifndef LCD_WIDTH #if HAS_GRAPHICAL_LCD #define LCD_WIDTH 21 - #elif ENABLED(ULTIPANEL) - #define LCD_WIDTH 20 #else - #define LCD_WIDTH 16 + #define LCD_WIDTH TERN(ULTIPANEL, 20, 16) #endif #endif #ifndef LCD_HEIGHT #if HAS_GRAPHICAL_LCD #define LCD_HEIGHT 5 - #elif ENABLED(ULTIPANEL) - #define LCD_HEIGHT 4 #else - #define LCD_HEIGHT 2 + #define LCD_HEIGHT TERN(ULTIPANEL, 4, 2) #endif #endif #endif @@ -2227,10 +2157,3 @@ #if !NUM_SERIAL #undef BAUD_RATE_GCODE #endif - -#if ENABLED(Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS) - #undef Z_STEPPER_ALIGN_AMP -#endif -#ifndef Z_STEPPER_ALIGN_AMP - #define Z_STEPPER_ALIGN_AMP 1.0 -#endif diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index f340e758ab..454183e548 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -34,6 +34,37 @@ #error "Marlin requires C++11 support (gcc >= 4.7, Arduino IDE >= 1.6.8). Please upgrade your toolchain." #endif +// Make sure macros aren't borked +#define TEST1 +#define TEST2 1 +#define TEST3 0 +#define TEST4 true +#if ENABLED(TEST0) + #error "ENABLED is borked!" +#endif +#if DISABLED(TEST1) + #error "DISABLED is borked!" +#endif +#if !ENABLED(TEST2) + #error "ENABLED is borked!" +#endif +#if ENABLED(TEST3) + #error "ENABLED is borked!" +#endif +#if DISABLED(TEST4) + #error "DISABLED is borked!" +#endif +#if !ANY(TEST1, TEST2, TEST3, TEST4) || ANY(TEST0, TEST3) + #error "ANY is borked!" +#endif +#if DISABLED(TEST0, TEST1, TEST2, TEST4) + #error "DISABLED is borked!" +#endif +#undef TEST1 +#undef TEST2 +#undef TEST3 +#undef TEST4 + /** * We try our best to include sanity checks for all changed configuration * directives because users have a tendency to use outdated config files with @@ -68,7 +99,9 @@ #elif defined(X_HOME_RETRACT_MM) #error "[XYZ]_HOME_RETRACT_MM settings have been renamed [XYZ]_HOME_BUMP_MM." #elif defined(SDCARDDETECTINVERTED) - #error "SDCARDDETECTINVERTED is now SD_DETECT_INVERTED. Please update your configuration." + #error "SDCARDDETECTINVERTED is now SD_DETECT_STATE (HIGH). Please update your configuration." +#elif defined(SD_DETECT_INVERTED) + #error "SD_DETECT_INVERTED is now SD_DETECT_STATE (HIGH). Please update your configuration." #elif defined(BTENABLED) #error "BTENABLED is now BLUETOOTH. Please update your configuration." #elif defined(CUSTOM_MENDEL_NAME) @@ -450,6 +483,8 @@ #error "Z_TRIPLE_ENDSTOPS is now Z_MULTI_ENDSTOPS. Please update Configuration_adv.h." #elif defined(Z_QUAD_ENDSTOPS) #error "Z_QUAD_ENDSTOPS is now Z_MULTI_ENDSTOPS. Please update Configuration_adv.h." +#elif defined(DUGS_UI_MOVE_DIS_OPTION) + #error "DUGS_UI_MOVE_DIS_OPTION is spelled DGUS_UI_MOVE_DIS_OPTION. Please update Configuration_adv.h." #endif /** @@ -1237,7 +1272,7 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS * Require some kind of probe for bed leveling and probe testing */ #if HAS_ABL_NOT_UBL && !PROBE_SELECTED - #error "Auto Bed Leveling requires one of these: PROBE_MANUALLY, FIX_MOUNTED_PROBE, NOZZLE_AS_PROBE, BLTOUCH, SOLENOID_PROBE, Z_PROBE_ALLEN_KEY, Z_PROBE_SLED, or a Z Servo." + #error "Auto Bed Leveling requires one of these: PROBE_MANUALLY, SENSORLESS_PROBING, BLTOUCH, FIX_MOUNTED_PROBE, NOZZLE_AS_PROBE, TOUCH_MI_PROBE, SOLENOID_PROBE, Z_PROBE_ALLEN_KEY, Z_PROBE_SLED, or a Z Servo." #endif #if ENABLED(Z_MIN_PROBE_REPEATABILITY_TEST) @@ -2057,6 +2092,8 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #error "An SPI driven TMC driver on Z2 requires Z2_CS_PIN." #elif INVALID_TMC_SPI(Z3) #error "An SPI driven TMC driver on Z3 requires Z3_CS_PIN." +#elif INVALID_TMC_SPI(Z4) + #error "An SPI driven TMC driver on Z4 requires Z4_CS_PIN." #elif INVALID_TMC_SPI(E0) #error "An SPI driven TMC driver on E0 requires E0_CS_PIN." #elif INVALID_TMC_SPI(E1) @@ -2094,6 +2131,8 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #error "TMC2208 or TMC2209 on Z2 requires Z2_HARDWARE_SERIAL or Z2_SERIAL_(RX|TX)_PIN." #elif INVALID_TMC_UART(Z3) #error "TMC2208 or TMC2209 on Z3 requires Z3_HARDWARE_SERIAL or Z3_SERIAL_(RX|TX)_PIN." +#elif INVALID_TMC_UART(Z4) + #error "TMC2208 or TMC2209 on Z4 requires Z4_HARDWARE_SERIAL or Z4_SERIAL_(RX|TX)_PIN." #elif INVALID_TMC_UART(E0) #error "TMC2208 or TMC2209 on E0 requires E0_HARDWARE_SERIAL or E0_SERIAL_(RX|TX)_PIN." #elif INVALID_TMC_UART(E1) @@ -2131,6 +2170,8 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS INVALID_TMC_ADDRESS(Z2); #elif AXIS_DRIVER_TYPE_Z3(TMC2209) INVALID_TMC_ADDRESS(Z3); +#elif AXIS_DRIVER_TYPE_Z4(TMC2209) + INVALID_TMC_ADDRESS(Z4); #elif AXIS_DRIVER_TYPE_E0(TMC2209) INVALID_TMC_ADDRESS(E0); #elif AXIS_DRIVER_TYPE_E1(TMC2209) @@ -2150,6 +2191,47 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #endif #undef INVALID_TMC_ADDRESS +#define _TMC_MICROSTEP_IS_VALID(MS) (MS == 0 || MS == 2 || MS == 4 || MS == 8 || MS == 16 || MS == 32 || MS == 64 || MS == 128 || MS == 256) +#define TMC_MICROSTEP_IS_VALID(M) (!AXIS_IS_TMC(M) || _TMC_MICROSTEP_IS_VALID(M##_MICROSTEPS)) +#define INVALID_TMC_MS(ST) static_assert(0, "Invalid " STRINGIFY(ST) "_MICROSTEPS. Valid values are 0, 2, 4, 8, 16, 32, 64, 128, and 256.") + +#if !TMC_MICROSTEP_IS_VALID(X) + INVALID_TMC_MS(X); +#elif !TMC_MICROSTEP_IS_VALID(Y) + INVALID_TMC_MS(Y) +#elif !TMC_MICROSTEP_IS_VALID(Z) + INVALID_TMC_MS(Z) +#elif !TMC_MICROSTEP_IS_VALID(X2) + INVALID_TMC_MS(X2); +#elif !TMC_MICROSTEP_IS_VALID(Y2) + INVALID_TMC_MS(Y2) +#elif !TMC_MICROSTEP_IS_VALID(Z2) + INVALID_TMC_MS(Z2) +#elif !TMC_MICROSTEP_IS_VALID(Z3) + INVALID_TMC_MS(Z3) +#elif !TMC_MICROSTEP_IS_VALID(Z4) + INVALID_TMC_MS(Z4) +#elif !TMC_MICROSTEP_IS_VALID(E0) + INVALID_TMC_MS(E0) +#elif !TMC_MICROSTEP_IS_VALID(E1) + INVALID_TMC_MS(E1) +#elif !TMC_MICROSTEP_IS_VALID(E2) + INVALID_TMC_MS(E2) +#elif !TMC_MICROSTEP_IS_VALID(E3) + INVALID_TMC_MS(E3) +#elif !TMC_MICROSTEP_IS_VALID(E4) + INVALID_TMC_MS(E4) +#elif !TMC_MICROSTEP_IS_VALID(E5) + INVALID_TMC_MS(E5) +#elif !TMC_MICROSTEP_IS_VALID(E6) + INVALID_TMC_MS(E6) +#elif !TMC_MICROSTEP_IS_VALID(E7) + INVALID_TMC_MS(E7) +#endif +#undef INVALID_TMC_MS +#undef TMC_MICROSTEP_IS_VALID +#undef _TMC_MICROSTEP_IS_VALID + #if ENABLED(DELTA) && (ENABLED(STEALTHCHOP_XY) != ENABLED(STEALTHCHOP_Z)) #error "STEALTHCHOP_XY and STEALTHCHOP_Z must be the same on DELTA." #endif @@ -2256,17 +2338,15 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #error "STEALTHCHOP requires TMC2130, TMC2160, TMC2208, TMC2209, or TMC5160 stepper drivers." #endif +/** + * TMC SPI Chaining + */ #define IN_CHAIN(A) ((A##_CHAIN_POS > 0) && !HAS_L64XX) -// TMC SPI Chaining -#if IN_CHAIN(X) || IN_CHAIN(Y) || IN_CHAIN(Z) || IN_CHAIN(X2) || IN_CHAIN(Y2) || IN_CHAIN(Z2) || IN_CHAIN(Z3) || IN_CHAIN(E0) || IN_CHAIN(E1) || IN_CHAIN(E2) || IN_CHAIN(E3) || IN_CHAIN(E4) || IN_CHAIN(E5) - #if (IN_CHAIN(X) && !PIN_EXISTS(X_CS) ) || (IN_CHAIN(Y) && !PIN_EXISTS(Y_CS) ) \ - || (IN_CHAIN(Z) && !PIN_EXISTS(Z_CS) ) || (IN_CHAIN(X2) && !PIN_EXISTS(X2_CS)) \ - || (IN_CHAIN(Y2) && !PIN_EXISTS(Y2_CS)) || (IN_CHAIN(Z2) && !PIN_EXISTS(Z2_CS)) \ - || (IN_CHAIN(Z3) && !PIN_EXISTS(Z3_CS)) || (IN_CHAIN(E0) && !PIN_EXISTS(E0_CS)) \ - || (IN_CHAIN(E1) && !PIN_EXISTS(E1_CS)) || (IN_CHAIN(E2) && !PIN_EXISTS(E2_CS)) \ - || (IN_CHAIN(E3) && !PIN_EXISTS(E3_CS)) || (IN_CHAIN(E4) && !PIN_EXISTS(E4_CS)) \ - || (IN_CHAIN(E5) && !PIN_EXISTS(E5_CS)) || (IN_CHAIN(E6) && !PIN_EXISTS(E6_CS)) \ - || (IN_CHAIN(E7) && !PIN_EXISTS(E7_CS)) +#if IN_CHAIN(X ) || IN_CHAIN(Y ) || IN_CHAIN(Z ) || IN_CHAIN(X2) || IN_CHAIN(Y2) || IN_CHAIN(Z2) || IN_CHAIN(Z3) || IN_CHAIN(Z4) \ + || IN_CHAIN(E0) || IN_CHAIN(E1) || IN_CHAIN(E2) || IN_CHAIN(E3) || IN_CHAIN(E4) || IN_CHAIN(E5) || IN_CHAIN(E6) || IN_CHAIN(E7) + #define BAD_CHAIN(A) (IN_CHAIN(A) && !PIN_EXISTS(A##_CS)) + #if BAD_CHAIN(X ) || BAD_CHAIN(Y ) || BAD_CHAIN(Z ) || BAD_CHAIN(X2) || BAD_CHAIN(Y2) || BAD_CHAIN(Z2) || BAD_CHAIN(Z3) || BAD_CHAIN(Z4) \ + || BAD_CHAIN(E0) || BAD_CHAIN(E1) || BAD_CHAIN(E2) || BAD_CHAIN(E3) || BAD_CHAIN(E4) || BAD_CHAIN(E5) || BAD_CHAIN(E6) || BAD_CHAIN(E7) #error "All chained TMC drivers need a CS pin." #else #if IN_CHAIN(X) @@ -2300,18 +2380,15 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #elif IN_CHAIN(E7) #define CS_COMPARE E7_CS_PIN #endif - #if (IN_CHAIN(X) && X_CS_PIN != CS_COMPARE) || (IN_CHAIN(Y) && Y_CS_PIN != CS_COMPARE) \ - || (IN_CHAIN(Z) && Z_CS_PIN != CS_COMPARE) || (IN_CHAIN(X2) && X2_CS_PIN != CS_COMPARE) \ - || (IN_CHAIN(Y2) && Y2_CS_PIN != CS_COMPARE) || (IN_CHAIN(Z2) && Z2_CS_PIN != CS_COMPARE) \ - || (IN_CHAIN(Z3) && Z3_CS_PIN != CS_COMPARE) || (IN_CHAIN(E0) && E0_CS_PIN != CS_COMPARE) \ - || (IN_CHAIN(E1) && E1_CS_PIN != CS_COMPARE) || (IN_CHAIN(E2) && E2_CS_PIN != CS_COMPARE) \ - || (IN_CHAIN(E3) && E3_CS_PIN != CS_COMPARE) || (IN_CHAIN(E4) && E4_CS_PIN != CS_COMPARE) \ - || (IN_CHAIN(E5) && E5_CS_PIN != CS_COMPARE) || (IN_CHAIN(E6) && E6_CS_PIN != CS_COMPARE) \ - || (IN_CHAIN(E7) && E7_CS_PIN != CS_COMPARE) + #define BAD_CS_PIN(A) (IN_CHAIN(A) && A##_CS_PIN != CS_COMPARE) + #if BAD_CS_PIN(X ) || BAD_CS_PIN(Y ) || BAD_CS_PIN(Z ) || BAD_CS_PIN(X2) || BAD_CS_PIN(Y2) || BAD_CS_PIN(Z2) || BAD_CS_PIN(Z3) || BAD_CS_PIN(Z4) \ + || BAD_CS_PIN(E0) || BAD_CS_PIN(E1) || BAD_CS_PIN(E2) || BAD_CS_PIN(E3) || BAD_CS_PIN(E4) || BAD_CS_PIN(E5) || BAD_CS_PIN(E6) || BAD_CS_PIN(E7) #error "All chained TMC drivers must use the same CS pin." #endif + #undef BAD_CS_PIN + #undef CS_COMPARE #endif - #undef CS_COMPARE + #undef BAD_CHAIN #endif #undef IN_CHAIN @@ -2432,8 +2509,8 @@ static_assert( _ARR_TEST(3,0) && _ARR_TEST(3,1) && _ARR_TEST(3,2) #error "Z_STEPPER_AUTO_ALIGN requires NUM_Z_STEPPER_DRIVERS greater than 1." #elif !HAS_BED_PROBE #error "Z_STEPPER_AUTO_ALIGN requires a Z-bed probe." - #elif ENABLED(Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS) && NUM_Z_STEPPER_DRIVERS != 3 - #error "Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS requires NUM_Z_STEPPER_DRIVERS to be 3." + #elif ENABLED(Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS) && NUM_Z_STEPPER_DRIVERS < 3 + #error "Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS requires NUM_Z_STEPPER_DRIVERS to be 3 or 4." #endif #endif @@ -2732,3 +2809,8 @@ static_assert( _ARR_TEST(3,0) && _ARR_TEST(3,1) && _ARR_TEST(3,2) #if HAS_TMC_SPI && ALL(MONITOR_DRIVER_STATUS, SDSUPPORT, USES_SHARED_SPI) #error "MONITOR_DRIVER_STATUS and SDSUPPORT cannot be used together on boards with shared SPI." #endif + +// G60/G61 Position Save +#if SAVED_POSITIONS > 256 + #error "SAVED_POSITIONS must be an integer from 0 to 256." +#endif diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index d2415b94a9..b549ceb7f1 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2020-02-27" + #define STRING_DISTRIBUTION_DATE "2020-03-14" #endif /** @@ -52,7 +52,7 @@ * to alert users to major changes. */ -#define MARLIN_HEX_VERSION 020004 +#define MARLIN_HEX_VERSION 020005 #ifndef REQUIRED_CONFIGURATION_H_VERSION #define REQUIRED_CONFIGURATION_H_VERSION MARLIN_HEX_VERSION #endif diff --git a/Marlin/src/lcd/HD44780/ultralcd_HD44780.cpp b/Marlin/src/lcd/HD44780/ultralcd_HD44780.cpp index 7cee7db4b4..ee025f6585 100644 --- a/Marlin/src/lcd/HD44780/ultralcd_HD44780.cpp +++ b/Marlin/src/lcd/HD44780/ultralcd_HD44780.cpp @@ -102,7 +102,7 @@ static void createChar_P(const char c, const byte * const ptr) { byte temp[8]; - for (uint8_t i = 0; i < 8; i++) + LOOP_L_N(i, 8) temp[i] = pgm_read_byte(&ptr[i]); lcd.createChar(c, temp); } @@ -414,7 +414,7 @@ void MarlinUI::clear_lcd() { lcd.clear(); } else { PGM_P p = text; int dly = time / _MAX(slen, 1); - for (uint8_t i = 0; i <= slen; i++) { + LOOP_LE_N(i, slen) { // Print the text at the correct place lcd_put_u8str_max_P(col, line, p, len); @@ -530,7 +530,7 @@ FORCE_INLINE void _draw_heater_status(const heater_ind_t heater, const char pref if (prefix >= 0) lcd_put_wchar(prefix); - lcd_put_u8str(i16tostr3(t1 + 0.5)); + lcd_put_u8str(i16tostr3rj(t1 + 0.5)); lcd_put_wchar('/'); #if !HEATER_IDLE_HANDLER @@ -582,7 +582,7 @@ FORCE_INLINE void _draw_bed_status(const bool blink) { #endif )); if (progress) - lcd_put_u8str(ui8tostr3(progress)); + lcd_put_u8str(ui8tostr3rj(progress)); else lcd_put_u8str_P(PSTR("---")); lcd_put_wchar('%'); @@ -631,7 +631,7 @@ void MarlinUI::draw_status_message(const bool blink) { lcd_put_u8str_P(PSTR("Dia ")); lcd_put_u8str(ftostr12ns(filwidth.measured_mm)); lcd_put_u8str_P(PSTR(" V")); - lcd_put_u8str(i16tostr3(planner.volumetric_percent(parser.volumetric_enabled))); + lcd_put_u8str(i16tostr3rj(planner.volumetric_percent(parser.volumetric_enabled))); lcd_put_wchar('%'); return; } @@ -829,7 +829,7 @@ void MarlinUI::draw_status_screen() { && !printingIsActive() #endif ) { - xy_pos_t lpos = current_position; toLogical(lpos); + const xy_pos_t lpos = current_position.asLogical(); _draw_axis_value(X_AXIS, ftostr4sign(lpos.x), blink); lcd_put_wchar(' '); _draw_axis_value(Y_AXIS, ftostr4sign(lpos.y), blink); @@ -863,7 +863,7 @@ void MarlinUI::draw_status_screen() { #if LCD_HEIGHT > 3 lcd_put_wchar(0, 2, LCD_STR_FEEDRATE[0]); - lcd_put_u8str(i16tostr3(feedrate_percentage)); + lcd_put_u8str(i16tostr3rj(feedrate_percentage)); lcd_put_wchar('%'); char buffer[14]; @@ -902,7 +902,7 @@ void MarlinUI::draw_status_screen() { #endif } lcd_put_wchar(c); - lcd_put_u8str(i16tostr3(per)); + lcd_put_u8str(i16tostr3rj(per)); lcd_put_wchar('%'); #endif #endif @@ -941,7 +941,7 @@ void MarlinUI::draw_status_screen() { #endif lcd_put_wchar(LCD_WIDTH - 9, 1, LCD_STR_FEEDRATE[0]); - lcd_put_u8str(i16tostr3(feedrate_percentage)); + lcd_put_u8str(i16tostr3rj(feedrate_percentage)); lcd_put_wchar('%'); // ========== Line 3 ========== @@ -1212,10 +1212,10 @@ void MarlinUI::draw_status_screen() { #define _LCD_W_POS 12 #define _PLOT_X 1 #define _MAP_X 3 - #define _LABEL(C,X,Y) lcd_put_u8str(X, Y, C) - #define _XLABEL(X,Y) _LABEL("X:",X,Y) - #define _YLABEL(X,Y) _LABEL("Y:",X,Y) - #define _ZLABEL(X,Y) _LABEL("Z:",X,Y) + #define _LABEL(C,X,Y) lcd_put_u8str_P(X, Y, C) + #define _XLABEL(X,Y) _LABEL(X_LBL,X,Y) + #define _YLABEL(X,Y) _LABEL(Y_LBL,X,Y) + #define _ZLABEL(X,Y) _LABEL(Z_LBL,X,Y) #else #define _LCD_W_POS 8 #define _PLOT_X 0 @@ -1415,9 +1415,9 @@ void MarlinUI::draw_status_screen() { * Print plot position */ lcd_put_wchar(_LCD_W_POS, 0, '('); - lcd_put_u8str(ui8tostr3(x_plot)); + lcd_put_u8str(ui8tostr3rj(x_plot)); lcd_put_wchar(','); - lcd_put_u8str(ui8tostr3(y_plot)); + lcd_put_u8str(ui8tostr3rj(y_plot)); lcd_put_wchar(')'); #if LCD_HEIGHT <= 3 // 16x2 or 20x2 display diff --git a/Marlin/src/lcd/dogm/dogm_Statusscreen.h b/Marlin/src/lcd/dogm/dogm_Statusscreen.h index 3656b02e08..3384f5798a 100644 --- a/Marlin/src/lcd/dogm/dogm_Statusscreen.h +++ b/Marlin/src/lcd/dogm/dogm_Statusscreen.h @@ -854,7 +854,9 @@ }; #endif -#else // HAS_HEATED_CHAMBER +#endif + +#ifndef STATUS_CHAMBER_WIDTH #define STATUS_CHAMBER_WIDTH 0 #endif diff --git a/Marlin/src/lcd/dogm/status_screen_DOGM.cpp b/Marlin/src/lcd/dogm/status_screen_DOGM.cpp index 1ea1424d30..92f935f04b 100644 --- a/Marlin/src/lcd/dogm/status_screen_DOGM.cpp +++ b/Marlin/src/lcd/dogm/status_screen_DOGM.cpp @@ -107,7 +107,7 @@ #define PROGRESS_BAR_WIDTH (LCD_PIXEL_WIDTH - PROGRESS_BAR_X) FORCE_INLINE void _draw_centered_temp(const int16_t temp, const uint8_t tx, const uint8_t ty) { - const char *str = i16tostr3(temp); + const char *str = i16tostr3rj(temp); const uint8_t len = str[0] != ' ' ? 3 : str[1] != ' ' ? 2 : 1; lcd_put_u8str(tx - len * (INFO_FONT_WIDTH) / 2 + 1, ty, &str[3-len]); lcd_put_wchar(LCD_STR_DEGREE[0]); @@ -406,7 +406,7 @@ void MarlinUI::draw_status_screen() { #if ENABLED(FILAMENT_LCD_DISPLAY) strcpy(wstring, ftostr12ns(filwidth.measured_mm)); - strcpy(mstring, i16tostr3(planner.volumetric_percent(parser.volumetric_enabled))); + strcpy(mstring, i16tostr3rj(planner.volumetric_percent(parser.volumetric_enabled))); #endif // Progress / elapsed / estimation updates and string formatting to avoid float math on each LCD draw @@ -438,7 +438,7 @@ void MarlinUI::draw_status_screen() { #if ENABLED(PRINT_PROGRESS_SHOW_DECIMALS) permyriadtostr4(progress) #else - ui8tostr3(progress / (PROGRESS_SCALE)) + ui8tostr3rj(progress / (PROGRESS_SCALE)) #endif )); } @@ -564,14 +564,14 @@ void MarlinUI::draw_status_screen() { if (PAGE_UNDER(6 + 1 + 12 + 1 + 6 + 1)) { // Extruders #if DO_DRAW_HOTENDS - for (uint8_t e = 0; e < MAX_HOTEND_DRAW; ++e) + LOOP_L_N(e, MAX_HOTEND_DRAW) _draw_hotend_status((heater_ind_t)e, blink); #endif // Laser / Spindle #if DO_DRAW_CUTTER if (cutter.power && PAGE_CONTAINS(STATUS_CUTTER_TEXT_Y - INFO_FONT_ASCENT, STATUS_CUTTER_TEXT_Y - 1)) { - lcd_put_u8str(STATUS_CUTTER_TEXT_X, STATUS_CUTTER_TEXT_Y, i16tostr3(cutter.powerPercent(cutter.power))); + lcd_put_u8str(STATUS_CUTTER_TEXT_X, STATUS_CUTTER_TEXT_Y, i16tostr3rj(cutter.powerPercent(cutter.power))); lcd_put_wchar('%'); } #endif @@ -598,7 +598,7 @@ void MarlinUI::draw_status_screen() { c = '*'; } #endif - lcd_put_u8str(STATUS_FAN_TEXT_X, STATUS_FAN_TEXT_Y, i16tostr3(thermalManager.fanPercent(spd))); + lcd_put_u8str(STATUS_FAN_TEXT_X, STATUS_FAN_TEXT_Y, i16tostr3rj(thermalManager.fanPercent(spd))); lcd_put_wchar(c); } } @@ -652,11 +652,11 @@ void MarlinUI::draw_status_screen() { } } else if (progress_state == 2 && estimation_string[0]) { - lcd_put_u8str(PROGRESS_BAR_X, EXTRAS_BASELINE, "R:"); + lcd_put_u8str_P(PROGRESS_BAR_X, EXTRAS_BASELINE, PSTR("R:")); lcd_put_u8str(estimation_x_pos, EXTRAS_BASELINE, estimation_string); } else if (elapsed_string[0]) { - lcd_put_u8str(PROGRESS_BAR_X, EXTRAS_BASELINE, "E:"); + lcd_put_u8str_P(PROGRESS_BAR_X, EXTRAS_BASELINE, E_LBL); lcd_put_u8str(elapsed_x_pos, EXTRAS_BASELINE, elapsed_string); } @@ -768,7 +768,7 @@ void MarlinUI::draw_status_screen() { lcd_put_wchar(3, EXTRAS_2_BASELINE, LCD_STR_FEEDRATE[0]); set_font(FONT_STATUSMENU); - lcd_put_u8str(12, EXTRAS_2_BASELINE, i16tostr3(feedrate_percentage)); + lcd_put_u8str(12, EXTRAS_2_BASELINE, i16tostr3rj(feedrate_percentage)); lcd_put_wchar('%'); // diff --git a/Marlin/src/lcd/dogm/status_screen_lite_ST7920.cpp b/Marlin/src/lcd/dogm/status_screen_lite_ST7920.cpp index f5931917ae..e623776b31 100644 --- a/Marlin/src/lcd/dogm/status_screen_lite_ST7920.cpp +++ b/Marlin/src/lcd/dogm/status_screen_lite_ST7920.cpp @@ -209,7 +209,7 @@ void ST7920_Lite_Status_Screen::clear_ddram() { /* This fills the entire graphics buffer with zeros */ void ST7920_Lite_Status_Screen::clear_gdram() { - for (uint8_t y = 0; y < BUFFER_HEIGHT; y++) { + LOOP_L_N(y, BUFFER_HEIGHT) { set_gdram_address(0, y); begin_data(); for (uint8_t i = (BUFFER_WIDTH) / 16; i--;) write_word(0); @@ -407,7 +407,7 @@ void ST7920_Lite_Status_Screen::draw_degree_symbol(uint8_t x, uint8_t y, const b const uint8_t x_word = x >> 1, y_top = degree_symbol_y_top, y_bot = y_top + COUNT(degree_symbol); - for (uint8_t i = y_top; i < y_bot; i++) { + LOOP_S_L_N(i, y_top, y_bot) { uint8_t byte = pgm_read_byte(p_bytes++); set_gdram_address(x_word, i + y * 16); begin_data(); @@ -467,10 +467,10 @@ void ST7920_Lite_Status_Screen::draw_progress_bar(const uint8_t value) { const uint8_t char_pcnt = 100 / width; // How many percent does each 16-bit word represent? // Draw the progress bar as a bitmap in CGRAM - for (uint8_t y = top; y <= bottom; y++) { + LOOP_S_LE_N(y, top, bottom) { set_gdram_address(left, y); begin_data(); - for (uint8_t x = 0; x < width; x++) { + LOOP_L_N(x, width) { uint16_t gfx_word = 0x0000; if ((x + 1) * char_pcnt <= value) gfx_word = 0xFFFF; // Draw completely filled bytes diff --git a/Marlin/src/lcd/dogm/u8g_dev_st7920_128x64_HAL.cpp b/Marlin/src/lcd/dogm/u8g_dev_st7920_128x64_HAL.cpp index b6449bd4ae..599ee2a9ef 100644 --- a/Marlin/src/lcd/dogm/u8g_dev_st7920_128x64_HAL.cpp +++ b/Marlin/src/lcd/dogm/u8g_dev_st7920_128x64_HAL.cpp @@ -87,11 +87,11 @@ void clear_graphics_DRAM(u8g_t *u8g, u8g_dev_t *dev) { u8g_SetAddress(u8g, dev, 0); // cmd mode u8g_WriteByte(u8g, dev, 0x08); //display off, cursor+blink off u8g_WriteByte(u8g, dev, 0x3E); //extended mode + GDRAM active - for (uint8_t y = 0; y < (LCD_PIXEL_HEIGHT) / 2; y++) { //clear GDRAM + LOOP_L_N(y, (LCD_PIXEL_HEIGHT) / 2) { //clear GDRAM u8g_WriteByte(u8g, dev, 0x80 | y); //set y u8g_WriteByte(u8g, dev, 0x80); //set x = 0 u8g_SetAddress(u8g, dev, 1); /* data mode */ - for (uint8_t i = 0; i < 2 * (LCD_PIXEL_WIDTH) / 8; i++) //2x width clears both segments + LOOP_L_N(i, 2 * (LCD_PIXEL_WIDTH) / 8) //2x width clears both segments u8g_WriteByte(u8g, dev, 0); u8g_SetAddress(u8g, dev, 0); /* cmd mode */ } diff --git a/Marlin/src/lcd/dogm/u8g_dev_tft_320x240_upscale_from_128x64.cpp b/Marlin/src/lcd/dogm/u8g_dev_tft_320x240_upscale_from_128x64.cpp index fcfebcbe12..206f61c675 100644 --- a/Marlin/src/lcd/dogm/u8g_dev_tft_320x240_upscale_from_128x64.cpp +++ b/Marlin/src/lcd/dogm/u8g_dev_tft_320x240_upscale_from_128x64.cpp @@ -670,7 +670,7 @@ uint8_t u8g_dev_tft_320x240_upscale_from_128x64_fn(u8g_t *u8g, u8g_dev_t *dev, u case U8G_DEV_MSG_PAGE_NEXT: if (++page > (HEIGHT / PAGE_HEIGHT)) return 1; - for (uint8_t y = 0; y < PAGE_HEIGHT; y++) { + LOOP_L_N(y, PAGE_HEIGHT) { uint32_t k = 0; #ifdef LCD_USE_DMA_FSMC buffer = (y & 1) ? bufferB : bufferA; diff --git a/Marlin/src/lcd/dogm/ultralcd_DOGM.cpp b/Marlin/src/lcd/dogm/ultralcd_DOGM.cpp index 8dd24e2737..fc7656f1cd 100644 --- a/Marlin/src/lcd/dogm/ultralcd_DOGM.cpp +++ b/Marlin/src/lcd/dogm/ultralcd_DOGM.cpp @@ -219,9 +219,6 @@ bool MarlinUI::detected() { return true; } // Show the Marlin bootscreen, with the u8g loop and delays void MarlinUI::show_marlin_bootscreen() { - #ifndef BOOTSCREEN_TIMEOUT - #define BOOTSCREEN_TIMEOUT 2500 - #endif constexpr uint8_t pages = two_part ? 2 : 1; for (uint8_t q = pages; q--;) { draw_marlin_bootscreen(q == 0); @@ -327,11 +324,11 @@ void MarlinUI::clear_lcd() { } // Automatically cleared by Picture Loop lcd_put_wchar(LCD_PIXEL_WIDTH - 11 * (MENU_FONT_WIDTH), row_y2, 'E'); lcd_put_wchar((char)('1' + extruder)); lcd_put_wchar(' '); - lcd_put_u8str(i16tostr3(thermalManager.degHotend(extruder))); + lcd_put_u8str(i16tostr3rj(thermalManager.degHotend(extruder))); lcd_put_wchar('/'); if (get_blink() || !thermalManager.hotend_idle[extruder].timed_out) - lcd_put_u8str(i16tostr3(thermalManager.degTargetHotend(extruder))); + lcd_put_u8str(i16tostr3rj(thermalManager.degTargetHotend(extruder))); } #endif // ADVANCED_PAUSE_FEATURE @@ -548,9 +545,9 @@ void MarlinUI::clear_lcd() { } // Automatically cleared by Picture Loop if (PAGE_UNDER(7)) { const xy_pos_t pos = { ubl.mesh_index_to_xpos(x_plot), ubl.mesh_index_to_ypos(y_plot) }, lpos = pos.asLogical(); - lcd_put_u8str(5, 7, "X:"); + lcd_put_u8str_P(5, 7, X_LBL); lcd_put_u8str(ftostr52(lpos.x)); - lcd_put_u8str(74, 7, "Y:"); + lcd_put_u8str_P(74, 7, Y_LBL); lcd_put_u8str(ftostr52(lpos.y)); } @@ -563,7 +560,7 @@ void MarlinUI::clear_lcd() { } // Automatically cleared by Picture Loop lcd_put_wchar(')'); // Show the location value - lcd_put_u8str(74, LCD_PIXEL_HEIGHT, "Z:"); + lcd_put_u8str_P(74, LCD_PIXEL_HEIGHT, Z_LBL); if (!isnan(ubl.z_values[x_plot][y_plot])) lcd_put_u8str(ftostr43sign(ubl.z_values[x_plot][y_plot])); else diff --git a/Marlin/src/lcd/extensible_ui/lib/dgus/DGUSDisplay.cpp b/Marlin/src/lcd/extui/lib/dgus/DGUSDisplay.cpp similarity index 98% rename from Marlin/src/lcd/extensible_ui/lib/dgus/DGUSDisplay.cpp rename to Marlin/src/lcd/extui/lib/dgus/DGUSDisplay.cpp index e62a77ebee..2b4080485f 100644 --- a/Marlin/src/lcd/extensible_ui/lib/dgus/DGUSDisplay.cpp +++ b/Marlin/src/lcd/extui/lib/dgus/DGUSDisplay.cpp @@ -32,7 +32,7 @@ #include "DGUSDisplay.h" #include "DGUSVPVariable.h" -#include "DGUSDisplayDefinition.h" +#include "DGUSDisplayDef.h" #include "../../ui_api.h" @@ -45,7 +45,7 @@ #include "../../../../libs/duration_t.h" #include "../../../../module/printcounter.h" #if ENABLED(POWER_LOSS_RECOVERY) - #include "../../../../feature/power_loss_recovery.h" + #include "../../../../feature/powerloss.h" #endif // Preamble... 2 Bytes, usually 0x5A 0xA5, but configurable @@ -179,6 +179,15 @@ void DGUSScreenVariableHandler::DGUSLCD_SendPercentageToDisplay(DGUS_VP_Variable } } +// Send the current print progress to the display. +void DGUSScreenVariableHandler::DGUSLCD_SendPrintProgressToDisplay(DGUS_VP_Variable &var) { + //DEBUG_ECHOPAIR(" DGUSLCD_SendPrintProgressToDisplay ", var.VP); + uint16_t tmp = ExtUI::getProgress_percent(); + //DEBUG_ECHOLNPAIR(" data ", tmp); + uint16_t data_to_send = swap16(tmp); + dgusdisplay.WriteVariable(var.VP, data_to_send); +} + // Send the current print time to the display. // It is using a hex display for that: It expects BSD coded data in the format xxyyzz void DGUSScreenVariableHandler::DGUSLCD_SendPrintTimeToDisplay(DGUS_VP_Variable &var) { @@ -465,7 +474,7 @@ void DGUSScreenVariableHandler::ScreenConfirmedOK(DGUS_VP_Variable &var, void *v const uint16_t* DGUSLCD_FindScreenVPMapList(uint8_t screen) { const uint16_t *ret; const struct VPMapping *map = VPMap; - while (ret = (uint16_t*) pgm_read_word(&(map->VPList))) { + while (ret = (uint16_t*) pgm_read_ptr(&(map->VPList))) { if (pgm_read_byte(&(map->screen)) == screen) return ret; map++; } @@ -594,7 +603,7 @@ void DGUSScreenVariableHandler::HandleManualExtrude(DGUS_VP_Variable &var, void skipVP = var.VP; } -#if ENABLED(DUGS_UI_MOVE_DIS_OPTION) +#if ENABLED(DGUS_UI_MOVE_DIS_OPTION) void DGUSScreenVariableHandler::HandleManualMoveOption(DGUS_VP_Variable &var, void *val_ptr) { DEBUG_ECHOLNPGM("HandleManualMoveOption"); *(uint16_t*)var.memadr = swap16(*(uint16_t*)val_ptr); @@ -605,7 +614,7 @@ void DGUSScreenVariableHandler::HandleManualMove(DGUS_VP_Variable &var, void *va DEBUG_ECHOLNPGM("HandleManualMove"); int16_t movevalue = swap16(*(uint16_t*)val_ptr); - #if ENABLED(DUGS_UI_MOVE_DIS_OPTION) + #if ENABLED(DGUS_UI_MOVE_DIS_OPTION) const uint16_t choice = *(uint16_t*)var.memadr; movevalue = movevalue > 0 ? choice : -choice; #endif @@ -846,8 +855,8 @@ void DGUSScreenVariableHandler::HandleStepPerMMExtruderChanged(DGUS_VP_Variable void DGUSScreenVariableHandler::HandleProbeOffsetZChanged(DGUS_VP_Variable &var, void *val_ptr) { DEBUG_ECHOLNPGM("HandleProbeOffsetZChanged"); - uint16_t value = swap16(*(uint16_t*)val_ptr)/100; - ExtUI::setZOffset_mm(value); + const float offset = float(swap16(*(uint16_t*)val_ptr)) / 100.0f; + ExtUI::setZOffset_mm(offset); ScreenHandler.skipVP = var.VP; // don't overwrite value the next update time as the display might autoincrement in parallel return; } @@ -858,7 +867,7 @@ void DGUSScreenVariableHandler::HandleProbeOffsetZChanged(DGUS_VP_Variable &var, int16_t flag = swap16(*(uint16_t*)val_ptr); int16_t steps = flag ? -20 : 20; - ExtUI::smartAdjustAxis_steps(steps,ExtUI::axis_t::Z,true); + ExtUI::smartAdjustAxis_steps(steps, ExtUI::axis_t::Z, true); ScreenHandler.ForceCompleteUpdate(); return; } @@ -1307,11 +1316,8 @@ void DGUSDisplay::ProcessRx() { //DEBUG_ECHOPAIR(" vp=", vp, " dlen=", dlen); DGUS_VP_Variable ramcopy; if (populate_VPVar(vp, &ramcopy)) { - if (!(dlen == ramcopy.size || (dlen == 2 && ramcopy.size == 1))) - DEBUG_ECHOLNPGM("SIZE MISMATCH"); - else if (ramcopy.set_by_display_handler) { + if (ramcopy.set_by_display_handler) ramcopy.set_by_display_handler(ramcopy, &tmp[3]); - } else DEBUG_ECHOLNPGM(" VPVar found, no handler."); } diff --git a/Marlin/src/lcd/extensible_ui/lib/dgus/DGUSDisplay.h b/Marlin/src/lcd/extui/lib/dgus/DGUSDisplay.h similarity index 97% rename from Marlin/src/lcd/extensible_ui/lib/dgus/DGUSDisplay.h rename to Marlin/src/lcd/extui/lib/dgus/DGUSDisplay.h index 165aab7ed6..00e626adc9 100644 --- a/Marlin/src/lcd/extensible_ui/lib/dgus/DGUSDisplay.h +++ b/Marlin/src/lcd/extui/lib/dgus/DGUSDisplay.h @@ -26,6 +26,9 @@ #include "../../../../inc/MarlinConfigPre.h" #include "../../../../MarlinCore.h" +#if HAS_BED_PROBE + #include "../../../../module/probe.h" +#endif #include "DGUSVPVariable.h" enum DGUSLCD_Screens : uint8_t; @@ -116,7 +119,7 @@ public: static void HandleTemperatureChanged(DGUS_VP_Variable &var, void *val_ptr); // Hook for "Change Flowrate" static void HandleFlowRateChanged(DGUS_VP_Variable &var, void *val_ptr); - #if ENABLED(DUGS_UI_MOVE_DIS_OPTION) + #if ENABLED(DGUS_UI_MOVE_DIS_OPTION) // Hook for manual move option static void HandleManualMoveOption(DGUS_VP_Variable &var, void *val_ptr); #endif @@ -140,8 +143,10 @@ public: // Hook for PID autotune static void HandlePIDAutotune(DGUS_VP_Variable &var, void *val_ptr); #endif - // Hook for "Change probe offset z" - static void HandleProbeOffsetZChanged(DGUS_VP_Variable &var, void *val_ptr); + #if HAS_BED_PROBE + // Hook for "Change probe offset z" + static void HandleProbeOffsetZChanged(DGUS_VP_Variable &var, void *val_ptr); + #endif #if ENABLED(BABYSTEPPING) // Hook for live z adjust action static void HandleLiveAdjustZ(DGUS_VP_Variable &var, void *val_ptr); @@ -210,6 +215,7 @@ public: static void DGUSLCD_SendStringToDisplayPGM(DGUS_VP_Variable &var); static void DGUSLCD_SendTemperaturePID(DGUS_VP_Variable &var); static void DGUSLCD_SendPercentageToDisplay(DGUS_VP_Variable &var); + static void DGUSLCD_SendPrintProgressToDisplay(DGUS_VP_Variable &var); static void DGUSLCD_SendPrintTimeToDisplay(DGUS_VP_Variable &var); #if ENABLED(PRINTCOUNTER) static void DGUSLCD_SendPrintAccTimeToDisplay(DGUS_VP_Variable &var); @@ -231,7 +237,7 @@ public: if (!var.memadr) return; union { unsigned char tmp[sizeof(T)]; T t; } x; unsigned char *ptr = (unsigned char*)val_ptr; - for (uint8_t i = 0; i < sizeof(T); i++) x.tmp[i] = ptr[sizeof(T) - i - 1]; + LOOP_L_N(i, sizeof(T)) x.tmp[i] = ptr[sizeof(T) - i - 1]; *(T*)var.memadr = x.t; } diff --git a/Marlin/src/lcd/extensible_ui/lib/dgus/DGUSDisplayDefinition.h b/Marlin/src/lcd/extui/lib/dgus/DGUSDisplayDef.h similarity index 92% rename from Marlin/src/lcd/extensible_ui/lib/dgus/DGUSDisplayDefinition.h rename to Marlin/src/lcd/extui/lib/dgus/DGUSDisplayDef.h index eebf18e377..7af1ffefa7 100644 --- a/Marlin/src/lcd/extensible_ui/lib/dgus/DGUSDisplayDefinition.h +++ b/Marlin/src/lcd/extui/lib/dgus/DGUSDisplayDef.h @@ -42,9 +42,9 @@ extern const struct VPMapping VPMap[]; extern const struct DGUS_VP_Variable ListOfVP[]; #if ENABLED(DGUS_LCD_UI_ORIGIN) - #include "DGUSDisplayDefinitionOrigin.h" + #include "origin/DGUSDisplayDef.h" #elif ENABLED(DGUS_LCD_UI_FYSETC) - #include "DGUSDisplayDefinitionFYSETC.h" + #include "fysetc/DGUSDisplayDef.h" #elif ENABLED(DGUS_LCD_UI_HIPRECY) - #include "DGUSDisplayDefinitionHIPRECY.h" + #include "hiprecy/DGUSDisplayDef.h" #endif diff --git a/Marlin/src/lcd/extensible_ui/lib/dgus/DGUSVPVariable.h b/Marlin/src/lcd/extui/lib/dgus/DGUSVPVariable.h similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/dgus/DGUSVPVariable.h rename to Marlin/src/lcd/extui/lib/dgus/DGUSVPVariable.h diff --git a/Marlin/src/lcd/extensible_ui/lib/dgus/DGUSDisplayDefinitionFYSETC.cpp b/Marlin/src/lcd/extui/lib/dgus/fysetc/DGUSDisplayDef.cpp similarity index 96% rename from Marlin/src/lcd/extensible_ui/lib/dgus/DGUSDisplayDefinitionFYSETC.cpp rename to Marlin/src/lcd/extui/lib/dgus/fysetc/DGUSDisplayDef.cpp index 6e26e63434..49d89948ba 100644 --- a/Marlin/src/lcd/extensible_ui/lib/dgus/DGUSDisplayDefinitionFYSETC.cpp +++ b/Marlin/src/lcd/extui/lib/dgus/fysetc/DGUSDisplayDef.cpp @@ -22,21 +22,21 @@ /* DGUS VPs changed by George Fu in 2019 for Marlin */ -#include "../../../../inc/MarlinConfigPre.h" +#include "../../../../../inc/MarlinConfigPre.h" #if ENABLED(DGUS_LCD_UI_FYSETC) -#include "DGUSDisplayDefinition.h" -#include "DGUSDisplay.h" +#include "../DGUSDisplayDef.h" +#include "../DGUSDisplay.h" -#include "../../../../module/temperature.h" -#include "../../../../module/motion.h" -#include "../../../../module/planner.h" +#include "../../../../../module/temperature.h" +#include "../../../../../module/motion.h" +#include "../../../../../module/planner.h" -#include "../../ui_api.h" -#include "../../../ultralcd.h" +#include "../../../ui_api.h" +#include "../../../../ultralcd.h" -#if ENABLED(DUGS_UI_MOVE_DIS_OPTION) +#if ENABLED(DGUS_UI_MOVE_DIS_OPTION) uint16_t distanceToMove = 0.1; #endif @@ -213,6 +213,7 @@ const uint16_t VPList_SDPrintTune[] PROGMEM = { VP_T_Bed_Is, VP_T_Bed_Set, #endif VP_Feedrate_Percentage, + VP_SD_Print_ProbeOffsetZ, 0x0000 }; @@ -279,6 +280,13 @@ const uint16_t VPList_FLCPrinting[] PROGMEM = { 0x0000 }; +const uint16_t VPList_Z_Offset[] PROGMEM = { + #if HOTENDS >= 1 + VP_SD_Print_ProbeOffsetZ, + #endif + 0x0000 +}; + const struct VPMapping VPMap[] PROGMEM = { { DGUSLCD_SCREEN_BOOT, VPList_Boot }, { DGUSLCD_SCREEN_MAIN, VPList_Main }, @@ -297,6 +305,7 @@ const struct VPMapping VPMap[] PROGMEM = { { DGUSLCD_SCREEN_WAITING, VPList_PIDTuningWaiting }, { DGUSLCD_SCREEN_FLC_PREHEAT, VPList_FLCPreheat }, { DGUSLCD_SCREEN_FLC_PRINTING, VPList_FLCPrinting }, + { DGUSLCD_SCREEN_Z_OFFSET, VPList_Z_Offset }, { DGUSLCD_SCREEN_STEPPERMM, VPList_StepPerMM }, { DGUSLCD_SCREEN_PID_E, VPList_PIDE0 }, { DGUSLCD_SCREEN_PID_BED, VPList_PIDBED }, @@ -322,10 +331,10 @@ const struct DGUS_VP_Variable ListOfVP[] PROGMEM = { VPHELPER(VP_CONFIRMED, nullptr, DGUSScreenVariableHandler::ScreenConfirmedOK, nullptr), VPHELPER(VP_TEMP_ALL_OFF, nullptr, &DGUSScreenVariableHandler::HandleAllHeatersOff, nullptr), - #if ENABLED(DUGS_UI_MOVE_DIS_OPTION) + #if ENABLED(DGUS_UI_MOVE_DIS_OPTION) VPHELPER(VP_MOVE_OPTION, &distanceToMove, &DGUSScreenVariableHandler::HandleManualMoveOption, nullptr), #endif - #if ENABLED(DUGS_UI_MOVE_DIS_OPTION) + #if ENABLED(DGUS_UI_MOVE_DIS_OPTION) VPHELPER(VP_MOVE_X, &distanceToMove, &DGUSScreenVariableHandler::HandleManualMove, nullptr), VPHELPER(VP_MOVE_Y, &distanceToMove, &DGUSScreenVariableHandler::HandleManualMove, nullptr), VPHELPER(VP_MOVE_Z, &distanceToMove, &DGUSScreenVariableHandler::HandleManualMove, nullptr), @@ -418,9 +427,7 @@ const struct DGUS_VP_Variable ListOfVP[] PROGMEM = { VPHELPER(VP_ZPos, ¤t_position.z, nullptr, DGUSScreenVariableHandler::DGUSLCD_SendFloatAsLongValueToDisplay<2>), // Print Progress - #if ENABLED(LCD_SET_PROGRESS_MANUALLY) - VPHELPER(VP_PrintProgress_Percentage, &ui.progress_override, nullptr, DGUSScreenVariableHandler::DGUSLCD_SendWordValueToDisplay), - #endif + VPHELPER(VP_PrintProgress_Percentage, nullptr, nullptr, DGUSScreenVariableHandler::DGUSLCD_SendPrintProgressToDisplay ), // Print Time VPHELPER_STR(VP_PrintTime, nullptr, VP_PrintTime_LEN, nullptr, DGUSScreenVariableHandler::DGUSLCD_SendPrintTimeToDisplay), diff --git a/Marlin/src/lcd/extensible_ui/lib/dgus/DGUSDisplayDefinitionFYSETC.h b/Marlin/src/lcd/extui/lib/dgus/fysetc/DGUSDisplayDef.h similarity index 98% rename from Marlin/src/lcd/extensible_ui/lib/dgus/DGUSDisplayDefinitionFYSETC.h rename to Marlin/src/lcd/extui/lib/dgus/fysetc/DGUSDisplayDef.h index 6eb2369fa1..309a23b9b5 100644 --- a/Marlin/src/lcd/extensible_ui/lib/dgus/DGUSDisplayDefinitionFYSETC.h +++ b/Marlin/src/lcd/extui/lib/dgus/fysetc/DGUSDisplayDef.h @@ -43,7 +43,8 @@ enum DGUSLCD_Screens : uint8_t { DGUSLCD_SCREEN_STEPPERMM = 212, DGUSLCD_SCREEN_PID_E = 214, DGUSLCD_SCREEN_PID_BED = 218, - DGUSLCD_SCREEN_INFOS = 30, + DGUSLCD_SCREEN_Z_OFFSET = 222, + DGUSLCD_SCREEN_INFOS = 36, DGUSLCD_SCREEN_CONFIRM = 240, DGUSLCD_SCREEN_KILL = 250, ///< Kill Screen. Must always be 250 (to be able to display "Error wrong LCD Version") DGUSLCD_SCREEN_WAITING = 251, @@ -121,8 +122,8 @@ constexpr uint16_t VP_POWER_LOSS_RECOVERY = 0x2180; // Fan Control Buttons , switch between "off" and "on" constexpr uint16_t VP_FAN0_CONTROL = 0x2200; constexpr uint16_t VP_FAN1_CONTROL = 0x2202; -//constexpr uint16_t VP_FAN2_CONTROL = 0x2204; -//constexpr uint16_t VP_FAN3_CONTROL = 0x2206; +constexpr uint16_t VP_FAN2_CONTROL = 0x2204; +constexpr uint16_t VP_FAN3_CONTROL = 0x2206; // Heater Control Buttons , triged between "cool down" and "heat PLA" state constexpr uint16_t VP_E0_CONTROL = 0x2210; @@ -240,8 +241,8 @@ constexpr uint16_t VP_SD_Print_Filename = 0x32C0; // Fan status constexpr uint16_t VP_FAN0_STATUS = 0x3300; constexpr uint16_t VP_FAN1_STATUS = 0x3302; -//constexpr uint16_t VP_FAN2_STATUS = 0x3304; -//constexpr uint16_t VP_FAN3_STATUS = 0x3306; +constexpr uint16_t VP_FAN2_STATUS = 0x3304; +constexpr uint16_t VP_FAN3_STATUS = 0x3306; // Heater status constexpr uint16_t VP_E0_STATUS = 0x3310; diff --git a/Marlin/src/lcd/extensible_ui/lib/dgus/DGUSDisplayDefinitionHIPRECY.cpp b/Marlin/src/lcd/extui/lib/dgus/hiprecy/DGUSDisplayDef.cpp similarity index 97% rename from Marlin/src/lcd/extensible_ui/lib/dgus/DGUSDisplayDefinitionHIPRECY.cpp rename to Marlin/src/lcd/extui/lib/dgus/hiprecy/DGUSDisplayDef.cpp index 6ec6cddae4..3ccde11411 100644 --- a/Marlin/src/lcd/extensible_ui/lib/dgus/DGUSDisplayDefinitionHIPRECY.cpp +++ b/Marlin/src/lcd/extui/lib/dgus/hiprecy/DGUSDisplayDef.cpp @@ -22,21 +22,21 @@ /* DGUS VPs changed by George Fu in 2019 for Marlin */ -#include "../../../../inc/MarlinConfigPre.h" +#include "../../../../../inc/MarlinConfigPre.h" #if ENABLED(DGUS_LCD_UI_HIPRECY) -#include "DGUSDisplayDefinition.h" -#include "DGUSDisplay.h" +#include "../DGUSDisplayDef.h" +#include "../DGUSDisplay.h" -#include "../../../../module/temperature.h" -#include "../../../../module/motion.h" -#include "../../../../module/planner.h" +#include "../../../../../module/temperature.h" +#include "../../../../../module/motion.h" +#include "../../../../../module/planner.h" -#include "../../ui_api.h" -#include "../../../ultralcd.h" +#include "../../../ui_api.h" +#include "../../../../ultralcd.h" -#if ENABLED(DUGS_UI_MOVE_DIS_OPTION) +#if ENABLED(DGUS_UI_MOVE_DIS_OPTION) uint16_t distanceToMove = 0.1; #endif @@ -327,10 +327,10 @@ const struct DGUS_VP_Variable ListOfVP[] PROGMEM = { VPHELPER(VP_TEMP_ALL_OFF, nullptr, &DGUSScreenVariableHandler::HandleAllHeatersOff, nullptr), - #if ENABLED(DUGS_UI_MOVE_DIS_OPTION) + #if ENABLED(DGUS_UI_MOVE_DIS_OPTION) VPHELPER(VP_MOVE_OPTION, &distanceToMove, &DGUSScreenVariableHandler::HandleManualMoveOption, nullptr), #endif - #if ENABLED(DUGS_UI_MOVE_DIS_OPTION) + #if ENABLED(DGUS_UI_MOVE_DIS_OPTION) VPHELPER(VP_MOVE_X, &distanceToMove, &DGUSScreenVariableHandler::HandleManualMove, nullptr), VPHELPER(VP_MOVE_Y, &distanceToMove, &DGUSScreenVariableHandler::HandleManualMove, nullptr), VPHELPER(VP_MOVE_Z, &distanceToMove, &DGUSScreenVariableHandler::HandleManualMove, nullptr), @@ -418,9 +418,7 @@ const struct DGUS_VP_Variable ListOfVP[] PROGMEM = { VPHELPER(VP_ZPos, ¤t_position.z, nullptr, DGUSScreenVariableHandler::DGUSLCD_SendFloatAsLongValueToDisplay<2>), // Print Progress - #if ENABLED(LCD_SET_PROGRESS_MANUALLY) - VPHELPER(VP_PrintProgress_Percentage, &ui.progress_override, nullptr, DGUSScreenVariableHandler::DGUSLCD_SendWordValueToDisplay ), - #endif + VPHELPER(VP_PrintProgress_Percentage, nullptr, nullptr, DGUSScreenVariableHandler::DGUSLCD_SendPrintProgressToDisplay ), // Print Time VPHELPER_STR(VP_PrintTime, nullptr, VP_PrintTime_LEN, nullptr, DGUSScreenVariableHandler::DGUSLCD_SendPrintTimeToDisplay ), diff --git a/Marlin/src/lcd/extensible_ui/lib/dgus/DGUSDisplayDefinitionHIPRECY.h b/Marlin/src/lcd/extui/lib/dgus/hiprecy/DGUSDisplayDef.h similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/dgus/DGUSDisplayDefinitionHIPRECY.h rename to Marlin/src/lcd/extui/lib/dgus/hiprecy/DGUSDisplayDef.h diff --git a/Marlin/src/lcd/extensible_ui/lib/dgus/DGUSDisplayDefinitionOrigin.cpp b/Marlin/src/lcd/extui/lib/dgus/origin/DGUSDisplayDef.cpp similarity index 96% rename from Marlin/src/lcd/extensible_ui/lib/dgus/DGUSDisplayDefinitionOrigin.cpp rename to Marlin/src/lcd/extui/lib/dgus/origin/DGUSDisplayDef.cpp index 51f292421a..37b7335e67 100644 --- a/Marlin/src/lcd/extensible_ui/lib/dgus/DGUSDisplayDefinitionOrigin.cpp +++ b/Marlin/src/lcd/extui/lib/dgus/origin/DGUSDisplayDef.cpp @@ -22,20 +22,20 @@ /* DGUS implementation written by coldtobi in 2019 for Marlin */ -#include "../../../../inc/MarlinConfigPre.h" +#include "../../../../../inc/MarlinConfigPre.h" #if ENABLED(DGUS_LCD_UI_ORIGIN) -#include "DGUSDisplayDefinition.h" -#include "DGUSDisplay.h" +#include "../DGUSDisplayDef.h" +#include "../DGUSDisplay.h" -#include "../../../../module/temperature.h" -#include "../../../../module/motion.h" -#include "../../../../module/planner.h" +#include "../../../../../module/temperature.h" +#include "../../../../../module/motion.h" +#include "../../../../../module/planner.h" -#include "../../../ultralcd.h" +#include "../../../../ultralcd.h" -#if ENABLED(DUGS_UI_MOVE_DIS_OPTION) +#if ENABLED(DGUS_UI_MOVE_DIS_OPTION) uint16_t distanceToMove = 0.1; #endif @@ -162,10 +162,10 @@ const struct DGUS_VP_Variable ListOfVP[] PROGMEM = { VPHELPER(VP_TEMP_ALL_OFF, nullptr, &DGUSScreenVariableHandler::HandleAllHeatersOff, nullptr), - #if ENABLED(DUGS_UI_MOVE_DIS_OPTION) + #if ENABLED(DGUS_UI_MOVE_DIS_OPTION) VPHELPER(VP_MOVE_OPTION, &distanceToMove, &DGUSScreenVariableHandler::HandleManualMoveOption, nullptr), #endif - #if ENABLED(DUGS_UI_MOVE_DIS_OPTION) + #if ENABLED(DGUS_UI_MOVE_DIS_OPTION) VPHELPER(VP_MOVE_X, &distanceToMove, &DGUSScreenVariableHandler::HandleManualMove, nullptr), VPHELPER(VP_MOVE_Y, &distanceToMove, &DGUSScreenVariableHandler::HandleManualMove, nullptr), VPHELPER(VP_MOVE_Z, &distanceToMove, &DGUSScreenVariableHandler::HandleManualMove, nullptr), @@ -250,9 +250,7 @@ const struct DGUS_VP_Variable ListOfVP[] PROGMEM = { VPHELPER(VP_ZPos, ¤t_position.z, nullptr, DGUSScreenVariableHandler::DGUSLCD_SendFloatAsLongValueToDisplay<2>), // Print Progress - #if ENABLED(LCD_SET_PROGRESS_MANUALLY) - VPHELPER(VP_PrintProgress_Percentage, &ui.progress_override, nullptr, DGUSScreenVariableHandler::DGUSLCD_SendWordValueToDisplay ), - #endif + VPHELPER(VP_PrintProgress_Percentage, nullptr, nullptr, DGUSScreenVariableHandler::DGUSLCD_SendPrintProgressToDisplay ), // Print Time VPHELPER_STR(VP_PrintTime, nullptr, VP_PrintTime_LEN, nullptr, DGUSScreenVariableHandler::DGUSLCD_SendPrintTimeToDisplay ), diff --git a/Marlin/src/lcd/extensible_ui/lib/dgus/DGUSDisplayDefinitionOrigin.h b/Marlin/src/lcd/extui/lib/dgus/origin/DGUSDisplayDef.h similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/dgus/DGUSDisplayDefinitionOrigin.h rename to Marlin/src/lcd/extui/lib/dgus/origin/DGUSDisplayDef.h diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/archim2-flash/flash_storage.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/archim2-flash/flash_storage.cpp similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/archim2-flash/flash_storage.cpp rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/archim2-flash/flash_storage.cpp diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/archim2-flash/flash_storage.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/archim2-flash/flash_storage.h similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/archim2-flash/flash_storage.h rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/archim2-flash/flash_storage.h diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/archim2-flash/media_file_reader.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/archim2-flash/media_file_reader.cpp similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/archim2-flash/media_file_reader.cpp rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/archim2-flash/media_file_reader.cpp diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/archim2-flash/media_file_reader.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/archim2-flash/media_file_reader.h similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/archim2-flash/media_file_reader.h rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/archim2-flash/media_file_reader.h diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/compat.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/compat.h similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/compat.h rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/compat.h diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/config.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/config.h similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/config.h rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/config.h diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/LICENSE.txt b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/LICENSE.txt similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/LICENSE.txt rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/LICENSE.txt diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/README.md b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/README.md similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/README.md rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/README.md diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/boards.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/boards.h similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/boards.h rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/boards.h diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/commands.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/commands.cpp similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/commands.cpp rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/commands.cpp diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/commands.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/commands.h similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/commands.h rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/commands.h diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/constants.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/constants.h similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/constants.h rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/constants.h diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/display_list.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/display_list.h similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/display_list.h rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/display_list.h diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/ftdi_basic.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/ftdi_basic.h similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/ftdi_basic.h rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/ftdi_basic.h diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/registers_ft800.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/registers_ft800.h similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/registers_ft800.h rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/registers_ft800.h diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/registers_ft810.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/registers_ft810.h similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/registers_ft810.h rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/registers_ft810.h diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/resolutions.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/resolutions.h similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/resolutions.h rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/resolutions.h diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/spi.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/spi.cpp similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/spi.cpp rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/spi.cpp diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/spi.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/spi.h similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/spi.h rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/spi.h diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/compat.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/compat.h similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/compat.h rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/compat.h diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/bitmap_info.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/bitmap_info.h similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/bitmap_info.h rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/bitmap_info.h diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/command_processor.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/command_processor.cpp similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/command_processor.cpp rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/command_processor.cpp diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/command_processor.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/command_processor.h similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/command_processor.h rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/command_processor.h diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/dl_cache.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/dl_cache.cpp similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/dl_cache.cpp rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/dl_cache.cpp diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/dl_cache.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/dl_cache.h similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/dl_cache.h rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/dl_cache.h diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/event_loop.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/event_loop.cpp similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/event_loop.cpp rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/event_loop.cpp diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/event_loop.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/event_loop.h similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/event_loop.h rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/event_loop.h diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/ftdi_extended.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/ftdi_extended.h similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/ftdi_extended.h rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/ftdi_extended.h diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/grid_layout.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/grid_layout.h similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/grid_layout.h rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/grid_layout.h diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/polygon.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/polygon.h similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/polygon.h rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/polygon.h diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/rgb_t.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/rgb_t.h similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/rgb_t.h rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/rgb_t.h diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/screen_types.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/screen_types.cpp similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/screen_types.cpp rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/screen_types.cpp diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/screen_types.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/screen_types.h similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/screen_types.h rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/screen_types.h diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/sound_list.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/sound_list.h similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/sound_list.h rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/sound_list.h diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/sound_player.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/sound_player.cpp similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/sound_player.cpp rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/sound_player.cpp diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/sound_player.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/sound_player.h similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/sound_player.h rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/sound_player.h diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_box.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_box.cpp similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_box.cpp rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_box.cpp diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_box.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_box.h similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_box.h rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_box.h diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/tiny_timer.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/tiny_timer.cpp similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/tiny_timer.cpp rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/tiny_timer.cpp diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/tiny_timer.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/tiny_timer.h similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/tiny_timer.h rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/tiny_timer.h diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/README.txt b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/README.txt similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/README.txt rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/README.txt diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_bitmaps.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_bitmaps.cpp similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_bitmaps.cpp rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_bitmaps.cpp diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_bitmaps.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_bitmaps.h similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_bitmaps.h rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_bitmaps.h diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_bitmaps/romfont_31.pbm b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_bitmaps/romfont_31.pbm similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_bitmaps/romfont_31.pbm rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_bitmaps/romfont_31.pbm diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_bitmaps/western_char_set_bitmap_31.png b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_bitmaps/western_char_set_bitmap_31.png similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_bitmaps/western_char_set_bitmap_31.png rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_bitmaps/western_char_set_bitmap_31.png diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_bitmaps/western_char_set_bitmap_31.svg b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_bitmaps/western_char_set_bitmap_31.svg similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_bitmaps/western_char_set_bitmap_31.svg rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_bitmaps/western_char_set_bitmap_31.svg diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_size_t.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_size_t.cpp similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_size_t.cpp rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_size_t.cpp diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_size_t.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_size_t.h similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_size_t.h rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_size_t.h diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/standard_char_set.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/standard_char_set.cpp similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/standard_char_set.cpp rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/standard_char_set.cpp diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/standard_char_set.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/standard_char_set.h similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/standard_char_set.h rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/standard_char_set.h diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/unicode.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/unicode.cpp similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/unicode.cpp rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/unicode.cpp diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/unicode.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/unicode.h similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/unicode.h rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/unicode.h diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/western_char_set.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/western_char_set.cpp similarity index 99% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/western_char_set.cpp rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/western_char_set.cpp index 688b68ae0c..e2ce15dc8f 100644 --- a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/western_char_set.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/western_char_set.cpp @@ -339,11 +339,11 @@ alt_fm.stride = 19; alt_fm.width = 38; alt_fm.height = 49; - for (uint8_t i = 0; i < 127; i++) + LOOP_L_N(i, 127) alt_fm.char_widths[i] = 0; // For special characters, copy the character widths from the char tables - for (uint8_t i = 0; i < NUM_ELEMENTS(char_recipe); i++) { + LOOP_L_N(i, NUM_ELEMENTS(char_recipe)) { uint8_t std_char, alt_char, alt_data; get_char_data(i, std_char, alt_char, alt_data); if (std_char == 0) diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/western_char_set.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/western_char_set.h similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/western_char_set.h rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/western_char_set.h diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/western_char_set_bitmap_31.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/western_char_set_bitmap_31.h similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/western_char_set_bitmap_31.h rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/western_char_set_bitmap_31.h diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extras/bitmap2cpp.py b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extras/bitmap2cpp.py similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extras/bitmap2cpp.py rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extras/bitmap2cpp.py diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extras/circular_progress.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extras/circular_progress.h similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extras/circular_progress.h rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extras/circular_progress.h diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extras/poly_ui.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extras/poly_ui.h similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extras/poly_ui.h rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extras/poly_ui.h diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extras/svg2cpp.py b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extras/svg2cpp.py similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extras/svg2cpp.py rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extras/svg2cpp.py diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/ftdi_eve_lib.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/ftdi_eve_lib.h similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/ftdi_eve_lib.h rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/ftdi_eve_lib.h diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/language/language.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/language/language.cpp similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/language/language.cpp rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/language/language.cpp diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/language/language.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/language/language.h similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/language/language.h rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/language/language.h diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/language/language_en.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/language/language_en.h similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/language/language_en.h rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/language/language_en.h diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/marlin_events.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/marlin_events.cpp similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/marlin_events.cpp rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/marlin_events.cpp diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/pin_mappings.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/pin_mappings.h similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/pin_mappings.h rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/pin_mappings.h diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/about_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/about_screen.cpp similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/about_screen.cpp rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/about_screen.cpp diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/advanced_settings_menu.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/advanced_settings_menu.cpp similarity index 97% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/advanced_settings_menu.cpp rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/advanced_settings_menu.cpp index 103dcc0364..6029382838 100644 --- a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/advanced_settings_menu.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/advanced_settings_menu.cpp @@ -58,13 +58,13 @@ void AdvancedSettingsMenu::onRedraw(draw_mode_t what) { .tag(16).button( BTN_POS(1,6), BTN_SIZE(1,1), GET_TEXT_F(MSG_CASE_LIGHT)) .tag(3) .button( BTN_POS(2,1), BTN_SIZE(1,1), GET_TEXT_F(MSG_STEPS_PER_MM)) .enabled( - #if HAS_TRINAMIC + #if HAS_TRINAMIC_CONFIG 1 #endif ) .tag(13).button( BTN_POS(1,4), BTN_SIZE(1,1), GET_TEXT_F(MSG_TMC_CURRENT)) .enabled( - #if HAS_TRINAMIC + #if HAS_TRINAMIC_CONFIG 1 #endif ) @@ -120,13 +120,13 @@ void AdvancedSettingsMenu::onRedraw(draw_mode_t what) { .enabled(1) .tag(3) .button( BTN_POS(2,1), BTN_SIZE(1,1), GET_TEXT_F(MSG_STEPS_PER_MM)) .enabled( - #if HAS_TRINAMIC + #if HAS_TRINAMIC_CONFIG 1 #endif ) .tag(13).button( BTN_POS(3,1), BTN_SIZE(1,1), GET_TEXT_F(MSG_TMC_CURRENT)) .enabled( - #if HAS_TRINAMIC + #if HAS_TRINAMIC_CONFIG 1 #endif ) @@ -189,7 +189,7 @@ bool AdvancedSettingsMenu::onTouchEnd(uint8_t tag) { case 11: GOTO_SCREEN(FilamentMenu); break; #endif case 12: GOTO_SCREEN(EndstopStatesScreen); break; - #if HAS_TRINAMIC + #if HAS_TRINAMIC_CONFIG case 13: GOTO_SCREEN(StepperCurrentScreen); break; case 14: GOTO_SCREEN(StepperBumpSensitivityScreen); break; #endif diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/alert_dialog_box.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/alert_dialog_box.cpp similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/alert_dialog_box.cpp rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/alert_dialog_box.cpp diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/backlash_compensation_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/backlash_compensation_screen.cpp similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/backlash_compensation_screen.cpp rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/backlash_compensation_screen.cpp diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/base_numeric_adjustment_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/base_numeric_adjustment_screen.cpp similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/base_numeric_adjustment_screen.cpp rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/base_numeric_adjustment_screen.cpp diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/base_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/base_screen.cpp similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/base_screen.cpp rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/base_screen.cpp diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/bio_advanced_settings.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_advanced_settings.cpp similarity index 98% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/bio_advanced_settings.cpp rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_advanced_settings.cpp index 0c53dca61b..6c9f74f93f 100644 --- a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/bio_advanced_settings.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_advanced_settings.cpp @@ -45,13 +45,13 @@ void AdvancedSettingsMenu::onRedraw(draw_mode_t what) { .tag(2) .button( BTN_POS(1,1), BTN_SIZE(1,1), GET_TEXT_F(MSG_DISPLAY_MENU)) .enabled( - #if HAS_TRINAMIC + #if HAS_TRINAMIC_CONFIG 1 #endif ) .tag(3) .button( BTN_POS(1,2), BTN_SIZE(1,1), GET_TEXT_F(MSG_TMC_CURRENT)) .enabled( - #if HAS_TRINAMIC + #if HAS_TRINAMIC_CONFIG 1 #endif ) @@ -100,7 +100,7 @@ bool AdvancedSettingsMenu::onTouchEnd(uint8_t tag) { switch (tag) { case 1: SaveSettingsDialogBox::promptToSaveSettings(); break; case 2: GOTO_SCREEN(DisplayTuningScreen); break; - #if HAS_TRINAMIC + #if HAS_TRINAMIC_CONFIG case 3: GOTO_SCREEN(StepperCurrentScreen); break; case 4: GOTO_SCREEN(StepperBumpSensitivityScreen); break; #endif diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/bio_confirm_home_e.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_confirm_home_e.cpp similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/bio_confirm_home_e.cpp rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_confirm_home_e.cpp diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/bio_confirm_home_xyz.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_confirm_home_xyz.cpp similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/bio_confirm_home_xyz.cpp rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_confirm_home_xyz.cpp diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/bio_main_menu.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_main_menu.cpp similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/bio_main_menu.cpp rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_main_menu.cpp diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/bio_printer_ui_landscape.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_printer_ui_landscape.h similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/bio_printer_ui_landscape.h rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_printer_ui_landscape.h diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/bio_printer_ui_portrait.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_printer_ui_portrait.h similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/bio_printer_ui_portrait.h rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_printer_ui_portrait.h diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/bio_printing_dialog_box.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_printing_dialog_box.cpp similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/bio_printing_dialog_box.cpp rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_printing_dialog_box.cpp diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/bio_status_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_status_screen.cpp similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/bio_status_screen.cpp rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_status_screen.cpp diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/bio_tune_menu.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_tune_menu.cpp similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/bio_tune_menu.cpp rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_tune_menu.cpp diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/boot_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/boot_screen.cpp similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/boot_screen.cpp rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/boot_screen.cpp diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/case_light_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/case_light_screen.cpp similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/case_light_screen.cpp rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/case_light_screen.cpp diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/change_filament_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/change_filament_screen.cpp similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/change_filament_screen.cpp rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/change_filament_screen.cpp diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/confirm_abort_print_dialog_box.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/confirm_abort_print_dialog_box.cpp similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/confirm_abort_print_dialog_box.cpp rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/confirm_abort_print_dialog_box.cpp diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/confirm_auto_calibration_dialog_box.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/confirm_auto_calibration_dialog_box.cpp similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/confirm_auto_calibration_dialog_box.cpp rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/confirm_auto_calibration_dialog_box.cpp diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/confirm_erase_flash_dialog_box.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/confirm_erase_flash_dialog_box.cpp similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/confirm_erase_flash_dialog_box.cpp rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/confirm_erase_flash_dialog_box.cpp diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/confirm_start_print_dialog_box.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/confirm_start_print_dialog_box.cpp similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/confirm_start_print_dialog_box.cpp rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/confirm_start_print_dialog_box.cpp diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/confirm_user_request_alert_box.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/confirm_user_request_alert_box.cpp similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/confirm_user_request_alert_box.cpp rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/confirm_user_request_alert_box.cpp diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/default_acceleration_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/default_acceleration_screen.cpp similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/default_acceleration_screen.cpp rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/default_acceleration_screen.cpp diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/developer_menu.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/developer_menu.cpp similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/developer_menu.cpp rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/developer_menu.cpp diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/dialog_box_base_class.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/dialog_box_base_class.cpp similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/dialog_box_base_class.cpp rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/dialog_box_base_class.cpp diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/display_tuning_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/display_tuning_screen.cpp similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/display_tuning_screen.cpp rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/display_tuning_screen.cpp diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/endstop_state_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/endstop_state_screen.cpp similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/endstop_state_screen.cpp rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/endstop_state_screen.cpp diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/feedrate_percent_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/feedrate_percent_screen.cpp similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/feedrate_percent_screen.cpp rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/feedrate_percent_screen.cpp diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/filament_menu.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/filament_menu.cpp similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/filament_menu.cpp rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/filament_menu.cpp diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/filament_runout_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/filament_runout_screen.cpp similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/filament_runout_screen.cpp rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/filament_runout_screen.cpp diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/files_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/files_screen.cpp similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/files_screen.cpp rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/files_screen.cpp diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/interface_settings_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/interface_settings_screen.cpp similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/interface_settings_screen.cpp rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/interface_settings_screen.cpp diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/interface_sounds_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/interface_sounds_screen.cpp similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/interface_sounds_screen.cpp rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/interface_sounds_screen.cpp diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/jerk_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/jerk_screen.cpp similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/jerk_screen.cpp rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/jerk_screen.cpp diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/junction_deviation_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/junction_deviation_screen.cpp similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/junction_deviation_screen.cpp rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/junction_deviation_screen.cpp diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/kill_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/kill_screen.cpp similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/kill_screen.cpp rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/kill_screen.cpp diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/language_menu.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/language_menu.cpp similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/language_menu.cpp rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/language_menu.cpp diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/linear_advance_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/linear_advance_screen.cpp similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/linear_advance_screen.cpp rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/linear_advance_screen.cpp diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/lock_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/lock_screen.cpp similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/lock_screen.cpp rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/lock_screen.cpp diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/main_menu.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/main_menu.cpp similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/main_menu.cpp rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/main_menu.cpp diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/max_acceleration_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/max_acceleration_screen.cpp similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/max_acceleration_screen.cpp rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/max_acceleration_screen.cpp diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/max_velocity_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/max_velocity_screen.cpp similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/max_velocity_screen.cpp rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/max_velocity_screen.cpp diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/media_player_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/media_player_screen.cpp similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/media_player_screen.cpp rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/media_player_screen.cpp diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/move_axis_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/move_axis_screen.cpp similarity index 99% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/move_axis_screen.cpp rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/move_axis_screen.cpp index 8513c79f84..4bf8ed190e 100644 --- a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/move_axis_screen.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/move_axis_screen.cpp @@ -36,7 +36,7 @@ void MoveAxisScreen::onEntry() { // ourselves. The relative distances are reset to zero whenever this // screen is entered. - for (uint8_t i = 0; i < ExtUI::extruderCount; i++) { + LOOP_L_N(i, ExtUI::extruderCount) { screen_data.MoveAxisScreen.e_rel[i] = 0; } BaseNumericAdjustmentScreen::onEntry(); diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/nozzle_offsets_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/nozzle_offsets_screen.cpp similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/nozzle_offsets_screen.cpp rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/nozzle_offsets_screen.cpp diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/nudge_nozzle_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/nudge_nozzle_screen.cpp similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/nudge_nozzle_screen.cpp rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/nudge_nozzle_screen.cpp diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/preheat_timer_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/preheat_timer_screen.cpp similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/preheat_timer_screen.cpp rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/preheat_timer_screen.cpp diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/restore_failsafe_dialog_box.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/restore_failsafe_dialog_box.cpp similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/restore_failsafe_dialog_box.cpp rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/restore_failsafe_dialog_box.cpp diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/save_settings_dialog_box.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/save_settings_dialog_box.cpp similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/save_settings_dialog_box.cpp rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/save_settings_dialog_box.cpp diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/screen_data.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/screen_data.h similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/screen_data.h rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/screen_data.h diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/screens.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/screens.cpp similarity index 99% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/screens.cpp rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/screens.cpp index bc92800054..69c1cf1420 100644 --- a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/screens.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/screens.cpp @@ -58,7 +58,7 @@ SCREEN_TABLE { #endif DECL_SCREEN(MoveAxisScreen), DECL_SCREEN(StepsScreen), -#if HAS_TRINAMIC +#if HAS_TRINAMIC_CONFIG DECL_SCREEN(StepperCurrentScreen), DECL_SCREEN(StepperBumpSensitivityScreen), #endif diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/screens.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/screens.h similarity index 99% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/screens.h rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/screens.h index 176c8145e3..02c5b14831 100644 --- a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/screens.h +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/screens.h @@ -455,7 +455,7 @@ class StepsScreen : public BaseNumericAdjustmentScreen, public CachedScreen { public: static void onRedraw(draw_mode_t); diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/spinner_dialog_box.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/spinner_dialog_box.cpp similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/spinner_dialog_box.cpp rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/spinner_dialog_box.cpp diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/statistics_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/statistics_screen.cpp similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/statistics_screen.cpp rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/statistics_screen.cpp diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/status_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/status_screen.cpp similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/status_screen.cpp rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/status_screen.cpp diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/stepper_bump_sensitivity_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/stepper_bump_sensitivity_screen.cpp similarity index 96% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/stepper_bump_sensitivity_screen.cpp rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/stepper_bump_sensitivity_screen.cpp index 9aa28aff39..2e05ad5c57 100644 --- a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/stepper_bump_sensitivity_screen.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/stepper_bump_sensitivity_screen.cpp @@ -22,7 +22,7 @@ #include "../config.h" -#if ENABLED(TOUCH_UI_FTDI_EVE) && HAS_TRINAMIC +#if ENABLED(TOUCH_UI_FTDI_EVE) && HAS_TRINAMIC_CONFIG #include "screens.h" @@ -74,4 +74,4 @@ bool StepperBumpSensitivityScreen::onTouchHeld(uint8_t tag) { return true; } -#endif // TOUCH_UI_FTDI_EVE && HAS_TRINAMIC +#endif // TOUCH_UI_FTDI_EVE && HAS_TRINAMIC_CONFIG diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/stepper_current_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/stepper_current_screen.cpp similarity index 98% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/stepper_current_screen.cpp rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/stepper_current_screen.cpp index acc94684e0..5abcea7a67 100644 --- a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/stepper_current_screen.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/stepper_current_screen.cpp @@ -22,7 +22,7 @@ #include "../config.h" -#if ENABLED(TOUCH_UI_FTDI_EVE) && HAS_TRINAMIC +#if ENABLED(TOUCH_UI_FTDI_EVE) && HAS_TRINAMIC_CONFIG #include "screens.h" diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/steps_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/steps_screen.cpp similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/steps_screen.cpp rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/steps_screen.cpp diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/stress_test_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/stress_test_screen.cpp similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/stress_test_screen.cpp rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/stress_test_screen.cpp diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/string_format.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/string_format.cpp similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/string_format.cpp rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/string_format.cpp diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/string_format.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/string_format.h similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/string_format.h rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/string_format.h diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/temperature_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/temperature_screen.cpp similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/temperature_screen.cpp rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/temperature_screen.cpp diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/touch_calibration_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/touch_calibration_screen.cpp similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/touch_calibration_screen.cpp rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/touch_calibration_screen.cpp diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/touch_registers_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/touch_registers_screen.cpp similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/touch_registers_screen.cpp rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/touch_registers_screen.cpp diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/tune_menu.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/tune_menu.cpp similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/tune_menu.cpp rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/tune_menu.cpp diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/widget_demo_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/widget_demo_screen.cpp similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/widget_demo_screen.cpp rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/widget_demo_screen.cpp diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/z_offset_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/z_offset_screen.cpp similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/screens/z_offset_screen.cpp rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/z_offset_screen.cpp diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/theme/bitmaps.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/theme/bitmaps.h similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/theme/bitmaps.h rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/theme/bitmaps.h diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/theme/colors.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/theme/colors.h similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/theme/colors.h rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/theme/colors.h diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/theme/fonts.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/theme/fonts.h similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/theme/fonts.h rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/theme/fonts.h diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/theme/marlin_bootscreen_landscape.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/theme/marlin_bootscreen_landscape.h similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/theme/marlin_bootscreen_landscape.h rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/theme/marlin_bootscreen_landscape.h diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/theme/marlin_bootscreen_portrait.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/theme/marlin_bootscreen_portrait.h similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/theme/marlin_bootscreen_portrait.h rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/theme/marlin_bootscreen_portrait.h diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/theme/sounds.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/theme/sounds.cpp similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/theme/sounds.cpp rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/theme/sounds.cpp diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/theme/sounds.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/theme/sounds.h similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/theme/sounds.h rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/theme/sounds.h diff --git a/Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/theme/theme.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/theme/theme.h similarity index 100% rename from Marlin/src/lcd/extensible_ui/lib/ftdi_eve_touch_ui/theme/theme.h rename to Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/theme/theme.h diff --git a/Marlin/src/lcd/extensible_ui/ui_api.cpp b/Marlin/src/lcd/extui/ui_api.cpp similarity index 99% rename from Marlin/src/lcd/extensible_ui/ui_api.cpp rename to Marlin/src/lcd/extui/ui_api.cpp index 7ef7614b8d..79e12f36d1 100644 --- a/Marlin/src/lcd/extensible_ui/ui_api.cpp +++ b/Marlin/src/lcd/extui/ui_api.cpp @@ -65,7 +65,7 @@ #endif #if ENABLED(EMERGENCY_PARSER) - #include "../../feature/emergency_parser.h" + #include "../../feature/e_parser.h" #endif #if ENABLED(SDSUPPORT) @@ -75,7 +75,7 @@ #define IFSD(A,B) (B) #endif -#if HAS_TRINAMIC +#if HAS_TRINAMIC_CONFIG #include "../../feature/tmc_util.h" #include "../../module/stepper/indirection.h" #endif @@ -445,7 +445,7 @@ namespace ExtUI { void setSoftEndstopState(const bool value) { soft_endstops_enabled = value; } #endif - #if HAS_TRINAMIC + #if HAS_TRINAMIC_CONFIG float getAxisCurrent_mA(const axis_t axis) { switch (axis) { #if AXIS_IS_TMC(X) diff --git a/Marlin/src/lcd/extensible_ui/ui_api.h b/Marlin/src/lcd/extui/ui_api.h similarity index 99% rename from Marlin/src/lcd/extensible_ui/ui_api.h rename to Marlin/src/lcd/extui/ui_api.h index 10df2bc72d..61fecaed46 100644 --- a/Marlin/src/lcd/extensible_ui/ui_api.h +++ b/Marlin/src/lcd/extui/ui_api.h @@ -97,7 +97,7 @@ namespace ExtUI { void setSoftEndstopState(const bool); #endif - #if HAS_TRINAMIC + #if HAS_TRINAMIC_CONFIG float getAxisCurrent_mA(const axis_t); float getAxisCurrent_mA(const extruder_t); void setAxisCurrent_mA(const float, const axis_t); diff --git a/Marlin/src/lcd/extui_dgus_lcd.cpp b/Marlin/src/lcd/extui_dgus_lcd.cpp index 5c6f11d7cb..66a58f82dc 100644 --- a/Marlin/src/lcd/extui_dgus_lcd.cpp +++ b/Marlin/src/lcd/extui_dgus_lcd.cpp @@ -30,9 +30,9 @@ #if HAS_DGUS_LCD -#include "extensible_ui/ui_api.h" -#include "extensible_ui/lib/dgus/DGUSDisplay.h" -#include "extensible_ui/lib/dgus/DGUSDisplayDefinition.h" +#include "extui/ui_api.h" +#include "extui/lib/dgus/DGUSDisplay.h" +#include "extui/lib/dgus/DGUSDisplayDef.h" extern const char NUL_STR[]; diff --git a/Marlin/src/lcd/extui_example.cpp b/Marlin/src/lcd/extui_example.cpp index 5e65af7381..741787dbe6 100644 --- a/Marlin/src/lcd/extui_example.cpp +++ b/Marlin/src/lcd/extui_example.cpp @@ -23,7 +23,7 @@ #if BOTH(EXTUI_EXAMPLE, EXTENSIBLE_UI) -#include "extensible_ui/ui_api.h" +#include "extui/ui_api.h" // To implement a new UI, complete the functions below and // read or update Marlin's state using the methods in the diff --git a/Marlin/src/lcd/extui_malyan_lcd.cpp b/Marlin/src/lcd/extui_malyan_lcd.cpp index 0d2567a204..0bb8060b07 100644 --- a/Marlin/src/lcd/extui_malyan_lcd.cpp +++ b/Marlin/src/lcd/extui_malyan_lcd.cpp @@ -47,7 +47,7 @@ #define DEBUG_MALYAN_LCD -#include "extensible_ui/ui_api.h" +#include "extui/ui_api.h" #include "ultralcd.h" #include "../sd/cardreader.h" @@ -81,7 +81,7 @@ void write_to_lcd_P(PGM_P const message) { char encoded_message[MAX_CURLY_COMMAND]; uint8_t message_length = _MIN(strlen_P(message), sizeof(encoded_message)); - for (uint8_t i = 0; i < message_length; i++) + LOOP_L_N(i, message_length) encoded_message[i] = pgm_read_byte(&message[i]) | 0x80; LCD_SERIAL.Print::write(encoded_message, message_length); @@ -91,7 +91,7 @@ void write_to_lcd(const char * const message) { char encoded_message[MAX_CURLY_COMMAND]; const uint8_t message_length = _MIN(strlen(message), sizeof(encoded_message)); - for (uint8_t i = 0; i < message_length; i++) + LOOP_L_N(i, message_length) encoded_message[i] = message[i] | 0x80; LCD_SERIAL.Print::write(encoded_message, message_length); @@ -483,6 +483,7 @@ namespace ExtUI { void onLoadSettings(const char*) {} void onConfigurationStoreWritten(bool) {} void onConfigurationStoreRead(bool) {} + void OnPidTuning(const result_t) {} } #endif // MALYAN_LCD diff --git a/Marlin/src/lcd/language/language_de.h b/Marlin/src/lcd/language/language_de.h index ed2f779dd8..5ac8ee04da 100644 --- a/Marlin/src/lcd/language/language_de.h +++ b/Marlin/src/lcd/language/language_de.h @@ -349,17 +349,17 @@ namespace Language_de { PROGMEM Language_Str MSG_ZPROBE_OUT = _UxGT("Z-Sonde außerhalb"); PROGMEM Language_Str MSG_SKEW_FACTOR = _UxGT("Korrekturfaktor"); PROGMEM Language_Str MSG_BLTOUCH = _UxGT("BLTouch"); - PROGMEM Language_Str MSG_BLTOUCH_SELFTEST = _UxGT("BLTouch Selbsttest"); - PROGMEM Language_Str MSG_BLTOUCH_RESET = _UxGT("BLTouch zurücks."); - PROGMEM Language_Str MSG_BLTOUCH_DEPLOY = _UxGT("BLTouch ausfahren"); - PROGMEM Language_Str MSG_BLTOUCH_SW_MODE = _UxGT("BLTouch SW-Modus"); - PROGMEM Language_Str MSG_BLTOUCH_5V_MODE = _UxGT("BLTouch 5V-Modus"); - PROGMEM Language_Str MSG_BLTOUCH_OD_MODE = _UxGT("BLTouch OD-Modus"); - PROGMEM Language_Str MSG_BLTOUCH_MODE_STORE = _UxGT("BLTouch Mode Store"); - PROGMEM Language_Str MSG_BLTOUCH_MODE_STORE_5V = _UxGT("BLTouch auf 5V"); - PROGMEM Language_Str MSG_BLTOUCH_MODE_STORE_OD = _UxGT("BLTouch auf OD"); - PROGMEM Language_Str MSG_BLTOUCH_STOW = _UxGT("BLTouch einfahren"); - PROGMEM Language_Str MSG_BLTOUCH_MODE_ECHO = _UxGT("BLTouch Modus: "); + PROGMEM Language_Str MSG_BLTOUCH_SELFTEST = _UxGT("Selbsttest"); + PROGMEM Language_Str MSG_BLTOUCH_RESET = _UxGT("Zurücksetzen"); + PROGMEM Language_Str MSG_BLTOUCH_DEPLOY = _UxGT("Ausfahren"); + PROGMEM Language_Str MSG_BLTOUCH_SW_MODE = _UxGT("SW-Modus"); + PROGMEM Language_Str MSG_BLTOUCH_5V_MODE = _UxGT("5V-Modus"); + PROGMEM Language_Str MSG_BLTOUCH_OD_MODE = _UxGT("OD-Modus"); + PROGMEM Language_Str MSG_BLTOUCH_MODE_STORE = _UxGT("Mode-Store"); + PROGMEM Language_Str MSG_BLTOUCH_MODE_STORE_5V = _UxGT("Setze auf 5V"); + PROGMEM Language_Str MSG_BLTOUCH_MODE_STORE_OD = _UxGT("Setze auf OD"); + PROGMEM Language_Str MSG_BLTOUCH_STOW = _UxGT("Einfahren"); + PROGMEM Language_Str MSG_BLTOUCH_MODE_ECHO = _UxGT("Modus: "); PROGMEM Language_Str MSG_BLTOUCH_MODE_CHANGE = _UxGT("ACHTUNG: Falsche Einstellung - kann zu Beschädigung führen! Fortfahren?"); PROGMEM Language_Str MSG_TOUCHMI_PROBE = _UxGT("TouchMI"); PROGMEM Language_Str MSG_TOUCHMI_INIT = _UxGT("TouchMI initial."); diff --git a/Marlin/src/lcd/language/language_tr.h b/Marlin/src/lcd/language/language_tr.h index 57d2911af9..0edade0374 100644 --- a/Marlin/src/lcd/language/language_tr.h +++ b/Marlin/src/lcd/language/language_tr.h @@ -42,9 +42,18 @@ namespace Language_tr { PROGMEM Language_Str LANGUAGE = _UxGT("Turkish"); PROGMEM Language_Str WELCOME_MSG = MACHINE_NAME _UxGT(" hazır."); + PROGMEM Language_Str MSG_MARLIN = _UxGT("Marlin"); + PROGMEM Language_Str MSG_YES = _UxGT("EVET"); + PROGMEM Language_Str MSG_NO = _UxGT("HAYIR"); PROGMEM Language_Str MSG_BACK = _UxGT("Geri"); + PROGMEM Language_Str MSG_MEDIA_ABORTING = _UxGT("Durduruluyor..."); PROGMEM Language_Str MSG_MEDIA_INSERTED = _UxGT("SD K. Yerleştirildi."); PROGMEM Language_Str MSG_MEDIA_REMOVED = _UxGT("SD Kart Çıkarıldı."); + PROGMEM Language_Str MSG_MEDIA_RELEASED = _UxGT("SD Kart Serbest"); + PROGMEM Language_Str MSG_MEDIA_WAITING = _UxGT("SD Kart Bekleniyor"); + PROGMEM Language_Str MSG_MEDIA_READ_ERROR = _UxGT("Kart Okuma Hatası"); + PROGMEM Language_Str MSG_MEDIA_USB_REMOVED = _UxGT("USB Çıkarıldı"); + PROGMEM Language_Str MSG_MEDIA_USB_FAILED = _UxGT("USB Başlat. Hatası"); PROGMEM Language_Str MSG_LCD_ENDSTOPS = _UxGT("Enstops"); // Max length 8 characters PROGMEM Language_Str MSG_LCD_SOFT_ENDSTOPS = _UxGT("Yazılımsal Endstops"); PROGMEM Language_Str MSG_MAIN = _UxGT("Ana"); @@ -64,8 +73,8 @@ namespace Language_tr { PROGMEM Language_Str MSG_LEVEL_BED_NEXT_POINT = _UxGT("Sonraki Nokta"); PROGMEM Language_Str MSG_LEVEL_BED_DONE = _UxGT("Hizalama Tamam!"); PROGMEM Language_Str MSG_Z_FADE_HEIGHT = _UxGT("Kaçınma Yüksekliği"); - PROGMEM Language_Str MSG_SET_HOME_OFFSETS = _UxGT("Offset Ayarla"); - PROGMEM Language_Str MSG_HOME_OFFSETS_APPLIED = _UxGT("Offset Tamam"); + PROGMEM Language_Str MSG_SET_HOME_OFFSETS = _UxGT("Ofset Ayarla"); + PROGMEM Language_Str MSG_HOME_OFFSETS_APPLIED = _UxGT("Ofset Tamam"); PROGMEM Language_Str MSG_SET_ORIGIN = _UxGT("Sıfır Belirle"); PROGMEM Language_Str MSG_PREHEAT_1 = _UxGT("Ön Isınma ") PREHEAT_1_LABEL; PROGMEM Language_Str MSG_PREHEAT_1_H = _UxGT("Ön Isınma ") PREHEAT_1_LABEL " ~"; @@ -82,7 +91,16 @@ namespace Language_tr { PROGMEM Language_Str MSG_PREHEAT_2_BEDONLY = _UxGT("Ön Isınma ") PREHEAT_2_LABEL _UxGT(" Tabla"); PROGMEM Language_Str MSG_PREHEAT_2_SETTINGS = _UxGT("Ön Isınma ") PREHEAT_2_LABEL _UxGT(" Ayarlar"); PROGMEM Language_Str MSG_PREHEAT_CUSTOM = _UxGT("Özel Ön Isınma"); - PROGMEM Language_Str MSG_COOLDOWN = _UxGT("Soğut"); + PROGMEM Language_Str MSG_COOLDOWN = _UxGT("Soğut/(Durdur)"); + PROGMEM Language_Str MSG_LASER_MENU = _UxGT("Lazer Kontrolü"); + PROGMEM Language_Str MSG_LASER_OFF = _UxGT("Lazeri Kapat"); + PROGMEM Language_Str MSG_LASER_ON = _UxGT("Lazeri Aç"); + PROGMEM Language_Str MSG_LASER_POWER = _UxGT("Lazer Gücü"); + PROGMEM Language_Str MSG_SPINDLE_MENU = _UxGT("Spindle Kontrolü"); + PROGMEM Language_Str MSG_SPINDLE_OFF = _UxGT("Spindle Kapat"); + PROGMEM Language_Str MSG_SPINDLE_ON = _UxGT("Spindle Aç"); + PROGMEM Language_Str MSG_SPINDLE_POWER = _UxGT("Spindle Gücü"); + PROGMEM Language_Str MSG_SPINDLE_REVERSE = _UxGT("Spindle Ters Yön"); PROGMEM Language_Str MSG_SWITCH_PS_ON = _UxGT("Gücü Aç"); PROGMEM Language_Str MSG_SWITCH_PS_OFF = _UxGT("Gücü Kapat"); PROGMEM Language_Str MSG_EXTRUDE = _UxGT("Ekstrüzyon"); @@ -92,13 +110,19 @@ namespace Language_tr { PROGMEM Language_Str MSG_LEVEL_BED = _UxGT("Tabla Hizası"); PROGMEM Language_Str MSG_LEVEL_CORNERS = _UxGT("Hizalama Köşeleri"); PROGMEM Language_Str MSG_NEXT_CORNER = _UxGT("Sonraki Köşe"); + PROGMEM Language_Str MSG_MESH_EDITOR = _UxGT("Mesh Editörü"); PROGMEM Language_Str MSG_EDIT_MESH = _UxGT("Mesh Düzenle"); PROGMEM Language_Str MSG_EDITING_STOPPED = _UxGT("Mesh Düzenleme Durdu"); + PROGMEM Language_Str MSG_PROBING_MESH = _UxGT("Prop Noktası"); PROGMEM Language_Str MSG_MESH_X = _UxGT("İndeks X"); PROGMEM Language_Str MSG_MESH_Y = _UxGT("İndeks Y"); PROGMEM Language_Str MSG_MESH_EDIT_Z = _UxGT("Z Değeri"); PROGMEM Language_Str MSG_USER_MENU = _UxGT("Özel Komutlar"); + PROGMEM Language_Str MSG_M48_TEST = _UxGT("M48 Prob Testi"); + PROGMEM Language_Str MSG_M48_POINT = _UxGT("M48 Nokta"); + PROGMEM Language_Str MSG_M48_DEVIATION = _UxGT("Sapma"); PROGMEM Language_Str MSG_IDEX_MENU = _UxGT("IDEX Modu"); + PROGMEM Language_Str MSG_OFFSETS_MENU = _UxGT("Takım Ofsetleri"); PROGMEM Language_Str MSG_IDEX_MODE_AUTOPARK = _UxGT("Oto-Park"); PROGMEM Language_Str MSG_IDEX_MODE_DUPLICATE = _UxGT("Kopyala"); PROGMEM Language_Str MSG_IDEX_MODE_MIRRORED_COPY = _UxGT("Yansıtılmış kopya"); @@ -109,6 +133,7 @@ namespace Language_tr { PROGMEM Language_Str MSG_UBL_DOING_G29 = _UxGT("G29 Çalışıyor"); PROGMEM Language_Str MSG_UBL_TOOLS = _UxGT("UBL Araçları"); PROGMEM Language_Str MSG_UBL_LEVEL_BED = _UxGT("UBL Yatak Hizalama"); + PROGMEM Language_Str MSG_LCD_TILTING_MESH = _UxGT("Eğim Noktası"); PROGMEM Language_Str MSG_UBL_MANUAL_MESH = _UxGT("Elle Mesh Oluştur"); PROGMEM Language_Str MSG_UBL_BC_INSERT = _UxGT("Altlık & Ölçü Ver"); PROGMEM Language_Str MSG_UBL_BC_INSERT2 = _UxGT("Ölçü"); @@ -135,6 +160,13 @@ namespace Language_tr { PROGMEM Language_Str MSG_UBL_VALIDATE_MESH_M1 = _UxGT("Doğrulama Mesh (") PREHEAT_1_LABEL _UxGT(")"); PROGMEM Language_Str MSG_UBL_VALIDATE_MESH_M2 = _UxGT("Doğrulama Mesh (") PREHEAT_2_LABEL _UxGT(")"); PROGMEM Language_Str MSG_UBL_VALIDATE_CUSTOM_MESH = _UxGT("Özel Mesh Doğrulama"); + PROGMEM Language_Str MSG_G26_HEATING_BED = _UxGT("G26 Isıtma Tablası"); + PROGMEM Language_Str MSG_G26_HEATING_NOZZLE = _UxGT("G26 Isıtma Memesi"); + PROGMEM Language_Str MSG_G26_MANUAL_PRIME = _UxGT("Manuel çalışma..."); + PROGMEM Language_Str MSG_G26_FIXED_LENGTH = _UxGT("Birincil Sabit Uzunluk"); + PROGMEM Language_Str MSG_G26_PRIME_DONE = _UxGT("Çalışma Tamamlandı"); + PROGMEM Language_Str MSG_G26_CANCELED = _UxGT("G26 İptal edildi"); + PROGMEM Language_Str MSG_G26_LEAVING = _UxGT("Çıkış G26"); PROGMEM Language_Str MSG_UBL_CONTINUE_MESH = _UxGT("Tabla Mesh Devam et"); PROGMEM Language_Str MSG_UBL_MESH_LEVELING = _UxGT("Mesh Hizalama"); PROGMEM Language_Str MSG_UBL_3POINT_MESH_LEVELING = _UxGT("3-Nokta Hizalama"); @@ -164,6 +196,7 @@ namespace Language_tr { PROGMEM Language_Str MSG_UBL_NO_STORAGE = _UxGT("Depolama Yok"); PROGMEM Language_Str MSG_UBL_SAVE_ERROR = _UxGT("Hata: UBL Kayıt"); PROGMEM Language_Str MSG_UBL_RESTORE_ERROR = _UxGT("Hata: UBL Yenileme"); + PROGMEM Language_Str MSG_UBL_Z_OFFSET = _UxGT("Z-Ofset: "); PROGMEM Language_Str MSG_UBL_Z_OFFSET_STOPPED = _UxGT("Z-Ofset Durduruldu"); PROGMEM Language_Str MSG_UBL_STEP_BY_STEP_MENU = _UxGT("Adım Adım UBL"); PROGMEM Language_Str MSG_UBL_1_BUILD_COLD_MESH = _UxGT("1.Soğuk Mesh Oluştur"); @@ -175,8 +208,8 @@ namespace Language_tr { PROGMEM Language_Str MSG_UBL_7_SAVE_MESH = _UxGT("7.Yatak Mesh Kayıt Et"); PROGMEM Language_Str MSG_LED_CONTROL = _UxGT("LED Kontrolü"); - PROGMEM Language_Str MSG_LEDS = _UxGT("Işıklar"); - PROGMEM Language_Str MSG_LED_PRESETS = _UxGT("Işık Hazır Ayarları"); + PROGMEM Language_Str MSG_LEDS = _UxGT("LEDler"); + PROGMEM Language_Str MSG_LED_PRESETS = _UxGT("LED Hazır Ayarları"); PROGMEM Language_Str MSG_SET_LEDS_RED = _UxGT("Kırmızı"); PROGMEM Language_Str MSG_SET_LEDS_ORANGE = _UxGT("Turuncu"); PROGMEM Language_Str MSG_SET_LEDS_YELLOW = _UxGT("Sarı"); @@ -192,6 +225,7 @@ namespace Language_tr { PROGMEM Language_Str MSG_INTENSITY_B = _UxGT("Mavi Şiddeti"); PROGMEM Language_Str MSG_INTENSITY_W = _UxGT("Beyaz Şiddeti"); PROGMEM Language_Str MSG_LED_BRIGHTNESS = _UxGT("Parlaklık"); + PROGMEM Language_Str MSG_MOVING = _UxGT("Hareket Ediyor.."); PROGMEM Language_Str MSG_FREE_XY = _UxGT("Durdur XY"); PROGMEM Language_Str MSG_MOVE_X = _UxGT("X Hareketi"); @@ -209,8 +243,10 @@ namespace Language_tr { PROGMEM Language_Str MSG_NOZZLE = _UxGT("Nozul"); PROGMEM Language_Str MSG_NOZZLE_N = _UxGT("Nozul ~"); PROGMEM Language_Str MSG_BED = _UxGT("Tabla"); + PROGMEM Language_Str MSG_CHAMBER = _UxGT("Çevirme"); PROGMEM Language_Str MSG_FAN_SPEED = _UxGT("Fan Hızı"); PROGMEM Language_Str MSG_FAN_SPEED_N = _UxGT("Fan Hızı ~"); + PROGMEM Language_Str MSG_STORED_FAN_N = _UxGT("Depolanan Fan ~"); PROGMEM Language_Str MSG_EXTRA_FAN_SPEED = _UxGT("Ekstra Fan Hızı"); PROGMEM Language_Str MSG_EXTRA_FAN_SPEED_N = _UxGT("Ekstra Fan Hızı ~"); PROGMEM Language_Str MSG_FLOW = _UxGT("Akış"); @@ -222,9 +258,22 @@ namespace Language_tr { PROGMEM Language_Str MSG_AUTOTEMP = _UxGT("Oto. Sıcaklık"); PROGMEM Language_Str MSG_LCD_ON = _UxGT("Açık"); PROGMEM Language_Str MSG_LCD_OFF = _UxGT("Kapalı"); + PROGMEM Language_Str MSG_PID_AUTOTUNE = _UxGT("PID Kalibrasyon"); + PROGMEM Language_Str MSG_PID_AUTOTUNE_E = _UxGT("PID Kalibrasyon *"); + PROGMEM Language_Str MSG_PID_P = _UxGT("PID-P"); + PROGMEM Language_Str MSG_PID_P_E = _UxGT("PID-P *"); + PROGMEM Language_Str MSG_PID_I = _UxGT("PID-I"); + PROGMEM Language_Str MSG_PID_I_E = _UxGT("PID-I *"); + PROGMEM Language_Str MSG_PID_D = _UxGT("PID-D"); + PROGMEM Language_Str MSG_PID_D_E = _UxGT("PID-D *"); + PROGMEM Language_Str MSG_PID_C = _UxGT("PID-C"); + PROGMEM Language_Str MSG_PID_C_E = _UxGT("PID-C *"); + PROGMEM Language_Str MSG_PID_F = _UxGT("PID-F"); + PROGMEM Language_Str MSG_PID_F_E = _UxGT("PID-F *"); PROGMEM Language_Str MSG_SELECT = _UxGT("Seç"); PROGMEM Language_Str MSG_SELECT_E = _UxGT("Seç *"); PROGMEM Language_Str MSG_ACC = _UxGT("İvme"); + PROGMEM Language_Str MSG_JERK = _UxGT("Sarsım"); PROGMEM Language_Str MSG_VA_JERK = _UxGT("V") LCD_STR_A _UxGT("-Sarsım"); PROGMEM Language_Str MSG_VB_JERK = _UxGT("V") LCD_STR_B _UxGT("-Sarsım"); @@ -268,15 +317,31 @@ namespace Language_tr { PROGMEM Language_Str MSG_LOAD_EEPROM = _UxGT("Hafızadan Yükle"); PROGMEM Language_Str MSG_RESTORE_DEFAULTS = _UxGT("Fabrika Ayarları"); PROGMEM Language_Str MSG_INIT_EEPROM = _UxGT("EEPROM'u başlat"); + PROGMEM Language_Str MSG_ERR_EEPROM_CRC = _UxGT("Hata: EEPROM CRC"); + PROGMEM Language_Str MSG_ERR_EEPROM_INDEX = _UxGT("Hata: EEPROM Indeks"); + PROGMEM Language_Str MSG_ERR_EEPROM_VERSION = _UxGT("Hata: EEPROM Versiyonu"); PROGMEM Language_Str MSG_MEDIA_UPDATE = _UxGT("SD Güncellemesi"); PROGMEM Language_Str MSG_RESET_PRINTER = _UxGT("Yazıcıyı Resetle"); PROGMEM Language_Str MSG_REFRESH = LCD_STR_REFRESH _UxGT("Yenile"); PROGMEM Language_Str MSG_INFO_SCREEN = _UxGT("Bilgi Ekranı"); PROGMEM Language_Str MSG_PREPARE = _UxGT("Hazırlık"); PROGMEM Language_Str MSG_TUNE = _UxGT("Ayar"); + PROGMEM Language_Str MSG_START_PRINT = _UxGT("Yaz. Başlat"); + PROGMEM Language_Str MSG_BUTTON_NEXT = _UxGT("İleri"); + PROGMEM Language_Str MSG_BUTTON_INIT = _UxGT("İçinde"); + PROGMEM Language_Str MSG_BUTTON_STOP = _UxGT("Durdur"); + PROGMEM Language_Str MSG_BUTTON_PRINT = _UxGT("Yazdır"); + PROGMEM Language_Str MSG_BUTTON_RESET = _UxGT("Resetle"); + PROGMEM Language_Str MSG_BUTTON_CANCEL = _UxGT("İptal"); + PROGMEM Language_Str MSG_BUTTON_DONE = _UxGT("Tamamlandı"); + PROGMEM Language_Str MSG_BUTTON_BACK = _UxGT("Geri"); + PROGMEM Language_Str MSG_BUTTON_PROCEED = _UxGT("Devam ediyor"); PROGMEM Language_Str MSG_PAUSE_PRINT = _UxGT("Duraklat"); PROGMEM Language_Str MSG_RESUME_PRINT = _UxGT("Sürdür"); PROGMEM Language_Str MSG_STOP_PRINT = _UxGT("Durdur"); + PROGMEM Language_Str MSG_PRINTING_OBJECT = _UxGT("Yazdırma Nesnesi"); + PROGMEM Language_Str MSG_CANCEL_OBJECT = _UxGT("Nesneyi İptal Et"); + PROGMEM Language_Str MSG_CANCEL_OBJECT_N = _UxGT("Nesneyi İptal Et ="); PROGMEM Language_Str MSG_OUTAGE_RECOVERY = _UxGT("Kesinti Kurtarma"); PROGMEM Language_Str MSG_MEDIA_MENU = _UxGT("SD Karttan Yazdır"); PROGMEM Language_Str MSG_NO_MEDIA = _UxGT("SD Kart Yok!"); @@ -298,10 +363,12 @@ namespace Language_tr { PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER_SWAPF = _UxGT("S UnRet V"); PROGMEM Language_Str MSG_AUTORETRACT = _UxGT("Oto. Geri Çekme"); PROGMEM Language_Str MSG_FILAMENT_SWAP_LENGTH = _UxGT("G.Çekme Boyu"); + PROGMEM Language_Str MSG_FILAMENT_PURGE_LENGTH = _UxGT("Tasfiye uzunluğu"); PROGMEM Language_Str MSG_TOOL_CHANGE = _UxGT("Takım Değişimi"); PROGMEM Language_Str MSG_TOOL_CHANGE_ZLIFT = _UxGT("Z Yükselt"); PROGMEM Language_Str MSG_SINGLENOZZLE_PRIME_SPD = _UxGT("Birincil Hız"); PROGMEM Language_Str MSG_SINGLENOZZLE_RETRACT_SPD = _UxGT("Geri Çekme Hızı"); + PROGMEM Language_Str MSG_NOZZLE_STANDBY = _UxGT("Nozul Beklemede"); PROGMEM Language_Str MSG_FILAMENTCHANGE = _UxGT("Filaman Değiştir"); PROGMEM Language_Str MSG_FILAMENTCHANGE_E = _UxGT("Filaman Değiştir *"); PROGMEM Language_Str MSG_FILAMENTLOAD = _UxGT("Filaman Yükle"); @@ -311,29 +378,52 @@ namespace Language_tr { PROGMEM Language_Str MSG_FILAMENTUNLOAD_ALL = _UxGT("Tümünü Çıkart"); PROGMEM Language_Str MSG_ATTACH_MEDIA = _UxGT("SD Kart Başlatılıyor"); PROGMEM Language_Str MSG_CHANGE_MEDIA = _UxGT("SD Kart Değiştir"); + PROGMEM Language_Str MSG_RELEASE_MEDIA = _UxGT("SD Kart Çıkart"); PROGMEM Language_Str MSG_ZPROBE_OUT = _UxGT("Z Prob Açık. Tabla"); PROGMEM Language_Str MSG_SKEW_FACTOR = _UxGT("Çarpıklık Faktörü"); PROGMEM Language_Str MSG_BLTOUCH = _UxGT("BLTouch"); - PROGMEM Language_Str MSG_BLTOUCH_SELFTEST = _UxGT("BLTouch Self-Test"); - PROGMEM Language_Str MSG_BLTOUCH_RESET = _UxGT("Sıfırla BLTouch"); - PROGMEM Language_Str MSG_BLTOUCH_DEPLOY = _UxGT("BLTouch Aç"); - PROGMEM Language_Str MSG_BLTOUCH_STOW = _UxGT("BLTouch Kapat"); - PROGMEM Language_Str MSG_MANUAL_DEPLOY = _UxGT("Z-Prob Aç"); - PROGMEM Language_Str MSG_MANUAL_STOW = _UxGT("Z-Sensör Kapat"); - PROGMEM Language_Str MSG_HOME_FIRST = _UxGT("Sıfırla %s%s%s Önce"); + PROGMEM Language_Str MSG_BLTOUCH_SELFTEST = _UxGT("BLTouch K. Test"); + PROGMEM Language_Str MSG_BLTOUCH_RESET = _UxGT("Cmd: Reset"); + PROGMEM Language_Str MSG_BLTOUCH_STOW = _UxGT("Cmd: Kapat"); + PROGMEM Language_Str MSG_BLTOUCH_DEPLOY = _UxGT("Cmd: Aç"); + PROGMEM Language_Str MSG_BLTOUCH_SW_MODE = _UxGT("Cmd: SW-Modu"); + PROGMEM Language_Str MSG_BLTOUCH_5V_MODE = _UxGT("Cmd: 5V-Modu"); + PROGMEM Language_Str MSG_BLTOUCH_OD_MODE = _UxGT("Cmd: OD-Modu"); + PROGMEM Language_Str MSG_BLTOUCH_MODE_STORE = _UxGT("Cmd: Mode-Store"); + PROGMEM Language_Str MSG_BLTOUCH_MODE_STORE_5V = _UxGT("BLTouch 5V Ayarla"); + PROGMEM Language_Str MSG_BLTOUCH_MODE_STORE_OD = _UxGT("BLTouch OD Ayarla"); + PROGMEM Language_Str MSG_BLTOUCH_MODE_ECHO = _UxGT("Drenaj Raporu"); + PROGMEM Language_Str MSG_BLTOUCH_MODE_CHANGE = _UxGT("TEHLIKE: Kötü ayarlar hasara neden olabilir! Yine de devam edilsin mi?"); + PROGMEM Language_Str MSG_TOUCHMI_PROBE = _UxGT("TouchMI"); + PROGMEM Language_Str MSG_TOUCHMI_INIT = _UxGT("Init TouchMI"); + PROGMEM Language_Str MSG_TOUCHMI_ZTEST = _UxGT("Z Ofset Testi"); + PROGMEM Language_Str MSG_TOUCHMI_SAVE = _UxGT("Kaydet"); + PROGMEM Language_Str MSG_MANUAL_DEPLOY_TOUCHMI = _UxGT("TouchMI Aç"); + PROGMEM Language_Str MSG_MANUAL_DEPLOY = _UxGT("Z-Probe Aç"); + PROGMEM Language_Str MSG_MANUAL_STOW = _UxGT("Z-Probe Kapat"); + PROGMEM Language_Str MSG_HOME_FIRST = _UxGT("Önce %s%s%s Sıfırla"); + PROGMEM Language_Str MSG_ZPROBE_OFFSETS = _UxGT("Prob Ofsetleri"); + PROGMEM Language_Str MSG_ZPROBE_XOFFSET = _UxGT("X Prob Ofset"); + PROGMEM Language_Str MSG_ZPROBE_YOFFSET = _UxGT("Y Prob Ofset"); + PROGMEM Language_Str MSG_ZPROBE_ZOFFSET = _UxGT("Z Prob Ofset"); PROGMEM Language_Str MSG_BABYSTEP_X = _UxGT("Miniadım X"); PROGMEM Language_Str MSG_BABYSTEP_Y = _UxGT("Miniadım Y"); PROGMEM Language_Str MSG_BABYSTEP_Z = _UxGT("Miniadım Z"); + PROGMEM Language_Str MSG_BABYSTEP_TOTAL = _UxGT("Toplam"); PROGMEM Language_Str MSG_ENDSTOP_ABORT = _UxGT("Endstop iptal"); PROGMEM Language_Str MSG_HEATING_FAILED_LCD = _UxGT("Isınma başarısız"); PROGMEM Language_Str MSG_HEATING_FAILED_LCD_BED = _UxGT("Yatak Isınma Başrsız"); + PROGMEM Language_Str MSG_HEATING_FAILED_LCD_CHAMBER = _UxGT("Oda Isıtma Hatası"); PROGMEM Language_Str MSG_ERR_REDUNDANT_TEMP = _UxGT("Hata: Sıcaklık Aşımı"); PROGMEM Language_Str MSG_THERMAL_RUNAWAY = _UxGT("TERMAL PROBLEM"); PROGMEM Language_Str MSG_THERMAL_RUNAWAY_BED = _UxGT("TABLA TERMAL PROBLEM"); + PROGMEM Language_Str MSG_THERMAL_RUNAWAY_CHAMBER = _UxGT("ODA TERMAL PROBLEM"); PROGMEM Language_Str MSG_ERR_MAXTEMP = _UxGT("Hata: MAX.SICAKLIK"); PROGMEM Language_Str MSG_ERR_MINTEMP = _UxGT("Hata: MIN.SICAKLIK"); PROGMEM Language_Str MSG_ERR_MAXTEMP_BED = _UxGT("Hata: MAX.SIC. TABLA"); PROGMEM Language_Str MSG_ERR_MINTEMP_BED = _UxGT("Hata: MIN.SIC. TABLA"); + PROGMEM Language_Str MSG_ERR_MAXTEMP_CHAMBER = _UxGT("Hata: MAX.SIC ODA"); + PROGMEM Language_Str MSG_ERR_MINTEMP_CHAMBER = _UxGT("Hata: MIN.SIC ODA"); PROGMEM Language_Str MSG_ERR_Z_HOMING = _UxGT("Önce XY Sıfırla"); PROGMEM Language_Str MSG_HALTED = _UxGT("YAZICI DURDURULDU"); PROGMEM Language_Str MSG_PLEASE_RESET = _UxGT("Lütfen Resetleyin"); @@ -344,6 +434,8 @@ namespace Language_tr { PROGMEM Language_Str MSG_COOLING = _UxGT("Soğuyor..."); PROGMEM Language_Str MSG_BED_HEATING = _UxGT("Tabla Isınıyor..."); PROGMEM Language_Str MSG_BED_COOLING = _UxGT("Tabla Soğuyor..."); + PROGMEM Language_Str MSG_CHAMBER_HEATING = _UxGT("Oda Isınıyor..."); + PROGMEM Language_Str MSG_CHAMBER_COOLING = _UxGT("Oda Soğuyor..."); PROGMEM Language_Str MSG_DELTA_CALIBRATE = _UxGT("Delta Kalibrasyonu"); PROGMEM Language_Str MSG_DELTA_CALIBRATE_X = _UxGT("Ayarla X"); PROGMEM Language_Str MSG_DELTA_CALIBRATE_Y = _UxGT("Ayarla Y"); @@ -371,7 +463,6 @@ namespace Language_tr { PROGMEM Language_Str MSG_INFO_PROTOCOL = _UxGT("Protokol"); PROGMEM Language_Str MSG_CASE_LIGHT = _UxGT("Aydınlatmayı Aç"); PROGMEM Language_Str MSG_CASE_LIGHT_BRIGHTNESS = _UxGT("Aydınlatma Parlaklğı"); - PROGMEM Language_Str MSG_EXPECTED_PRINTER = _UxGT("Yanlış Yazıcı"); #if LCD_WIDTH >= 20 @@ -387,6 +478,7 @@ namespace Language_tr { PROGMEM Language_Str MSG_INFO_PRINT_LONGEST = _UxGT("En Uzun"); PROGMEM Language_Str MSG_INFO_PRINT_FILAMENT = _UxGT("Filaman"); #endif + PROGMEM Language_Str MSG_INFO_MIN_TEMP = _UxGT("Min Sıc."); PROGMEM Language_Str MSG_INFO_MAX_TEMP = _UxGT("Max Sıc."); PROGMEM Language_Str MSG_INFO_PSU = _UxGT("Güç Kaynağı"); @@ -395,7 +487,9 @@ namespace Language_tr { PROGMEM Language_Str MSG_DAC_PERCENT_Y = _UxGT("Y Sürücü %"); PROGMEM Language_Str MSG_DAC_PERCENT_Z = _UxGT("Z Sürücü %"); PROGMEM Language_Str MSG_DAC_PERCENT_E = _UxGT("E Sürücü %"); + PROGMEM Language_Str MSG_ERROR_TMC = _UxGT("TMC BAĞLANTI HATASI"); PROGMEM Language_Str MSG_DAC_EEPROM_WRITE = _UxGT("DAC EEPROM Yaz"); + PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEADER = _UxGT("FILAMAN DEGISTIR"); PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEADER_PAUSE = _UxGT("BASKI DURAKLATILDI"); PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEADER_LOAD = _UxGT("FILAMAN YüKLE"); PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEADER_UNLOAD = _UxGT("FILAMAN ÇIKART"); @@ -404,15 +498,69 @@ namespace Language_tr { PROGMEM Language_Str MSG_FILAMENT_CHANGE_OPTION_RESUME = _UxGT("Baskıyı sürdür"); PROGMEM Language_Str MSG_FILAMENT_CHANGE_NOZZLE = _UxGT(" Nozul: "); PROGMEM Language_Str MSG_RUNOUT_SENSOR = _UxGT("Runout Sensörü"); + PROGMEM Language_Str MSG_RUNOUT_DISTANCE_MM = _UxGT("Aşınma Farkı mm"); PROGMEM Language_Str MSG_LCD_HOMING_FAILED = _UxGT("Sıfırlama Başarısız"); PROGMEM Language_Str MSG_LCD_PROBING_FAILED = _UxGT("Probing Başarısız"); PROGMEM Language_Str MSG_M600_TOO_COLD = _UxGT("M600: Çok Soğuk"); + + PROGMEM Language_Str MSG_MMU2_CHOOSE_FILAMENT_HEADER = _UxGT("FILAMAN SEÇ"); + PROGMEM Language_Str MSG_MMU2_MENU = _UxGT("MMU"); + PROGMEM Language_Str MSG_MMU2_WRONG_FIRMWARE = _UxGT("MMU Yaz. Güncelle!"); + PROGMEM Language_Str MSG_MMU2_NOT_RESPONDING = _UxGT("MMU Dikkat Gerektirir."); + PROGMEM Language_Str MSG_MMU2_RESUME = _UxGT("Yaz. Devam Et"); + PROGMEM Language_Str MSG_MMU2_RESUMING = _UxGT("Sürdürülüyor..."); + PROGMEM Language_Str MSG_MMU2_LOAD_FILAMENT = _UxGT("Filaman Yükle"); + PROGMEM Language_Str MSG_MMU2_LOAD_ALL = _UxGT("Tümünü Yükle"); + PROGMEM Language_Str MSG_MMU2_LOAD_TO_NOZZLE = _UxGT("Nozula Yükle"); + PROGMEM Language_Str MSG_MMU2_EJECT_FILAMENT = _UxGT("Filaman Çıkart"); + PROGMEM Language_Str MSG_MMU2_EJECT_FILAMENT_N = _UxGT("Filaman Çıkart ~"); + PROGMEM Language_Str MSG_MMU2_UNLOAD_FILAMENT = _UxGT("Filamenti Boşalt"); + PROGMEM Language_Str MSG_MMU2_LOADING_FILAMENT = _UxGT("Fil. Yükleniyor %i..."); + PROGMEM Language_Str MSG_MMU2_EJECTING_FILAMENT = _UxGT("Fil Çıkartılıyor. ..."); + PROGMEM Language_Str MSG_MMU2_UNLOADING_FILAMENT = _UxGT("Fil. Boşaltılıyor...."); + PROGMEM Language_Str MSG_MMU2_ALL = _UxGT("Tümü"); + PROGMEM Language_Str MSG_MMU2_FILAMENT_N = _UxGT("Filaman ~"); + PROGMEM Language_Str MSG_MMU2_RESET = _UxGT("MMU Resetle"); + PROGMEM Language_Str MSG_MMU2_RESETTING = _UxGT("MMU Resetleniyot..."); + PROGMEM Language_Str MSG_MMU2_EJECT_RECOVER = _UxGT("Kaldır, tıkla"); + + PROGMEM Language_Str MSG_MIX = _UxGT("Karışım"); + PROGMEM Language_Str MSG_MIX_COMPONENT_N = _UxGT("Bileşen ="); + PROGMEM Language_Str MSG_MIXER = _UxGT("Karıştırıcı"); + PROGMEM Language_Str MSG_GRADIENT = _UxGT("Gradyan"); + PROGMEM Language_Str MSG_FULL_GRADIENT = _UxGT("Tam Gradyan"); + PROGMEM Language_Str MSG_TOGGLE_MIX = _UxGT("Karışım Geçişi"); + PROGMEM Language_Str MSG_CYCLE_MIX = _UxGT("Döngü Karışımı"); + PROGMEM Language_Str MSG_GRADIENT_MIX = _UxGT("Gradyan Karışımı"); + PROGMEM Language_Str MSG_REVERSE_GRADIENT = _UxGT("Ters Gradyan"); + PROGMEM Language_Str MSG_ACTIVE_VTOOL = _UxGT("Aktif V-tool"); + PROGMEM Language_Str MSG_START_VTOOL = _UxGT("Başlat V-tool"); + PROGMEM Language_Str MSG_END_VTOOL = _UxGT(" Bitir V-tool"); + PROGMEM Language_Str MSG_GRADIENT_ALIAS = _UxGT("Alias V-tool"); + PROGMEM Language_Str MSG_RESET_VTOOLS = _UxGT("Reset V-tools"); + PROGMEM Language_Str MSG_COMMIT_VTOOL = _UxGT("V-tool Karışıö Yap"); + PROGMEM Language_Str MSG_VTOOLS_RESET = _UxGT("V-tools Resetlendi"); + PROGMEM Language_Str MSG_START_Z = _UxGT("Başlat Z:"); + PROGMEM Language_Str MSG_END_Z = _UxGT(" Bitir Z:"); + + PROGMEM Language_Str MSG_GAMES = _UxGT("Oyunlar"); + PROGMEM Language_Str MSG_BRICKOUT = _UxGT("Brickout"); + PROGMEM Language_Str MSG_INVADERS = _UxGT("Invaders"); + PROGMEM Language_Str MSG_SNAKE = _UxGT("Sn4k3"); + PROGMEM Language_Str MSG_MAZE = _UxGT("Maze"); + + #define MSG_1_LINE(A) A "\0" "\0" + #define MSG_2_LINE(A,B) A "\0" B "\0" + #define MSG_3_LINE(A,B,C) A "\0" B "\0" C + // - // Filament Değiştirme ekranları, 4 satırlı bir ekranda 3 satıra kadar gösterilir + // Filament Değişim ekranları 4 satırlı ekranda 3 satıra kadar gösterilir // ...veya 3 satırlı ekranda 2 satıra kadar + // #if LCD_HEIGHT >= 4 - // Up to 3 lines allowed + PROGMEM Language_Str MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_2_LINE("Baskıya devam etmek", "için Butona bas")); + PROGMEM Language_Str MSG_PAUSE_PRINT_INIT = _UxGT(MSG_1_LINE("Park Ediliyor...")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_3_LINE("Filaman değişimi", "için başlama", "bekleniyor")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_3_LINE("Filamanı yükle", "ve devam için", "tuşa bas...")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_2_LINE("Nozulü Isıtmak için", "Butona Bas.")); @@ -422,9 +570,9 @@ namespace Language_tr { PROGMEM Language_Str MSG_FILAMENT_CHANGE_PURGE = _UxGT(MSG_2_LINE("Filaman Temizlemesi", "için bekle")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_CONT_PURGE = _UxGT(MSG_2_LINE("Filaman Temizlemesi", "bitirmek için tıkla")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_2_LINE("Baskının devam ", "etmesi için bekle")); - #else // LCD_HEIGHT < 4 - // Up to 2 lines allowed + #else PROGMEM Language_Str MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_1_LINE("Sürdürmek İçin Tıkla")); + PROGMEM Language_Str MSG_PAUSE_PRINT_INIT = _UxGT(MSG_1_LINE("Park Ediliyor...")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_1_LINE("Lütfen bekleyiniz...")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_1_LINE("Yükle ve bas")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_1_LINE("Isıtmak için Tıkla")); @@ -434,5 +582,28 @@ namespace Language_tr { PROGMEM Language_Str MSG_FILAMENT_CHANGE_PURGE = _UxGT(MSG_1_LINE("Temizleniyor...")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_CONT_PURGE = _UxGT(MSG_1_LINE("Bitirmek için Tıkla")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_1_LINE("Sürdürülüyor...")); - #endif // LCD_HEIGHT < 4 + #endif + PROGMEM Language_Str MSG_TMC_DRIVERS = _UxGT("TMC Sürücüleri"); + PROGMEM Language_Str MSG_TMC_CURRENT = _UxGT("Sürücü Akımı"); + PROGMEM Language_Str MSG_TMC_HYBRID_THRS = _UxGT("Hibrit Eşiği"); + PROGMEM Language_Str MSG_TMC_HOMING_THRS = _UxGT("Sensörsüz Sıfırlama"); + PROGMEM Language_Str MSG_TMC_STEPPING_MODE = _UxGT("Adım Modu"); + PROGMEM Language_Str MSG_TMC_STEALTH_ENABLED = _UxGT("StealthChop Aktif"); + PROGMEM Language_Str MSG_SERVICE_RESET = _UxGT("Resetle"); + PROGMEM Language_Str MSG_SERVICE_IN = _UxGT(" içinde:"); + PROGMEM Language_Str MSG_BACKLASH = _UxGT("Ters Tepki"); + PROGMEM Language_Str MSG_BACKLASH_A = LCD_STR_A; + PROGMEM Language_Str MSG_BACKLASH_B = LCD_STR_B; + PROGMEM Language_Str MSG_BACKLASH_C = LCD_STR_C; + PROGMEM Language_Str MSG_BACKLASH_CORRECTION = _UxGT("Düzeltme"); + PROGMEM Language_Str MSG_BACKLASH_SMOOTHING = _UxGT("Yumuşatma"); } + +#if FAN_COUNT == 1 + #define MSG_FIRST_FAN_SPEED MSG_FAN_SPEED + #define MSG_FIRST_EXTRA_FAN_SPEED MSG_EXTRA_FAN_SPEED +#else + #define MSG_FIRST_FAN_SPEED MSG_FAN_SPEED_N + #define MSG_FIRST_EXTRA_FAN_SPEED MSG_EXTRA_FAN_SPEED_N +#endif + diff --git a/Marlin/src/lcd/language/language_zh_TW.h b/Marlin/src/lcd/language/language_zh_TW.h index d0871f0e46..06b19440f2 100644 --- a/Marlin/src/lcd/language/language_zh_TW.h +++ b/Marlin/src/lcd/language/language_zh_TW.h @@ -35,11 +35,23 @@ namespace Language_zh_TW { PROGMEM Language_Str LANGUAGE = _UxGT("Traditional Chinese"); PROGMEM Language_Str WELCOME_MSG = MACHINE_NAME _UxGT("已就緒."); //" ready." - PROGMEM Language_Str MSG_BACK = _UxGT("返回"); // ”Back“ + PROGMEM Language_Str MSG_MARLIN = _UxGT("Marlin"); + PROGMEM Language_Str MSG_YES = _UxGT("是"); //"YES" + PROGMEM Language_Str MSG_NO = _UxGT("否"); //"NO" + PROGMEM Language_Str MSG_BACK = _UxGT("返回"); // "Back" + PROGMEM Language_Str MSG_MEDIA_ABORTING = _UxGT("正在中止..."); //"Aborting..." PROGMEM Language_Str MSG_MEDIA_INSERTED = _UxGT("記憶卡已插入"); //"Card inserted" PROGMEM Language_Str MSG_MEDIA_REMOVED = _UxGT("記憶卡被拔出"); //"Card removed" + PROGMEM Language_Str MSG_MEDIA_RELEASED = _UxGT("記憶卡被釋放"); //"Media Released" + PROGMEM Language_Str MSG_MEDIA_WAITING = _UxGT("等待記憶卡"); //"Waiting for media" + PROGMEM Language_Str MSG_MEDIA_READ_ERROR = _UxGT("記憶卡讀取錯誤"); //"Media read error" + PROGMEM Language_Str MSG_MEDIA_USB_REMOVED = _UxGT("USB裝置已移除"); //"USB device removed" + PROGMEM Language_Str MSG_MEDIA_USB_FAILED = _UxGT("USB啟動失敗"); //"USB start failed" PROGMEM Language_Str MSG_LCD_ENDSTOPS = _UxGT("擋塊"); //"Endstops" // Max length 8 characters + PROGMEM Language_Str MSG_LCD_SOFT_ENDSTOPS = _UxGT("軟體擋塊"); //"Soft Endstops" PROGMEM Language_Str MSG_MAIN = _UxGT("主選單"); //"Main" + PROGMEM Language_Str MSG_ADVANCED_SETTINGS = _UxGT("進階設置"); //"Advanced Settings" + PROGMEM Language_Str MSG_CONFIGURATION = _UxGT("設置"); //Configuration PROGMEM Language_Str MSG_AUTOSTART = _UxGT("自動開始"); //"Autostart" PROGMEM Language_Str MSG_DISABLE_STEPPERS = _UxGT("關閉步進馬達"); //"Disable steppers" PROGMEM Language_Str MSG_DEBUG_MENU = _UxGT("除錯選單"); // "Debug Menu" @@ -48,6 +60,7 @@ namespace Language_zh_TW { PROGMEM Language_Str MSG_AUTO_HOME_X = _UxGT("回X原點"); //"Home X" PROGMEM Language_Str MSG_AUTO_HOME_Y = _UxGT("回Y原點"); //"Home Y" PROGMEM Language_Str MSG_AUTO_HOME_Z = _UxGT("回Z原點"); //"Home Z" + PROGMEM Language_Str MSG_AUTO_Z_ALIGN = _UxGT("自動Z對齊"); //"Auto Z-Align" PROGMEM Language_Str MSG_LEVEL_BED_HOMING = _UxGT("平台調平XYZ歸原點"); //"Homing XYZ" PROGMEM Language_Str MSG_LEVEL_BED_WAITING = _UxGT("單擊開始熱床調平"); //"Click to Begin" PROGMEM Language_Str MSG_LEVEL_BED_NEXT_POINT = _UxGT("下個熱床調平點"); //"Next Point" @@ -70,7 +83,17 @@ namespace Language_zh_TW { PROGMEM Language_Str MSG_PREHEAT_2_ALL = _UxGT("預熱 ") PREHEAT_2_LABEL _UxGT(" 全部"); //MSG_PREHEAT_2 " All" PROGMEM Language_Str MSG_PREHEAT_2_BEDONLY = _UxGT("預熱 ") PREHEAT_2_LABEL _UxGT(" 熱床"); //MSG_PREHEAT_2 " Bed" PROGMEM Language_Str MSG_PREHEAT_2_SETTINGS = _UxGT("預熱 ") PREHEAT_2_LABEL _UxGT(" 設置"); //MSG_PREHEAT_2 " conf" + PROGMEM Language_Str MSG_PREHEAT_CUSTOM = _UxGT("自定預熱"); //"Preheat Custom" PROGMEM Language_Str MSG_COOLDOWN = _UxGT("降溫"); //"Cooldown" + PROGMEM Language_Str MSG_LASER_MENU = _UxGT("激光控制"); //"Laser Control" + PROGMEM Language_Str MSG_LASER_OFF = _UxGT("激光 關"); //"Laser Off" + PROGMEM Language_Str MSG_LASER_ON = _UxGT("激光 開"); //"Laser On" + PROGMEM Language_Str MSG_LASER_POWER = _UxGT("激光電源"); //"Laser Power" + PROGMEM Language_Str MSG_SPINDLE_MENU = _UxGT("主軸控告制"); //"Spindle Control" + PROGMEM Language_Str MSG_SPINDLE_OFF = _UxGT("主軸 關"); //"Spindle Off" + PROGMEM Language_Str MSG_SPINDLE_ON = _UxGT("主軸 開"); //"Spindle On" + PROGMEM Language_Str MSG_SPINDLE_POWER = _UxGT("主軸電源"); //"Spindle Power" + PROGMEM Language_Str MSG_SPINDLE_REVERSE = _UxGT("主軸反轉"); //"Spindle Reverse" PROGMEM Language_Str MSG_SWITCH_PS_ON = _UxGT("電源打開"); //"Switch power on" PROGMEM Language_Str MSG_SWITCH_PS_OFF = _UxGT("電源關閉"); //"Switch power off" PROGMEM Language_Str MSG_EXTRUDE = _UxGT("擠出"); //"Extrude" @@ -79,15 +102,31 @@ namespace Language_zh_TW { PROGMEM Language_Str MSG_BED_LEVELING = _UxGT("調平熱床"); //"Bed leveling" PROGMEM Language_Str MSG_LEVEL_BED = _UxGT("調平熱床"); //"Level bed" PROGMEM Language_Str MSG_LEVEL_CORNERS = _UxGT("調平邊角"); // "Level corners" - PROGMEM Language_Str MSG_NEXT_CORNER = _UxGT("下個邊角"); // "Next corner" + PROGMEM Language_Str MSG_MESH_EDITOR = _UxGT("網格編輯器"); //"Mesh Editor" PROGMEM Language_Str MSG_EDIT_MESH = _UxGT("編輯網格"); // "Edit Mesh" PROGMEM Language_Str MSG_EDITING_STOPPED = _UxGT("網格編輯已停止"); // "Mesh Editing Stopped" - PROGMEM Language_Str MSG_USER_MENU = _UxGT("客制命令"); // "Custom Commands" - + PROGMEM Language_Str MSG_PROBING_MESH = _UxGT("探測點"); //"Probing Point" + PROGMEM Language_Str MSG_MESH_X = _UxGT("索引 X"); //"Index X" + PROGMEM Language_Str MSG_MESH_Y = _UxGT("索引 Y"); //"Index Y" + PROGMEM Language_Str MSG_MESH_EDIT_Z = _UxGT("Z 值"); //"Z Value" + PROGMEM Language_Str MSG_USER_MENU = _UxGT("自定命令"); // "Custom Commands" + PROGMEM Language_Str MSG_M48_TEST = _UxGT("M48 探測測試"); //"M48 Probe Test" + PROGMEM Language_Str MSG_M48_POINT = _UxGT("M48 探測點"); //"M48 Point" + PROGMEM Language_Str MSG_M48_DEVIATION = _UxGT("偏差"); //"Deviation" + PROGMEM Language_Str MSG_IDEX_MENU = _UxGT("IDEX Mode"); + PROGMEM Language_Str MSG_OFFSETS_MENU = _UxGT("Tool Offsets"); + PROGMEM Language_Str MSG_IDEX_MODE_AUTOPARK = _UxGT("Auto-Park"); + PROGMEM Language_Str MSG_IDEX_MODE_DUPLICATE = _UxGT("Duplication"); + PROGMEM Language_Str MSG_IDEX_MODE_MIRRORED_COPY = _UxGT("Mirrored Copy"); + PROGMEM Language_Str MSG_IDEX_MODE_FULL_CTRL = _UxGT("Full Control"); + PROGMEM Language_Str MSG_HOTEND_OFFSET_X = _UxGT("2nd Nozzle X"); + PROGMEM Language_Str MSG_HOTEND_OFFSET_Y = _UxGT("2nd Nozzle Y"); + PROGMEM Language_Str MSG_HOTEND_OFFSET_Z = _UxGT("2nd Nozzle Z"); PROGMEM Language_Str MSG_UBL_DOING_G29 = _UxGT("執行G29"); // "Doing G29" PROGMEM Language_Str MSG_UBL_TOOLS = _UxGT("UBL工具"); // "UBL Tools" PROGMEM Language_Str MSG_UBL_LEVEL_BED = _UxGT("統一熱床調平(UBL)"); // "Unified Bed Leveling" + PROGMEM Language_Str MSG_LCD_TILTING_MESH = _UxGT("傾斜點"); //"Tilting Point" PROGMEM Language_Str MSG_UBL_MANUAL_MESH = _UxGT("手工建網"); // "Manually Build Mesh" PROGMEM Language_Str MSG_UBL_BC_INSERT = _UxGT("放置墊片並測量"); // "Place shim & measure" PROGMEM Language_Str MSG_UBL_BC_INSERT2 = _UxGT("測量"); // "Measure" @@ -95,8 +134,10 @@ namespace Language_zh_TW { PROGMEM Language_Str MSG_UBL_MOVING_TO_NEXT = _UxGT("移動到下一個"); // "Moving to next" PROGMEM Language_Str MSG_UBL_ACTIVATE_MESH = _UxGT("啟動UBL"); // "Activate UBL" PROGMEM Language_Str MSG_UBL_DEACTIVATE_MESH = _UxGT("關閉UBL"); // "Deactivate UBL" - PROGMEM Language_Str MSG_UBL_SET_TEMP_BED = _UxGT("設置熱床溫度"); // "Bed Temp" - PROGMEM Language_Str MSG_UBL_SET_TEMP_HOTEND = _UxGT("熱端溫度"); // "Hotend Temp" + PROGMEM Language_Str MSG_UBL_SET_TEMP_BED = _UxGT("置設熱床溫度"); // "Bed Temp" + PROGMEM Language_Str MSG_UBL_BED_TEMP_CUSTOM = _UxGT("置設熱床溫度"); //"Bed Temp") + PROGMEM Language_Str MSG_UBL_SET_TEMP_HOTEND = _UxGT("置設噴嘴溫度"); // "Hotend Temp" + PROGMEM Language_Str MSG_UBL_HOTEND_TEMP_CUSTOM = _UxGT("熱端溫度"); //"Hotend Temp" PROGMEM Language_Str MSG_UBL_MESH_EDIT = _UxGT("網格編輯"); // "Mesh Edit" PROGMEM Language_Str MSG_UBL_EDIT_CUSTOM_MESH = _UxGT("編輯客戶網格"); // "Edit Custom Mesh" PROGMEM Language_Str MSG_UBL_FINE_TUNE_MESH = _UxGT("細調網格"); // "Fine Tuning Mesh" @@ -112,6 +153,13 @@ namespace Language_zh_TW { PROGMEM Language_Str MSG_UBL_VALIDATE_MESH_M1 = _UxGT("批准 ") PREHEAT_1_LABEL _UxGT(" 網格"); // "Validate PREHEAT_1_LABEL Mesh" PROGMEM Language_Str MSG_UBL_VALIDATE_MESH_M2 = _UxGT("批准 ") PREHEAT_2_LABEL _UxGT(" 網格"); // "Validate PREHEAT_2_LABEL Mesh" PROGMEM Language_Str MSG_UBL_VALIDATE_CUSTOM_MESH = _UxGT("批准客戶網格"); // "Validate Custom Mesh" + PROGMEM Language_Str MSG_G26_HEATING_BED = _UxGT("G26 加熱熱床"); //"G26 Heating Bed" + PROGMEM Language_Str MSG_G26_HEATING_NOZZLE = _UxGT("G26 加熱噴嘴"); //"G26 Heating Nozzle" + PROGMEM Language_Str MSG_G26_MANUAL_PRIME = _UxGT("手動填裝"); //"Manual priming..." + PROGMEM Language_Str MSG_G26_FIXED_LENGTH = _UxGT("固定距離填裝"); //"Fixed Length Prime" + PROGMEM Language_Str MSG_G26_PRIME_DONE = _UxGT("完成填裝"); //"Done Priming" + PROGMEM Language_Str MSG_G26_CANCELED = _UxGT("G26已取消"); //"G26 Canceled" + PROGMEM Language_Str MSG_G26_LEAVING = _UxGT("離開 G26"); //"Leaving G26" PROGMEM Language_Str MSG_UBL_CONTINUE_MESH = _UxGT("繼續熱床網格"); // "Continue Bed Mesh" PROGMEM Language_Str MSG_UBL_MESH_LEVELING = _UxGT("網格調平"); // "Mesh Leveling" PROGMEM Language_Str MSG_UBL_3POINT_MESH_LEVELING = _UxGT("三點調平"); // "3-Point Leveling" @@ -141,6 +189,7 @@ namespace Language_zh_TW { PROGMEM Language_Str MSG_UBL_NO_STORAGE = _UxGT("沒有存儲"); // "No storage" PROGMEM Language_Str MSG_UBL_SAVE_ERROR = _UxGT("錯誤: UBL保存"); // "Err: UBL Save" PROGMEM Language_Str MSG_UBL_RESTORE_ERROR = _UxGT("錯誤: UBL還原"); // "Err: UBL Restore" + PROGMEM Language_Str MSG_UBL_Z_OFFSET = _UxGT("Z-偏移:"); //"Z-Offset: " PROGMEM Language_Str MSG_UBL_Z_OFFSET_STOPPED = _UxGT("Z偏移已停止"); // "Z-Offset Stopped" PROGMEM Language_Str MSG_UBL_STEP_BY_STEP_MENU = _UxGT("一步步UBL"); // "Step-By-Step UBL" PROGMEM Language_Str MSG_UBL_1_BUILD_COLD_MESH = _UxGT("1. 創設冷網格"); @@ -162,7 +211,7 @@ namespace Language_zh_TW { PROGMEM Language_Str MSG_SET_LEDS_INDIGO = _UxGT("青"); // "Indigo") PROGMEM Language_Str MSG_SET_LEDS_VIOLET = _UxGT("紫"); // "Violet") PROGMEM Language_Str MSG_SET_LEDS_WHITE = _UxGT("白"); // "White") - PROGMEM Language_Str MSG_SET_LEDS_DEFAULT = _UxGT("缺省"); // "Default") + PROGMEM Language_Str MSG_SET_LEDS_DEFAULT = _UxGT("復歸"); // "Default") PROGMEM Language_Str MSG_CUSTOM_LEDS = _UxGT("定制燈"); // "Custom Lights") PROGMEM Language_Str MSG_INTENSITY_R = _UxGT("紅飽和度"); // "Red Intensity") PROGMEM Language_Str MSG_INTENSITY_G = _UxGT("綠飽和度"); // "Green Intensity") @@ -176,7 +225,8 @@ namespace Language_zh_TW { PROGMEM Language_Str MSG_MOVE_Y = _UxGT("移動Y"); //"Move Y" PROGMEM Language_Str MSG_MOVE_Z = _UxGT("移動Z"); //"Move Z" PROGMEM Language_Str MSG_MOVE_E = _UxGT("擠出機"); //"Extruder" - PROGMEM Language_Str MSG_MOVE_EN = _UxGT("擠出機 *"); + PROGMEM Language_Str MSG_MOVE_EN = _UxGT("擠出機 *"); //"Extruder *" + PROGMEM Language_Str MSG_HOTEND_TOO_COLD = _UxGT("噴嘴溫度不夠"); //"Hotend too cold" PROGMEM Language_Str MSG_MOVE_Z_DIST = _UxGT("移動 %s mm"); //"Move 0.025mm" PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("移動 0.1 mm"); //"Move 0.1mm" PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("移動 1 mm"); //"Move 1mm" @@ -186,10 +236,12 @@ namespace Language_zh_TW { PROGMEM Language_Str MSG_NOZZLE = " " LCD_STR_THERMOMETER _UxGT(" 噴嘴"); //"Nozzle" 噴嘴 PROGMEM Language_Str MSG_NOZZLE_N = " " LCD_STR_THERMOMETER _UxGT(" 噴嘴 ~"); PROGMEM Language_Str MSG_BED = " " LCD_STR_THERMOMETER _UxGT(" 熱床"); //"Bed" + PROGMEM Language_Str MSG_CHAMBER = _UxGT("Enclosure"); PROGMEM Language_Str MSG_FAN_SPEED = _UxGT("風扇速率"); //"Fan speed" - PROGMEM Language_Str MSG_FAN_SPEED_N = _UxGT("風扇速率 ~"); + PROGMEM Language_Str MSG_FAN_SPEED_N = _UxGT("風扇速率 ="); + PROGMEM Language_Str MSG_STORED_FAN_N = _UxGT("Stored Fan ="); PROGMEM Language_Str MSG_EXTRA_FAN_SPEED = _UxGT("額外風扇速率"); // "Extra fan speed" - PROGMEM Language_Str MSG_EXTRA_FAN_SPEED_N = _UxGT("額外風扇速率 ~"); + PROGMEM Language_Str MSG_EXTRA_FAN_SPEED_N = _UxGT("額外風扇速率 ="); PROGMEM Language_Str MSG_FLOW = _UxGT("擠出速率"); PROGMEM Language_Str MSG_FLOW_N = _UxGT("擠出速率 ~"); //"Flow" PROGMEM Language_Str MSG_CONTROL = _UxGT("控制"); //"Control" @@ -197,8 +249,20 @@ namespace Language_zh_TW { PROGMEM Language_Str MSG_MAX = " " LCD_STR_THERMOMETER _UxGT(" 最大"); //" " LCD_STR_THERMOMETER " Max" PROGMEM Language_Str MSG_FACTOR = " " LCD_STR_THERMOMETER _UxGT(" 系數"); //" " LCD_STR_THERMOMETER " Fact" PROGMEM Language_Str MSG_AUTOTEMP = _UxGT("自動控溫"); //"Autotemp" - PROGMEM Language_Str MSG_LCD_ON = _UxGT("開"); //"On" - PROGMEM Language_Str MSG_LCD_OFF = _UxGT("關"); //"Off" + PROGMEM Language_Str MSG_LCD_ON = _UxGT("開 "); //"On" + PROGMEM Language_Str MSG_LCD_OFF = _UxGT("關 "); //"Off" + PROGMEM Language_Str MSG_PID_AUTOTUNE = _UxGT("PID Autotune"); + PROGMEM Language_Str MSG_PID_AUTOTUNE_E = _UxGT("PID Autotune *"); + PROGMEM Language_Str MSG_PID_P = _UxGT("PID-P"); //"PID-P" + PROGMEM Language_Str MSG_PID_P_E = _UxGT("PID-P *"); + PROGMEM Language_Str MSG_PID_I = _UxGT("PID-I"); //"PID-I" + PROGMEM Language_Str MSG_PID_I_E = _UxGT("PID-I *"); + PROGMEM Language_Str MSG_PID_D = _UxGT("PID-D"); //"PID-D" + PROGMEM Language_Str MSG_PID_D_E = _UxGT("PID-D *"); + PROGMEM Language_Str MSG_PID_C = _UxGT("PID-C"); //"PID-C" + PROGMEM Language_Str MSG_PID_C_E = _UxGT("PID-C *"); + PROGMEM Language_Str MSG_PID_F = _UxGT("PID-F"); //"PID-F" + PROGMEM Language_Str MSG_PID_F_E = _UxGT("PID-F *"); PROGMEM Language_Str MSG_SELECT = _UxGT("選擇"); //"Select" PROGMEM Language_Str MSG_SELECT_E = _UxGT("選擇 *"); PROGMEM Language_Str MSG_ACC = _UxGT("加速度"); //"Accel" acceleration @@ -207,6 +271,7 @@ namespace Language_zh_TW { PROGMEM Language_Str MSG_VB_JERK = _UxGT("軸抖動速率") LCD_STR_B; //"Vb-jerk" PROGMEM Language_Str MSG_VC_JERK = _UxGT("軸抖動速率") LCD_STR_C; //"Vc-jerk" PROGMEM Language_Str MSG_VE_JERK = _UxGT("擠出機抖動速率"); //"Ve-jerk" + PROGMEM Language_Str MSG_JUNCTION_DEVIATION = _UxGT("Junction Dev"); PROGMEM Language_Str MSG_VELOCITY = _UxGT("速度"); // "Velocity" PROGMEM Language_Str MSG_VMAX_A = _UxGT("最大進料速率") LCD_STR_A; //"Vmax " max_feedrate_mm_s PROGMEM Language_Str MSG_VMAX_B = _UxGT("最大進料速率") LCD_STR_B; @@ -237,23 +302,45 @@ namespace Language_zh_TW { PROGMEM Language_Str MSG_FILAMENT_DIAM_E = _UxGT("絲料直徑 *"); PROGMEM Language_Str MSG_FILAMENT_UNLOAD = _UxGT("卸載 mm"); // "Unload mm" PROGMEM Language_Str MSG_FILAMENT_LOAD = _UxGT("装載 mm"); // "Load mm" + PROGMEM Language_Str MSG_ADVANCE_K = _UxGT("Advance K"); + PROGMEM Language_Str MSG_ADVANCE_K_E = _UxGT("Advance K *"); PROGMEM Language_Str MSG_CONTRAST = _UxGT("LCD對比度"); //"LCD contrast" PROGMEM Language_Str MSG_STORE_EEPROM = _UxGT("保存設置"); //"Store memory" PROGMEM Language_Str MSG_LOAD_EEPROM = _UxGT("載入設置"); //"Load memory" - PROGMEM Language_Str MSG_RESTORE_DEFAULTS = _UxGT("恢復安全值"); //"Restore Defaults" + PROGMEM Language_Str MSG_RESTORE_DEFAULTS = _UxGT("恢復安全值"); //"Restore failsafe" PROGMEM Language_Str MSG_INIT_EEPROM = _UxGT("初始化設置"); // "Initialize EEPROM" - PROGMEM Language_Str MSG_REFRESH = LCD_STR_REFRESH _UxGT("刷新"); //"Refresh" + PROGMEM Language_Str MSG_ERR_EEPROM_CRC = _UxGT("錯誤: EEPROM CRC"); //"Err: EEPROM CRC" + PROGMEM Language_Str MSG_ERR_EEPROM_INDEX = _UxGT("錯誤: EEPROM Index"); //"Err: EEPROM Index" + PROGMEM Language_Str MSG_ERR_EEPROM_VERSION = _UxGT("錯誤: EEPROM Version"); //"EEPROM Version" + PROGMEM Language_Str MSG_MEDIA_UPDATE = _UxGT("媒體更新"); //"Media Update" + PROGMEM Language_Str MSG_RESET_PRINTER = _UxGT("重置打印機"); //"Reset Printer + PROGMEM Language_Str MSG_REFRESH = _UxGT("刷新"); //"Refresh" PROGMEM Language_Str MSG_INFO_SCREEN = _UxGT("資訊界面"); //"Info screen" PROGMEM Language_Str MSG_PREPARE = _UxGT("準備"); //"Prepare" PROGMEM Language_Str MSG_TUNE = _UxGT("調整"); //"Tune" + PROGMEM Language_Str MSG_START_PRINT = _UxGT("開始列印"); //"Start Print" + PROGMEM Language_Str MSG_BUTTON_NEXT = _UxGT("下一個"); //"Next" + PROGMEM Language_Str MSG_BUTTON_INIT = _UxGT("初始 "); //"Init" + PROGMEM Language_Str MSG_BUTTON_STOP = _UxGT("停止 "); //"Stop" + PROGMEM Language_Str MSG_BUTTON_PRINT = _UxGT("列印 "); //"Print" + PROGMEM Language_Str MSG_BUTTON_RESET = _UxGT("復歸 "); //"Reset" + PROGMEM Language_Str MSG_BUTTON_CANCEL = _UxGT("放棄 "); //"Cancel" + PROGMEM Language_Str MSG_BUTTON_DONE = _UxGT("確認 "); //"Done" + PROGMEM Language_Str MSG_BUTTON_BACK = _UxGT("返回 "); //"Back" + PROGMEM Language_Str MSG_BUTTON_PROCEED = _UxGT("繼續 "); //"Proceed" PROGMEM Language_Str MSG_PAUSE_PRINT = _UxGT("暫停列印"); //"Pause print" PROGMEM Language_Str MSG_RESUME_PRINT = _UxGT("恢復列印"); //"Resume print" PROGMEM Language_Str MSG_STOP_PRINT = _UxGT("停止列印"); //"Stop print" + PROGMEM Language_Str MSG_PRINTING_OBJECT = _UxGT("列印物件"); //"Printing Object" + PROGMEM Language_Str MSG_CANCEL_OBJECT = _UxGT("中止物件"); //"Cancel Object" + PROGMEM Language_Str MSG_CANCEL_OBJECT_N = _UxGT("中止物件 ="); //"Cancel Object =" + PROGMEM Language_Str MSG_OUTAGE_RECOVERY = _UxGT("中斷恢復"); //"Outage Recovery" PROGMEM Language_Str MSG_MEDIA_MENU = _UxGT("從記憶卡上列印"); //"Print from SD" PROGMEM Language_Str MSG_NO_MEDIA = _UxGT("無記憶卡"); //"No SD card" PROGMEM Language_Str MSG_DWELL = _UxGT("休眠 ..."); //"Sleep..." PROGMEM Language_Str MSG_USERWAIT = _UxGT("點擊繼續 ..."); //"Click to resume..." PROGMEM Language_Str MSG_PRINT_PAUSED = _UxGT("列印已暫停"); // "Print paused" + PROGMEM Language_Str MSG_PRINTING = _UxGT("列印中 ..."); //"Printing..." PROGMEM Language_Str MSG_PRINT_ABORTED = _UxGT("已取消列印"); //"Print aborted" PROGMEM Language_Str MSG_NO_MOVE = _UxGT("無移動"); //"No move." PROGMEM Language_Str MSG_KILLED = _UxGT("已砍掉"); //"KILLED. " @@ -267,6 +354,13 @@ namespace Language_zh_TW { PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVERF = _UxGT("回縮恢復後進料速率mm/s"); //"UnRet V" retract_recover_feedrate_mm_s, feedrate for recovering from retraction (mm/s) PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER_SWAPF = _UxGT("S UnRet V"); // "S UnRet V" PROGMEM Language_Str MSG_AUTORETRACT = _UxGT("自動回縮"); //"AutoRetr." autoretract_enabled, + PROGMEM Language_Str MSG_FILAMENT_SWAP_LENGTH = _UxGT("交換長度"); //"Swap Length" + PROGMEM Language_Str MSG_FILAMENT_PURGE_LENGTH = _UxGT("清除長度"); //"Purge Length" + PROGMEM Language_Str MSG_TOOL_CHANGE = _UxGT("交換工具"); //"Tool Change" + PROGMEM Language_Str MSG_TOOL_CHANGE_ZLIFT = _UxGT("Z軸提昇"); //"Z Raise" + PROGMEM Language_Str MSG_SINGLENOZZLE_PRIME_SPD = _UxGT("最高速度"); //"Prime Speed" + PROGMEM Language_Str MSG_SINGLENOZZLE_RETRACT_SPD = _UxGT("收回速度"); //"Retract Speed" + PROGMEM Language_Str MSG_NOZZLE_STANDBY = _UxGT("噴嘴待機"); //"Nozzle Standby" PROGMEM Language_Str MSG_FILAMENTCHANGE = _UxGT("更換絲料"); //"Change filament" PROGMEM Language_Str MSG_FILAMENTCHANGE_E = _UxGT("更換絲料 *"); PROGMEM Language_Str MSG_FILAMENTLOAD = _UxGT("裝載絲料"); // "Load filament" @@ -274,28 +368,55 @@ namespace Language_zh_TW { PROGMEM Language_Str MSG_FILAMENTUNLOAD = _UxGT("卸載絲料"); // "Unload filament" PROGMEM Language_Str MSG_FILAMENTUNLOAD_E = _UxGT("卸載絲料 *"); // "Unload filament" PROGMEM Language_Str MSG_FILAMENTUNLOAD_ALL = _UxGT("卸載全部"); // "Unload All" - PROGMEM Language_Str MSG_ATTACH_MEDIA = _UxGT("初始化記憶卡"); //"Init. SD card" + PROGMEM Language_Str MSG_INIT_MEDIA = _UxGT("初始化記憶卡"); //"Init. SD card" + PROGMEM Language_Str MSG_ATTACH_MEDIA = _UxGT("連接記憶卡"); //"Attach Media PROGMEM Language_Str MSG_CHANGE_MEDIA = _UxGT("更換記憶卡"); //"Change SD card" + PROGMEM Language_Str MSG_RELEASE_MEDIA = _UxGT("釋放媒體"); //"Release Media" PROGMEM Language_Str MSG_ZPROBE_OUT = _UxGT("Z探針在熱床之外"); //"Z probe out. bed" Z probe is not within the physical limits PROGMEM Language_Str MSG_SKEW_FACTOR = _UxGT("偏斜因數"); // "Skew Factor" PROGMEM Language_Str MSG_BLTOUCH = _UxGT("BLTouch"); // "BLTouch" PROGMEM Language_Str MSG_BLTOUCH_SELFTEST = _UxGT("BLTouch 自檢"); // "BLTouch Self-Test" PROGMEM Language_Str MSG_BLTOUCH_RESET = _UxGT("重置BLTouch"); // "Reset BLTouch" - PROGMEM Language_Str MSG_BLTOUCH_DEPLOY = _UxGT("部署BLTouch"); // "Deploy BLTouch" PROGMEM Language_Str MSG_BLTOUCH_STOW = _UxGT("裝載BLTouch"); // "Stow BLTouch" + PROGMEM Language_Str MSG_BLTOUCH_DEPLOY = _UxGT("部署BLTouch"); // "Deploy BLTouch" + PROGMEM Language_Str MSG_BLTOUCH_SW_MODE = _UxGT("Cmd: SW-Mode"); + PROGMEM Language_Str MSG_BLTOUCH_5V_MODE = _UxGT("Cmd: 5V-Mode"); + PROGMEM Language_Str MSG_BLTOUCH_OD_MODE = _UxGT("Cmd: OD-Mode"); + PROGMEM Language_Str MSG_BLTOUCH_MODE_STORE = _UxGT("Cmd: Mode-Store"); + PROGMEM Language_Str MSG_BLTOUCH_MODE_STORE_5V = _UxGT("Set BLTouch to 5V"); + PROGMEM Language_Str MSG_BLTOUCH_MODE_STORE_OD = _UxGT("Set BLTouch to OD"); + PROGMEM Language_Str MSG_BLTOUCH_MODE_ECHO = _UxGT("Report Drain"); + PROGMEM Language_Str MSG_BLTOUCH_MODE_CHANGE = _UxGT("DANGER: Bad settings can cause damage! Proceed anyway?"); + PROGMEM Language_Str MSG_TOUCHMI_PROBE = _UxGT("TouchMI"); + PROGMEM Language_Str MSG_TOUCHMI_INIT = _UxGT("Init TouchMI"); + PROGMEM Language_Str MSG_TOUCHMI_ZTEST = _UxGT("Z Offset Test"); + PROGMEM Language_Str MSG_TOUCHMI_SAVE = _UxGT("Save"); + PROGMEM Language_Str MSG_MANUAL_DEPLOY_TOUCHMI = _UxGT("Deploy TouchMI"); + PROGMEM Language_Str MSG_MANUAL_DEPLOY = _UxGT("Deploy Z-Probe"); + PROGMEM Language_Str MSG_MANUAL_STOW = _UxGT("Stow Z-Probe"); PROGMEM Language_Str MSG_HOME_FIRST = _UxGT("歸位 %s%s%s 先"); //"Home ... first" - PROGMEM Language_Str MSG_ZPROBE_ZOFFSET = _UxGT("Z偏移"); //"Z Offset" + PROGMEM Language_Str MSG_ZPROBE_OFFSETS = _UxGT("探針偏移"); //Probe Offsets + PROGMEM Language_Str MSG_ZPROBE_XOFFSET = _UxGT("探針X偏移量"); //Probe X Offset + PROGMEM Language_Str MSG_ZPROBE_YOFFSET = _UxGT("探針Y偏移量"); //Probe Y Offset + PROGMEM Language_Str MSG_ZPROBE_ZOFFSET = _UxGT("探針Z偏移量"); //Probe Z Offset PROGMEM Language_Str MSG_BABYSTEP_X = _UxGT("微量調整X軸"); //"Babystep X" lcd_babystep_x, Babystepping enables the user to control the axis in tiny amounts PROGMEM Language_Str MSG_BABYSTEP_Y = _UxGT("微量調整Y軸"); //"Babystep Y" PROGMEM Language_Str MSG_BABYSTEP_Z = _UxGT("微量調整Z軸"); //"Babystep Z" + PROGMEM Language_Str MSG_BABYSTEP_TOTAL = _UxGT("總計"); //"Total" PROGMEM Language_Str MSG_ENDSTOP_ABORT = _UxGT("擋塊終止"); //"Endstop abort" PROGMEM Language_Str MSG_HEATING_FAILED_LCD = _UxGT("加熱失敗"); //"Heating failed" - PROGMEM Language_Str MSG_ERR_REDUNDANT_TEMP = _UxGT("錯誤:REDUNDANT TEMP"); //"Err: REDUNDANT TEMP" - PROGMEM Language_Str MSG_THERMAL_RUNAWAY = _UxGT("溫控失控"); //"THERMAL RUNAWAY" + PROGMEM Language_Str MSG_HEATING_FAILED_LCD_BED = _UxGT("熱床加熱失敗"); //"Bed Heating Failed" + PROGMEM Language_Str MSG_HEATING_FAILED_LCD_CHAMBER = _UxGT("機箱加熱失敗"); //"Chamber Heating Fail" + PROGMEM Language_Str MSG_ERR_REDUNDANT_TEMP = _UxGT("錯誤:冗餘溫度"); //"Err: REDUNDANT TEMP" + PROGMEM Language_Str MSG_THERMAL_RUNAWAY = _UxGT("溫度失控"); //"THERMAL RUNAWAY" + PROGMEM Language_Str MSG_THERMAL_RUNAWAY_BED = _UxGT("熱床溫度失控"); //"BED THERMAL RUNAWAY" + PROGMEM Language_Str MSG_THERMAL_RUNAWAY_CHAMBER = _UxGT("機箱溫度失控"); //"CHAMBER T. RUNAWAY" PROGMEM Language_Str MSG_ERR_MAXTEMP = _UxGT("錯誤:最高溫度"); //"Err: MAXTEMP" PROGMEM Language_Str MSG_ERR_MINTEMP = _UxGT("錯誤:最低溫度"); //"Err: MINTEMP" PROGMEM Language_Str MSG_ERR_MAXTEMP_BED = _UxGT("錯誤:最高熱床溫度"); //"Err: MAXTEMP BED" PROGMEM Language_Str MSG_ERR_MINTEMP_BED = _UxGT("錯誤:最低熱床溫度"); //"Err: MINTEMP BED" + PROGMEM Language_Str MSG_ERR_MAXTEMP_CHAMBER = _UxGT("錯誤:最高機箱溫度"); //"Err: MAXTEMP CHAMBER" + PROGMEM Language_Str MSG_ERR_MINTEMP_CHAMBER = _UxGT("錯誤:最低機箱溫度"); //"Err: MINTEMP CHAMBER" PROGMEM Language_Str MSG_ERR_Z_HOMING = _UxGT("歸位 XY 先"); //"Home XY First" PROGMEM Language_Str MSG_HALTED = _UxGT("印表機停機"); //"PRINTER HALTED" PROGMEM Language_Str MSG_PLEASE_RESET = _UxGT("請重置"); //"Please reset" @@ -303,7 +424,11 @@ namespace Language_zh_TW { PROGMEM Language_Str MSG_SHORT_HOUR = _UxGT("時"); //"h" // One character only PROGMEM Language_Str MSG_SHORT_MINUTE = _UxGT("分"); //"m" // One character only PROGMEM Language_Str MSG_HEATING = _UxGT("加熱中 ..."); //"Heating..." + PROGMEM Language_Str MSG_COOLING = _UxGT("冷卻中 ..."); //"Cooling..." PROGMEM Language_Str MSG_BED_HEATING = _UxGT("加熱熱床中 ..."); //"Bed Heating..." + PROGMEM Language_Str MSG_BED_COOLING = _UxGT("熱床冷卻中 ..."); //"Bed Cooling..." + PROGMEM Language_Str MSG_CHAMBER_HEATING = _UxGT("機箱加熱中 .."); //"Chamber Heating..." + PROGMEM Language_Str MSG_CHAMBER_COOLING = _UxGT("機箱冷卻中 ..."); //Chamber Cooling... PROGMEM Language_Str MSG_DELTA_CALIBRATE = _UxGT("⊿校準"); //"Delta Calibration" PROGMEM Language_Str MSG_DELTA_CALIBRATE_X = _UxGT("⊿校準X"); //"Calibrate X" PROGMEM Language_Str MSG_DELTA_CALIBRATE_Y = _UxGT("⊿校準Y"); //"Calibrate Y" @@ -312,6 +437,7 @@ namespace Language_zh_TW { PROGMEM Language_Str MSG_DELTA_SETTINGS = _UxGT("⊿設置"); // "Delta Settings" PROGMEM Language_Str MSG_DELTA_AUTO_CALIBRATE = _UxGT("⊿自動校準"); // "Auto Calibration" PROGMEM Language_Str MSG_DELTA_HEIGHT_CALIBRATE = _UxGT("設置⊿高度"); // "Set Delta Height" + PROGMEM Language_Str MSG_DELTA_Z_OFFSET_CALIBRATE = _UxGT("Z偏移"); PROGMEM Language_Str MSG_DELTA_DIAG_ROD = _UxGT("⊿斜柱"); // "Diag Rod" PROGMEM Language_Str MSG_DELTA_HEIGHT = _UxGT("⊿高度"); // "Height" PROGMEM Language_Str MSG_DELTA_RADIUS = _UxGT("⊿半徑"); // "Radius" @@ -319,18 +445,20 @@ namespace Language_zh_TW { PROGMEM Language_Str MSG_INFO_PRINTER_MENU = _UxGT("印表機訊息"); //"Printer Info" PROGMEM Language_Str MSG_3POINT_LEVELING = _UxGT("三點調平"); // "3-Point Leveling" PROGMEM Language_Str MSG_LINEAR_LEVELING = _UxGT("線性調平"); // "Linear Leveling" - PROGMEM Language_Str MSG_BILINEAR_LEVELING = _UxGT("雙線性調平"); // "Bilinear Leveling" + PROGMEM Language_Str MSG_BILINEAR_LEVELING = _UxGT(" 雙線性調平"); // "Bilinear Leveling" PROGMEM Language_Str MSG_UBL_LEVELING = _UxGT("統一熱床調平(UBL)"); // "Unified Bed Leveling" PROGMEM Language_Str MSG_MESH_LEVELING = _UxGT("網格調平"); // "Mesh Leveling" PROGMEM Language_Str MSG_INFO_STATS_MENU = _UxGT("印表機統計"); //"Printer Stats" PROGMEM Language_Str MSG_INFO_BOARD_MENU = _UxGT("主板訊息"); //"Board Info" PROGMEM Language_Str MSG_INFO_THERMISTOR_MENU = _UxGT("溫度計"); //"Thermistors" - PROGMEM Language_Str MSG_INFO_EXTRUDERS = _UxGT("擠出機"); //"Extruders" + PROGMEM Language_Str MSG_INFO_EXTRUDERS = _UxGT(" 擠出機"); //"Extruders" PROGMEM Language_Str MSG_INFO_BAUDRATE = _UxGT("傳輸率"); //"Baud" PROGMEM Language_Str MSG_INFO_PROTOCOL = _UxGT("協議"); //"Protocol" + PROGMEM Language_Str MSG_INFO_RUNAWAY_OFF = _UxGT("監測溫度失控:關"); //"Runaway Watch: OFF" + PROGMEM Language_Str MSG_INFO_RUNAWAY_ON = _UxGT("監測溫度失控:開"); //"Runaway Watch: ON" + PROGMEM Language_Str MSG_CASE_LIGHT = _UxGT("外殼燈"); // "Case light" PROGMEM Language_Str MSG_CASE_LIGHT_BRIGHTNESS = _UxGT("燈亮度"); // "Light BRIGHTNESS" - PROGMEM Language_Str MSG_EXPECTED_PRINTER = _UxGT("打印機不正確"); // "The printer is incorrect" #if LCD_WIDTH >= 20 @@ -351,11 +479,14 @@ namespace Language_zh_TW { PROGMEM Language_Str MSG_INFO_MAX_TEMP = _UxGT("最高溫度"); //"Max Temp" PROGMEM Language_Str MSG_INFO_PSU = _UxGT("電源供應"); //"Power Supply" PROGMEM Language_Str MSG_DRIVE_STRENGTH = _UxGT("驅動力度"); // "Drive Strength" - PROGMEM Language_Str MSG_DAC_PERCENT_X = _UxGT("X 驅動 %"); // "X Driver %" - PROGMEM Language_Str MSG_DAC_PERCENT_Y = _UxGT("Y 驅動 %"); // "Y Driver %" - PROGMEM Language_Str MSG_DAC_PERCENT_Z = _UxGT("Z 驅動 %"); // "Z Driver %" - PROGMEM Language_Str MSG_DAC_PERCENT_E = _UxGT("E 驅動 %"); // "E Driver %" + PROGMEM Language_Str MSG_DAC_PERCENT = _UxGT("驅動 %"); // "Driver %" + PROGMEM Language_Str MSG_DAC_PERCENT_X = _UxGT("X 驅動 %"); //X Driver % + PROGMEM Language_Str MSG_DAC_PERCENT_Y = _UxGT("Y 驅動 %"); //Y Driver % + PROGMEM Language_Str MSG_DAC_PERCENT_Z = _UxGT("Z 驅動 %"); //Z Driver % + PROGMEM Language_Str MSG_DAC_PERCENT_E = _UxGT("E 驅動 %"); //E Driver % + PROGMEM Language_Str MSG_ERROR_TMC = _UxGT("TMC連接錯誤"); //"TMC CONNECTION ERROR" PROGMEM Language_Str MSG_DAC_EEPROM_WRITE = _UxGT("保存驅動設置"); // "DAC EEPROM Write" + PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEADER = _UxGT("更換絲料"); //"FILAMENT CHANGE" PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEADER_PAUSE = _UxGT("列印已暫停"); // "PRINT PAUSED" PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEADER_LOAD = _UxGT("裝載絲料"); // "LOAD FILAMENT" PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEADER_UNLOAD = _UxGT("卸載絲料"); // "UNLOAD FILAMENT" @@ -363,26 +494,112 @@ namespace Language_zh_TW { PROGMEM Language_Str MSG_FILAMENT_CHANGE_OPTION_PURGE = _UxGT("清除更多"); // "Purge more" PROGMEM Language_Str MSG_FILAMENT_CHANGE_OPTION_RESUME = _UxGT("恢復列印"); //"Resume print" PROGMEM Language_Str MSG_FILAMENT_CHANGE_NOZZLE = _UxGT(" 噴嘴: "); // " Nozzle: " + PROGMEM Language_Str MSG_RUNOUT_SENSOR = _UxGT("斷絲偵測"); //"Runout Sensor" + PROGMEM Language_Str MSG_RUNOUT_DISTANCE_MM = _UxGT("絲距離mm"); //"Runout Dist mm" PROGMEM Language_Str MSG_LCD_HOMING_FAILED = _UxGT("歸原位失敗"); // "Homing failed" PROGMEM Language_Str MSG_LCD_PROBING_FAILED = _UxGT("探針探測失敗"); // "Probing failed" PROGMEM Language_Str MSG_M600_TOO_COLD = _UxGT("M600: 太冷"); // "M600: Too cold" + PROGMEM Language_Str MSG_MMU2_CHOOSE_FILAMENT_HEADER = _UxGT("CHOOSE FILAMENT"); + PROGMEM Language_Str MSG_MMU2_MENU = _UxGT("MMU"); + PROGMEM Language_Str MSG_MMU2_WRONG_FIRMWARE = _UxGT("Update MMU Firmware!"); + PROGMEM Language_Str MSG_MMU2_NOT_RESPONDING = _UxGT("MMU Needs Attention."); + PROGMEM Language_Str MSG_MMU2_RESUME = _UxGT("Resume Print"); + PROGMEM Language_Str MSG_MMU2_RESUMING = _UxGT("Resuming..."); + PROGMEM Language_Str MSG_MMU2_LOAD_FILAMENT = _UxGT("Load Filament"); + PROGMEM Language_Str MSG_MMU2_LOAD_ALL = _UxGT("Load All"); + PROGMEM Language_Str MSG_MMU2_LOAD_TO_NOZZLE = _UxGT("Load to Nozzle"); + PROGMEM Language_Str MSG_MMU2_EJECT_FILAMENT = _UxGT("Eject Filament"); + PROGMEM Language_Str MSG_MMU2_EJECT_FILAMENT_N = _UxGT("Eject Filament ~"); + PROGMEM Language_Str MSG_MMU2_UNLOAD_FILAMENT = _UxGT("Unload Filament"); + PROGMEM Language_Str MSG_MMU2_LOADING_FILAMENT = _UxGT("Loading Fil. %i..."); + PROGMEM Language_Str MSG_MMU2_EJECTING_FILAMENT = _UxGT("Ejecting Fil. ..."); + PROGMEM Language_Str MSG_MMU2_UNLOADING_FILAMENT = _UxGT("Unloading Fil...."); + PROGMEM Language_Str MSG_MMU2_ALL = _UxGT("All"); + PROGMEM Language_Str MSG_MMU2_FILAMENT_N = _UxGT("Filament ~"); + PROGMEM Language_Str MSG_MMU2_RESET = _UxGT("Reset MMU"); + PROGMEM Language_Str MSG_MMU2_RESETTING = _UxGT("Resetting MMU..."); + PROGMEM Language_Str MSG_MMU2_EJECT_RECOVER = _UxGT("Remove, click"); + + PROGMEM Language_Str MSG_MIX = _UxGT("Mix"); + PROGMEM Language_Str MSG_MIX_COMPONENT_N = _UxGT("Component ="); + PROGMEM Language_Str MSG_MIXER = _UxGT("Mixer"); + PROGMEM Language_Str MSG_GRADIENT = _UxGT("Gradient"); + PROGMEM Language_Str MSG_FULL_GRADIENT = _UxGT("Full Gradient"); + PROGMEM Language_Str MSG_TOGGLE_MIX = _UxGT("Toggle Mix"); + PROGMEM Language_Str MSG_CYCLE_MIX = _UxGT("Cycle Mix"); + PROGMEM Language_Str MSG_GRADIENT_MIX = _UxGT("Gradient Mix"); + PROGMEM Language_Str MSG_REVERSE_GRADIENT = _UxGT("Reverse Gradient"); + PROGMEM Language_Str MSG_ACTIVE_VTOOL = _UxGT("Active V-tool"); + PROGMEM Language_Str MSG_START_VTOOL = _UxGT("Start V-tool"); + PROGMEM Language_Str MSG_END_VTOOL = _UxGT(" End V-tool"); + PROGMEM Language_Str MSG_GRADIENT_ALIAS = _UxGT("Alias V-tool"); + PROGMEM Language_Str MSG_RESET_VTOOLS = _UxGT("Reset V-tools"); + PROGMEM Language_Str MSG_COMMIT_VTOOL = _UxGT("Commit V-tool Mix"); + PROGMEM Language_Str MSG_VTOOLS_RESET = _UxGT("V-tools Were Reset"); + PROGMEM Language_Str MSG_START_Z = _UxGT("Start Z:"); + PROGMEM Language_Str MSG_END_Z = _UxGT(" End Z:"); + + PROGMEM Language_Str MSG_GAMES = _UxGT("Games"); + PROGMEM Language_Str MSG_BRICKOUT = _UxGT("Brickout"); + PROGMEM Language_Str MSG_INVADERS = _UxGT("Invaders"); + PROGMEM Language_Str MSG_SNAKE = _UxGT("Sn4k3"); + PROGMEM Language_Str MSG_MAZE = _UxGT("Maze"); + + #define MSG_1_LINE(A) A "\0" "\0" + #define MSG_2_LINE(A,B) A "\0" B "\0" + #define MSG_3_LINE(A,B,C) A "\0" B "\0" C + + // + // Filament Change screens show up to 3 lines on a 4-line display + // ...or up to 2 lines on a 3-line display + // #if LCD_HEIGHT >= 4 + PROGMEM Language_Str MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_2_LINE("按下按鈕", "恢復列印")); //"Press Button to resume print" + PROGMEM Language_Str MSG_PAUSE_PRINT_INIT = _UxGT(MSG_1_LINE("停車中 ...")); //"Parking..." PROGMEM Language_Str MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_3_LINE("等待開始", "絲料", "變更")); //"Wait for start of the filament change" PROGMEM Language_Str MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_2_LINE("等待", "卸下絲料")); //"Wait for filament unload" PROGMEM Language_Str MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_3_LINE("插入絲料", "並按鍵", "繼續 ...")); //"Insert filament and press button to continue..." - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_2_LINE("按下按鈕來", "加熱噴嘴.")); // "Press button to heat nozzle." + PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_2_LINE("按下按鈕", "加熱噴嘴.")); // "Press button to heat nozzle." PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEATING = _UxGT(MSG_2_LINE("加熱噴嘴", "請等待 ...")); // "Heating nozzle Please wait..." PROGMEM Language_Str MSG_FILAMENT_CHANGE_LOAD = _UxGT(MSG_2_LINE("等待", "進料")); //"Wait for filament load" PROGMEM Language_Str MSG_FILAMENT_CHANGE_PURGE = _UxGT(MSG_2_LINE("等待", "絲料清除")); // "Wait for filament purge" + PROGMEM Language_Str MSG_FILAMENT_CHANGE_CONT_PURGE = _UxGT(MSG_2_LINE("按下完成","絲料清除")); //"Press button to filament purge" PROGMEM Language_Str MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_2_LINE("等待列印", "恢復")); //"Wait for print to resume" #else // LCD_HEIGHT < 4 + PROGMEM Language_Str MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_1_LINE("按下繼續..")); //"Click to continue" + PROGMEM Language_Str MSG_PAUSE_PRINT_INIT = _UxGT(MSG_1_LINE("停車中 ...")); //"Parking..." PROGMEM Language_Str MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_1_LINE("請等待 ...")); //"Please wait..." - PROGMEM Language_Str MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_1_LINE("退出中 ...")); //"Ejecting..." PROGMEM Language_Str MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_1_LINE("插入並點擊")); //"Insert and Click" - PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEATING = _UxGT(MSG_1_LINE("加熱中 ...")); // "Heating..." + PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_1_LINE("按下加熱..")); //"Click to heat" + PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEATING = _UxGT(MSG_1_LINE("加熱中 ...")); //"Heating..." + PROGMEM Language_Str MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_1_LINE("退出中 ...")); //"Ejecting..." PROGMEM Language_Str MSG_FILAMENT_CHANGE_LOAD = _UxGT(MSG_1_LINE("載入中 ...")); //"Loading..." - PROGMEM Language_Str MSG_FILAMENT_CHANGE_PURGE = _UxGT(MSG_1_LINE("清除中 ...")); // "Purging..." + PROGMEM Language_Str MSG_FILAMENT_CHANGE_PURGE = _UxGT(MSG_1_LINE("清除中 ...")); //"Purging..." + PROGMEM Language_Str MSG_FILAMENT_CHANGE_CONT_PURGE = _UxGT(MSG_1_LINE("按下完成..")); //"Click to finish" PROGMEM Language_Str MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_1_LINE("恢復中 ...")); //"Resuming..." #endif // LCD_HEIGHT < 4 + + PROGMEM Language_Str MSG_TMC_DRIVERS = _UxGT("TMC Drivers"); + PROGMEM Language_Str MSG_TMC_CURRENT = _UxGT("Driver Current"); + PROGMEM Language_Str MSG_TMC_HYBRID_THRS = _UxGT("Hybrid Threshold"); + PROGMEM Language_Str MSG_TMC_HOMING_THRS = _UxGT("Sensorless Homing"); + PROGMEM Language_Str MSG_TMC_STEPPING_MODE = _UxGT("Stepping Mode"); + PROGMEM Language_Str MSG_TMC_STEALTH_ENABLED = _UxGT("StealthChop Enabled"); + PROGMEM Language_Str MSG_SERVICE_RESET = _UxGT("Reset"); + PROGMEM Language_Str MSG_SERVICE_IN = _UxGT(" in:"); + PROGMEM Language_Str MSG_BACKLASH = _UxGT("Backlash"); + PROGMEM Language_Str MSG_BACKLASH_A = LCD_STR_A; + PROGMEM Language_Str MSG_BACKLASH_B = LCD_STR_B; + PROGMEM Language_Str MSG_BACKLASH_C = LCD_STR_C; + PROGMEM Language_Str MSG_BACKLASH_CORRECTION = _UxGT("Correction"); + PROGMEM Language_Str MSG_BACKLASH_SMOOTHING = _UxGT("Smoothing"); } + +#if FAN_COUNT == 1 + #define MSG_FIRST_FAN_SPEED MSG_FAN_SPEED + #define MSG_FIRST_EXTRA_FAN_SPEED MSG_EXTRA_FAN_SPEED +#else + #define MSG_FIRST_FAN_SPEED MSG_FAN_SPEED_N + #define MSG_FIRST_EXTRA_FAN_SPEED MSG_EXTRA_FAN_SPEED_N +#endif diff --git a/Marlin/src/lcd/menu/game/brickout.cpp b/Marlin/src/lcd/menu/game/brickout.cpp index 50da0f9cc7..6fe0a31ffa 100644 --- a/Marlin/src/lcd/menu/game/brickout.cpp +++ b/Marlin/src/lcd/menu/game/brickout.cpp @@ -140,13 +140,13 @@ void BrickoutGame::game_screen() { // Draw bricks if (PAGE_CONTAINS(BRICK_TOP, BRICK_BOT)) { - for (uint8_t y = 0; y < BRICK_ROWS; ++y) { + LOOP_L_N(y, BRICK_ROWS) { const uint8_t yy = y * BRICK_H + BRICK_TOP; if (PAGE_CONTAINS(yy, yy + BRICK_H - 1)) { - for (uint8_t x = 0; x < BRICK_COLS; ++x) { + LOOP_L_N(x, BRICK_COLS) { if (TEST(bdat.bricks[y], x)) { const uint8_t xx = x * BRICK_W; - for (uint8_t v = 0; v < BRICK_H - 1; ++v) + LOOP_L_N(v, BRICK_H - 1) if (PAGE_CONTAINS(yy + v, yy + v)) u8g.drawHLine(xx, yy + v, BRICK_W - 1); } diff --git a/Marlin/src/lcd/menu/game/invaders.cpp b/Marlin/src/lcd/menu/game/invaders.cpp index 487f540671..31df47ce7f 100644 --- a/Marlin/src/lcd/menu/game/invaders.cpp +++ b/Marlin/src/lcd/menu/game/invaders.cpp @@ -170,7 +170,7 @@ inline void update_invader_data() { uint8_t m = idat.bugs[y]; if (m) idat.botmost = y + 1; inv_mask |= m; - for (uint8_t x = 0; x < INVADER_COLS; ++x) + LOOP_L_N(x, INVADER_COLS) if (TEST(m, x)) idat.shooters[sc++] = (y << 4) | x; } idat.leftmost = 0; @@ -371,11 +371,11 @@ void InvadersGame::game_screen() { // Draw invaders if (PAGE_CONTAINS(idat.pos.y, idat.pos.y + idat.botmost * (INVADER_ROW_H) - 2 - 1)) { int8_t yy = idat.pos.y; - for (uint8_t y = 0; y < INVADER_ROWS; ++y) { + LOOP_L_N(y, INVADER_ROWS) { const uint8_t type = inv_type[y]; if (PAGE_CONTAINS(yy, yy + INVADER_H - 1)) { int8_t xx = idat.pos.x; - for (uint8_t x = 0; x < INVADER_COLS; ++x) { + LOOP_L_N(x, INVADER_COLS) { if (TEST(idat.bugs[y], x)) u8g.drawBitmapP(xx, yy, 2, INVADER_H, invader[type][idat.game_blink]); xx += INVADER_COL_W; diff --git a/Marlin/src/lcd/menu/game/maze.cpp b/Marlin/src/lcd/menu/game/maze.cpp index 9cfa5da4da..d92f14ecd8 100644 --- a/Marlin/src/lcd/menu/game/maze.cpp +++ b/Marlin/src/lcd/menu/game/maze.cpp @@ -83,7 +83,7 @@ void MazeGame::game_screen() { if (PAGE_UNDER(HEADER_H)) lcd_put_int(0, HEADER_H - 1, score); // Draw the maze - // for (uint8_t n = 0; n < head_ind; ++n) { + // LOOP_L_N(n, head_ind) { // const pos_t &p = maze_walls[n], &q = maze_walls[n + 1]; // if (p.x == q.x) { // const int8_t y1 = GAMEY(_MIN(p.y, q.y)), y2 = GAMEY(_MAX(p.y, q.y)); diff --git a/Marlin/src/lcd/menu/game/snake.cpp b/Marlin/src/lcd/menu/game/snake.cpp index 8c5280b689..d6af224553 100644 --- a/Marlin/src/lcd/menu/game/snake.cpp +++ b/Marlin/src/lcd/menu/game/snake.cpp @@ -84,14 +84,14 @@ void shorten_tail() { } if (shift) { sdat.head_ind--; - for (uint8_t i = 0; i <= sdat.head_ind; ++i) + LOOP_LE_N(i, sdat.head_ind) sdat.snake_tail[i] = sdat.snake_tail[i + 1]; } } // The food is on a line inline bool food_on_line() { - for (uint8_t n = 0; n < sdat.head_ind; ++n) { + LOOP_L_N(n, sdat.head_ind) { pos_t &p = sdat.snake_tail[n], &q = sdat.snake_tail[n + 1]; if (p.x == q.x) { if ((sdat.foodx == p.x - 1 || sdat.foodx == p.x) && WITHIN(sdat.foody, _MIN(p.y, q.y), _MAX(p.y, q.y))) @@ -151,7 +151,7 @@ bool snake_overlap() { // VERTICAL head segment? if (h1.x == h2.x) { // Loop from oldest to segment two away from head - for (uint8_t n = 0; n < sdat.head_ind - 2; ++n) { + LOOP_L_N(n, sdat.head_ind - 2) { // Segment p to q const pos_t &p = sdat.snake_tail[n], &q = sdat.snake_tail[n + 1]; if (p.x != q.x) { @@ -163,7 +163,7 @@ bool snake_overlap() { } else { // Loop from oldest to segment two away from head - for (uint8_t n = 0; n < sdat.head_ind - 2; ++n) { + LOOP_L_N(n, sdat.head_ind - 2) { // Segment p to q const pos_t &p = sdat.snake_tail[n], &q = sdat.snake_tail[n + 1]; if (p.y != q.y) { @@ -240,7 +240,7 @@ void SnakeGame::game_screen() { #if SNAKE_WH < 2 // At this scale just draw a line - for (uint8_t n = 0; n < sdat.head_ind; ++n) { + LOOP_L_N(n, sdat.head_ind) { const pos_t &p = sdat.snake_tail[n], &q = sdat.snake_tail[n + 1]; if (p.x == q.x) { const int8_t y1 = GAMEY(_MIN(p.y, q.y)), y2 = GAMEY(_MAX(p.y, q.y)); @@ -256,7 +256,7 @@ void SnakeGame::game_screen() { #elif SNAKE_WH == 2 // At this scale draw two lines - for (uint8_t n = 0; n < sdat.head_ind; ++n) { + LOOP_L_N(n, sdat.head_ind) { const pos_t &p = sdat.snake_tail[n], &q = sdat.snake_tail[n + 1]; if (p.x == q.x) { const int8_t y1 = GAMEY(_MIN(p.y, q.y)), y2 = GAMEY(_MAX(p.y, q.y)); @@ -275,7 +275,7 @@ void SnakeGame::game_screen() { #else // Draw a series of boxes - for (uint8_t n = 0; n < sdat.head_ind; ++n) { + LOOP_L_N(n, sdat.head_ind) { const pos_t &p = sdat.snake_tail[n], &q = sdat.snake_tail[n + 1]; if (p.x == q.x) { const int8_t y1 = _MIN(p.y, q.y), y2 = _MAX(p.y, q.y); diff --git a/Marlin/src/lcd/menu/menu.cpp b/Marlin/src/lcd/menu/menu.cpp index f1bcb970d4..959c1c4160 100644 --- a/Marlin/src/lcd/menu/menu.cpp +++ b/Marlin/src/lcd/menu/menu.cpp @@ -127,7 +127,7 @@ void MenuItem_gcode::action(PGM_P const, PGM_P const pgcode) { queue.inject_P(pg * * The prerequisite is that in the header the type was already declared: * - * DEFINE_MENU_EDIT_ITEM_TYPE(int16_t, int3, i16tostr3, 1) + * DEFINE_MENU_EDIT_ITEM_TYPE(int3, int16_t, i16tostr3rj, 1) * * For example, DEFINE_MENU_EDIT_ITEM(int3) expands into: * @@ -396,11 +396,7 @@ void scroll_screen(const uint8_t limit, const bool is_menu) { void lcd_babystep_zoffset() { if (ui.use_click()) return ui.goto_previous_screen_no_defer(); ui.defer_status_screen(); - #if ENABLED(BABYSTEP_HOTEND_Z_OFFSET) - const bool do_probe = (active_extruder == 0); - #else - constexpr bool do_probe = true; - #endif + const bool do_probe = DISABLED(BABYSTEP_HOTEND_Z_OFFSET) || active_extruder == 0; if (ui.encoderPosition) { const int16_t babystep_increment = int16_t(ui.encoderPosition) * (BABYSTEP_MULTIPLICATOR_Z); ui.encoderPosition = 0; @@ -429,14 +425,14 @@ void scroll_screen(const uint8_t limit, const bool is_menu) { if (ui.should_draw()) { #if ENABLED(BABYSTEP_HOTEND_Z_OFFSET) if (!do_probe) - MenuEditItemBase::draw_edit_screen(GET_TEXT(MSG_HOTEND_OFFSET_Z), LCD_Z_OFFSET_FUNC(hotend_offset[active_extruder].z)); - else - #endif - MenuEditItemBase::draw_edit_screen(GET_TEXT(MSG_ZPROBE_ZOFFSET), LCD_Z_OFFSET_FUNC(probe.offset.z)); - - #if ENABLED(BABYSTEP_ZPROBE_GFX_OVERLAY) - if (do_probe) _lcd_zoffset_overlay_gfx(probe.offset.z); + MenuEditItemBase::draw_edit_screen(GET_TEXT(MSG_HOTEND_OFFSET_Z), ftostr54sign(hotend_offset[active_extruder].z)); #endif + if (do_probe) { + MenuEditItemBase::draw_edit_screen(GET_TEXT(MSG_ZPROBE_ZOFFSET), ftostr52sign(probe.offset.z)); + #if ENABLED(BABYSTEP_ZPROBE_GFX_OVERLAY) + _lcd_zoffset_overlay_gfx(probe.offset.z); + #endif + } } } diff --git a/Marlin/src/lcd/menu/menu.h b/Marlin/src/lcd/menu/menu.h index 5299fefde2..4ba618e5ca 100644 --- a/Marlin/src/lcd/menu/menu.h +++ b/Marlin/src/lcd/menu/menu.h @@ -48,9 +48,11 @@ typedef void (*selectFunc_t)(); #endif #if Z_PROBE_OFFSET_RANGE_MIN >= -9 && Z_PROBE_OFFSET_RANGE_MAX <= 9 + // Only values from -9.999 to 9.999 #define LCD_Z_OFFSET_FUNC(N) ftostr54sign(N) #define LCD_Z_OFFSET_TYPE float43 #else + // Values from -99.99 to 99.99 #define LCD_Z_OFFSET_FUNC(N) ftostr52sign(N) #define LCD_Z_OFFSET_TYPE float52 #endif @@ -266,35 +268,37 @@ class TMenuEditItem : MenuEditItemBase { // Provide a set of Edit Item Types which encompass a primitive // type, a string function, and a scale factor for edit and display. // These items call the Edit Item draw method passing the prepared string. -#define DEFINE_MENU_EDIT_ITEM_TYPE(TYPE, NAME, FIX, STRFUNC, SCALE, V...) \ +#define __DOFIXfloat PROBE() +#define _DOFIX(TYPE,V) TYPE(TERN(IS_PROBE(__DOFIX##TYPE),FIXFLOAT(V),(V))) +#define DEFINE_MENU_EDIT_ITEM_TYPE(NAME, TYPE, STRFUNC, SCALE, V...) \ struct MenuEditItemInfo_##NAME { \ typedef TYPE type_t; \ static inline float scale(const float value) { return value * (SCALE) + (V+0); } \ static inline float unscale(const float value) { return value / (SCALE) + (V+0); } \ - static inline const char* strfunc(const float value) { return STRFUNC((TYPE)(FIX ? FIXFLOAT(value) : value)); } \ + static inline const char* strfunc(const float value) { return STRFUNC(_DOFIX(TYPE,value)); } \ }; \ typedef TMenuEditItem MenuItem_##NAME -// TYPE NAME STRFUNC SCALE -DEFINE_MENU_EDIT_ITEM_TYPE(uint8_t, percent, 0, ui8tostr4pct, 100.0/255, 0.5); // 100% right-justified -DEFINE_MENU_EDIT_ITEM_TYPE(int16_t, int3, 0, i16tostr3, 1 ); // 123, -12 right-justified -DEFINE_MENU_EDIT_ITEM_TYPE(int16_t, int4, 0, i16tostr4sign, 1 ); // 1234, -123 right-justified -DEFINE_MENU_EDIT_ITEM_TYPE(int8_t, int8, 0, i8tostr3, 1 ); // 123, -12 right-justified -DEFINE_MENU_EDIT_ITEM_TYPE(uint8_t, uint8, 0, ui8tostr3, 1 ); // 123 right-justified -DEFINE_MENU_EDIT_ITEM_TYPE(uint16_t, uint16_3, 0, ui16tostr3, 1 ); // 123 right-justified -DEFINE_MENU_EDIT_ITEM_TYPE(uint16_t, uint16_4, 0, ui16tostr4, 0.1 ); // 1234 right-justified -DEFINE_MENU_EDIT_ITEM_TYPE(uint16_t, uint16_5, 0, ui16tostr5, 0.01 ); // 12345 right-justified -DEFINE_MENU_EDIT_ITEM_TYPE(float, float3, 1, ftostr3, 1 ); // 123 right-justified -DEFINE_MENU_EDIT_ITEM_TYPE(float, float52, 1, ftostr42_52, 100 ); // _2.34, 12.34, -2.34 or 123.45, -23.45 -DEFINE_MENU_EDIT_ITEM_TYPE(float, float43, 1, ftostr43sign, 1000 ); // 1.234 -DEFINE_MENU_EDIT_ITEM_TYPE(float, float5, 1, ftostr5rj, 1 ); // 12345 right-justified -DEFINE_MENU_EDIT_ITEM_TYPE(float, float5_25, 1, ftostr5rj, 0.04f ); // 12345 right-justified (25 increment) -DEFINE_MENU_EDIT_ITEM_TYPE(float, float51, 1, ftostr51rj, 10 ); // 1234.5 right-justified -DEFINE_MENU_EDIT_ITEM_TYPE(float, float41sign, 1, ftostr41sign, 10 ); // +123.4 -DEFINE_MENU_EDIT_ITEM_TYPE(float, float51sign, 1, ftostr51sign, 10 ); // +1234.5 -DEFINE_MENU_EDIT_ITEM_TYPE(float, float52sign, 1, ftostr52sign, 100 ); // +123.45 -DEFINE_MENU_EDIT_ITEM_TYPE(uint32_t, long5, 0, ftostr5rj, 0.01f ); // 12345 right-justified -DEFINE_MENU_EDIT_ITEM_TYPE(uint32_t, long5_25, 0, ftostr5rj, 0.04f ); // 12345 right-justified (25 increment) +// NAME TYPE STRFUNC SCALE +ROUND +DEFINE_MENU_EDIT_ITEM_TYPE(percent ,uint8_t ,ui8tostr4pctrj , 100.f/255.f, 0.5f); // 100% right-justified +DEFINE_MENU_EDIT_ITEM_TYPE(int3 ,int16_t ,i16tostr3rj , 1 ); // 123, -12 right-justified +DEFINE_MENU_EDIT_ITEM_TYPE(int4 ,int16_t ,i16tostr4signrj , 1 ); // 1234, -123 right-justified +DEFINE_MENU_EDIT_ITEM_TYPE(int8 ,int8_t ,i8tostr3rj , 1 ); // 123, -12 right-justified +DEFINE_MENU_EDIT_ITEM_TYPE(uint8 ,uint8_t ,ui8tostr3rj , 1 ); // 123 right-justified +DEFINE_MENU_EDIT_ITEM_TYPE(uint16_3 ,uint16_t ,ui16tostr3rj , 1 ); // 123 right-justified +DEFINE_MENU_EDIT_ITEM_TYPE(uint16_4 ,uint16_t ,ui16tostr4rj , 0.1f ); // 1234 right-justified +DEFINE_MENU_EDIT_ITEM_TYPE(uint16_5 ,uint16_t ,ui16tostr5rj , 0.01f ); // 12345 right-justified +DEFINE_MENU_EDIT_ITEM_TYPE(float3 ,float ,ftostr3 , 1 ); // 123 right-justified +DEFINE_MENU_EDIT_ITEM_TYPE(float52 ,float ,ftostr42_52 , 100 ); // _2.34, 12.34, -2.34 or 123.45, -23.45 +DEFINE_MENU_EDIT_ITEM_TYPE(float43 ,float ,ftostr43sign ,1000 ); // -1.234, _1.234, +1.234 +DEFINE_MENU_EDIT_ITEM_TYPE(float5 ,float ,ftostr5rj , 1 ); // 12345 right-justified +DEFINE_MENU_EDIT_ITEM_TYPE(float5_25 ,float ,ftostr5rj , 0.04f ); // 12345 right-justified (25 increment) +DEFINE_MENU_EDIT_ITEM_TYPE(float51 ,float ,ftostr51rj , 10 ); // 1234.5 right-justified +DEFINE_MENU_EDIT_ITEM_TYPE(float41sign ,float ,ftostr41sign , 10 ); // +123.4 +DEFINE_MENU_EDIT_ITEM_TYPE(float51sign ,float ,ftostr51sign , 10 ); // +1234.5 +DEFINE_MENU_EDIT_ITEM_TYPE(float52sign ,float ,ftostr52sign , 100 ); // +123.45 +DEFINE_MENU_EDIT_ITEM_TYPE(long5 ,uint32_t ,ftostr5rj , 0.01f ); // 12345 right-justified +DEFINE_MENU_EDIT_ITEM_TYPE(long5_25 ,uint32_t ,ftostr5rj , 0.04f ); // 12345 right-justified (25 increment) class MenuItem_bool : public MenuEditItemBase { public: @@ -322,10 +326,10 @@ class MenuItem_bool : public MenuEditItemBase { * _menuLineNr is the menu item to draw and process * _thisItemNr is the index of each MENU_ITEM or STATIC_ITEM */ -#define SCREEN_OR_MENU_LOOP(IS_MENU) \ - scroll_screen(IS_MENU ? 1 : LCD_HEIGHT, IS_MENU); \ - int8_t _menuLineNr = encoderTopLine, _thisItemNr; \ - bool _skipStatic = IS_MENU; UNUSED(_thisItemNr); \ +#define SCREEN_OR_MENU_LOOP(IS_MENU) \ + scroll_screen(IS_MENU ? 1 : LCD_HEIGHT, IS_MENU); \ + int8_t _menuLineNr = encoderTopLine, _thisItemNr = 0; \ + bool _skipStatic = IS_MENU; UNUSED(_thisItemNr); \ for (int8_t _lcdLineNr = 0; _lcdLineNr < LCD_HEIGHT; _lcdLineNr++, _menuLineNr++) { \ _thisItemNr = 0 diff --git a/Marlin/src/lcd/menu/menu_advanced.cpp b/Marlin/src/lcd/menu/menu_advanced.cpp index 03bcedb730..a4a8176d3a 100644 --- a/Marlin/src/lcd/menu/menu_advanced.cpp +++ b/Marlin/src/lcd/menu/menu_advanced.cpp @@ -114,7 +114,7 @@ void menu_cancelobject(); #if EXTRUDERS == 1 EDIT_ITEM(float52, MSG_ADVANCE_K, &planner.extruder_advance_K[0], 0, 999); #elif EXTRUDERS > 1 - for (uint8_t n = 0; n < EXTRUDERS; n++) + LOOP_L_N(n, EXTRUDERS) EDIT_ITEM_N(float52, n, MSG_ADVANCE_K_E, &planner.extruder_advance_K[n], 0, 999); #endif #endif @@ -125,7 +125,7 @@ void menu_cancelobject(); if (parser.volumetric_enabled) { EDIT_ITEM_FAST(float43, MSG_FILAMENT_DIAM, &planner.filament_size[active_extruder], 1.5f, 3.25f, planner.calculate_volumetric_multipliers); #if EXTRUDERS > 1 - for (uint8_t n = 0; n < EXTRUDERS; n++) + LOOP_L_N(n, EXTRUDERS) EDIT_ITEM_FAST_N(float43, n, MSG_FILAMENT_DIAM_E, &planner.filament_size[n], 1.5f, 3.25f, planner.calculate_volumetric_multipliers); #endif } @@ -142,13 +142,13 @@ void menu_cancelobject(); EDIT_ITEM_FAST(float3, MSG_FILAMENT_UNLOAD, &fc_settings[active_extruder].unload_length, 0, extrude_maxlength); #if EXTRUDERS > 1 - for (uint8_t n = 0; n < EXTRUDERS; n++) + LOOP_L_N(n, EXTRUDERS) EDIT_ITEM_FAST_N(float3, n, MSG_FILAMENTUNLOAD_E, &fc_settings[n].unload_length, 0, extrude_maxlength); #endif EDIT_ITEM_FAST(float3, MSG_FILAMENT_LOAD, &fc_settings[active_extruder].load_length, 0, extrude_maxlength); #if EXTRUDERS > 1 - for (uint8_t n = 0; n < EXTRUDERS; n++) + LOOP_L_N(n, EXTRUDERS) EDIT_ITEM_FAST_N(float3, n, MSG_FILAMENTLOAD_E, &fc_settings[n].load_length, 0, extrude_maxlength); #endif #endif @@ -358,7 +358,7 @@ void menu_cancelobject(); EDIT_ITEM_FAST(float3, MSG_VMAX_E, &planner.settings.max_feedrate_mm_s[E_AXIS_N(active_extruder)], 1, max_fr_edit_scaled.e); #endif #if ENABLED(DISTINCT_E_FACTORS) - for (uint8_t n = 0; n < E_STEPPERS; n++) + LOOP_L_N(n, E_STEPPERS) EDIT_ITEM_FAST_N(float3, n, MSG_VMAX_EN, &planner.settings.max_feedrate_mm_s[E_AXIS_N(n)], 1, max_fr_edit_scaled.e); #endif @@ -409,7 +409,7 @@ void menu_cancelobject(); #if ENABLED(DISTINCT_E_FACTORS) EDIT_ITEM_FAST(long5_25, MSG_AMAX_E, &planner.settings.max_acceleration_mm_per_s2[E_AXIS_N(active_extruder)], 100, max_accel_edit_scaled.e, []{ planner.reset_acceleration_rates(); }); - for (uint8_t n = 0; n < E_STEPPERS; n++) + LOOP_L_N(n, E_STEPPERS) EDIT_ITEM_FAST_N(long5_25, n, MSG_AMAX_EN, &planner.settings.max_acceleration_mm_per_s2[E_AXIS_N(n)], 100, max_accel_edit_scaled.e, []{ _reset_e_acceleration_rate(MenuItemBase::itemIndex); }); #elif E_STEPPERS EDIT_ITEM_FAST(long5_25, MSG_AMAX_E, &planner.settings.max_acceleration_mm_per_s2[E_AXIS], 100, max_accel_edit_scaled.e, []{ planner.reset_acceleration_rates(); }); @@ -484,7 +484,7 @@ void menu_advanced_steps_per_mm() { #if ENABLED(DISTINCT_E_FACTORS) EDIT_ITEM_FAST(float51, MSG_E_STEPS, &planner.settings.axis_steps_per_mm[E_AXIS_N(active_extruder)], 5, 9999, []{ planner.refresh_positioning(); }); - for (uint8_t n = 0; n < E_STEPPERS; n++) + LOOP_L_N(n, E_STEPPERS) EDIT_ITEM_FAST_N(float51, n, MSG_EN_STEPS, &planner.settings.axis_steps_per_mm[E_AXIS_N(n)], 5, 9999, []{ _planner_refresh_e_positioning(MenuItemBase::itemIndex); }); #elif E_STEPPERS EDIT_ITEM_FAST(float51, MSG_E_STEPS, &planner.settings.axis_steps_per_mm[E_AXIS], 5, 9999, []{ planner.refresh_positioning(); }); @@ -544,7 +544,7 @@ void menu_advanced_settings() { SUBMENU(MSG_DRIVE_STRENGTH, menu_pwm); #endif - #if HAS_TRINAMIC + #if HAS_TRINAMIC_CONFIG SUBMENU(MSG_TMC_DRIVERS, menu_tmc); #endif @@ -558,7 +558,7 @@ void menu_advanced_settings() { #if EXTRUDERS == 1 EDIT_ITEM(float52, MSG_ADVANCE_K, &planner.extruder_advance_K[0], 0, 999); #elif EXTRUDERS > 1 - for (uint8_t n = 0; n < E_STEPPERS; n++) + LOOP_L_N(n, E_STEPPERS) EDIT_ITEM_N(float52, n, MSG_ADVANCE_K_E, &planner.extruder_advance_K[n], 0, 999); #endif #endif diff --git a/Marlin/src/lcd/menu/menu_configuration.cpp b/Marlin/src/lcd/menu/menu_configuration.cpp index d2285e0835..ae0abbf746 100644 --- a/Marlin/src/lcd/menu/menu_configuration.cpp +++ b/Marlin/src/lcd/menu/menu_configuration.cpp @@ -37,7 +37,7 @@ #endif #if ENABLED(POWER_LOSS_RECOVERY) - #include "../../feature/power_loss_recovery.h" + #include "../../feature/powerloss.h" #endif #if HAS_BED_PROBE diff --git a/Marlin/src/lcd/menu/menu_delta_calibrate.cpp b/Marlin/src/lcd/menu/menu_delta_calibrate.cpp index 2b3cac5bd2..aa35a6915c 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/extensible_ui/ui_api.h" + #include "../../lcd/extui/ui_api.h" #endif void _man_probe_pt(const xy_pos_t &xy) { diff --git a/Marlin/src/lcd/menu/menu_filament.cpp b/Marlin/src/lcd/menu/menu_filament.cpp index 5f2ecb9ccd..0c8f1f61c8 100644 --- a/Marlin/src/lcd/menu/menu_filament.cpp +++ b/Marlin/src/lcd/menu/menu_filament.cpp @@ -114,7 +114,7 @@ void _menu_temp_filament_op(const PauseMode mode, const int8_t extruder) { GCODES_ITEM_P(msg, PSTR("M600 B0")); #else PGM_P const msg = GET_TEXT(MSG_FILAMENTCHANGE_E); - for (uint8_t s = 0; s < E_STEPPERS; s++) { + LOOP_L_N(s, E_STEPPERS) { if (thermalManager.targetTooColdToExtrude(s)) SUBMENU_N_P(s, msg, []{ _menu_temp_filament_op(PAUSE_MODE_CHANGE_FILAMENT, MenuItemBase::itemIndex); }); else { @@ -138,7 +138,7 @@ void _menu_temp_filament_op(const PauseMode mode, const int8_t extruder) { GCODES_ITEM_P(msg_load, PSTR("M701")); #else PGM_P const msg_load = GET_TEXT(MSG_FILAMENTLOAD_E); - for (uint8_t s = 0; s < E_STEPPERS; s++) { + LOOP_L_N(s, E_STEPPERS) { if (thermalManager.targetTooColdToExtrude(s)) SUBMENU_N_P(s, msg_load, []{ _menu_temp_filament_op(PAUSE_MODE_LOAD_FILAMENT, MenuItemBase::itemIndex); }); else { @@ -162,7 +162,7 @@ void _menu_temp_filament_op(const PauseMode mode, const int8_t extruder) { #if ENABLED(FILAMENT_UNLOAD_ALL_EXTRUDERS) { bool too_cold = false; - for (uint8_t s = 0; s < E_STEPPERS; s++) { + LOOP_L_N(s, E_STEPPERS) { if (thermalManager.targetTooColdToExtrude(s)) { too_cold = true; break; } @@ -174,7 +174,7 @@ void _menu_temp_filament_op(const PauseMode mode, const int8_t extruder) { } #endif PGM_P const msg_unload = GET_TEXT(MSG_FILAMENTUNLOAD_E); - for (uint8_t s = 0; s < E_STEPPERS; s++) { + LOOP_L_N(s, E_STEPPERS) { if (thermalManager.targetTooColdToExtrude(s)) SUBMENU_N_P(s, msg_unload, []{ _menu_temp_filament_op(PAUSE_MODE_UNLOAD_FILAMENT, MenuItemBase::itemIndex); }); else { diff --git a/Marlin/src/lcd/menu/menu_job_recovery.cpp b/Marlin/src/lcd/menu/menu_job_recovery.cpp index 5b57992f45..31db50fe23 100644 --- a/Marlin/src/lcd/menu/menu_job_recovery.cpp +++ b/Marlin/src/lcd/menu/menu_job_recovery.cpp @@ -31,7 +31,7 @@ #include "menu.h" #include "../../gcode/queue.h" #include "../../sd/cardreader.h" -#include "../../feature/power_loss_recovery.h" +#include "../../feature/powerloss.h" static void lcd_power_loss_recovery_resume() { ui.return_to_status(); diff --git a/Marlin/src/lcd/menu/menu_mixer.cpp b/Marlin/src/lcd/menu/menu_mixer.cpp index 65b8af20ca..a74fcb6e6a 100644 --- a/Marlin/src/lcd/menu/menu_mixer.cpp +++ b/Marlin/src/lcd/menu/menu_mixer.cpp @@ -181,7 +181,7 @@ void lcd_mixer_mix_edit() { #if CHANNEL_MIX_EDITING - for (uint8_t n = 1; n <= MIXING_STEPPERS; n++) + LOOP_S_LE_N(n, 1, MIXING_STEPPERS) EDIT_ITEM_FAST_N(float52, n, MSG_MIX_COMPONENT_N, &mixer.collector[n-1], 0, 10); ACTION_ITEM(MSG_CYCLE_MIX, _lcd_mixer_cycle_mix); diff --git a/Marlin/src/lcd/menu/menu_mmu2.cpp b/Marlin/src/lcd/menu/menu_mmu2.cpp index c2b8d4ae0a..e2f5e8d658 100644 --- a/Marlin/src/lcd/menu/menu_mmu2.cpp +++ b/Marlin/src/lcd/menu/menu_mmu2.cpp @@ -24,7 +24,7 @@ #if HAS_LCD_MENU && ENABLED(MMU2_MENUS) -#include "../../feature/prusa_MMU2/mmu2.h" +#include "../../feature/mmu2/mmu2.h" #include "menu_mmu2.h" #include "menu.h" @@ -54,7 +54,7 @@ void _mmu2_load_filament(uint8_t index) { ui.reset_status(); } void action_mmu2_load_all() { - for (uint8_t i = 0; i < EXTRUDERS; i++) + LOOP_L_N(i, EXTRUDERS) _mmu2_load_filament(i); ui.return_to_status(); } diff --git a/Marlin/src/lcd/menu/menu_motion.cpp b/Marlin/src/lcd/menu/menu_motion.cpp index 12cc7a331e..b7f57c8146 100644 --- a/Marlin/src/lcd/menu/menu_motion.cpp +++ b/Marlin/src/lcd/menu/menu_motion.cpp @@ -357,7 +357,7 @@ void menu_move() { #elif E_MANUAL > 1 // Independent extruders with one E-stepper per hotend - for (uint8_t n = 0; n < E_MANUAL; n++) SUBMENU_MOVE_E(n); + LOOP_L_N(n, E_MANUAL) SUBMENU_MOVE_E(n); #endif @@ -393,9 +393,9 @@ void menu_motion() { // GCODES_ITEM(MSG_AUTO_HOME, G28_STR); #if ENABLED(INDIVIDUAL_AXIS_HOMING_MENU) - GCODES_ITEM(MSG_AUTO_HOME_X, PSTR("G28 X")); - GCODES_ITEM(MSG_AUTO_HOME_Y, PSTR("G28 Y")); - GCODES_ITEM(MSG_AUTO_HOME_Z, PSTR("G28 Z")); + GCODES_ITEM(MSG_AUTO_HOME_X, PSTR("G28X")); + GCODES_ITEM(MSG_AUTO_HOME_Y, PSTR("G28Y")); + GCODES_ITEM(MSG_AUTO_HOME_Z, PSTR("G28Z")); #endif // diff --git a/Marlin/src/lcd/menu/menu_temperature.cpp b/Marlin/src/lcd/menu/menu_temperature.cpp index 40fb88fcca..01cf39d7b3 100644 --- a/Marlin/src/lcd/menu/menu_temperature.cpp +++ b/Marlin/src/lcd/menu/menu_temperature.cpp @@ -111,7 +111,7 @@ void _lcd_preheat(const int16_t endnum, const int16_t temph, const int16_t tempb #if HAS_HEATED_BED _PREHEAT_ITEMS(1,0); #endif - for (uint8_t n = 1; n < HOTENDS; n++) PREHEAT_ITEMS(1,n); + LOOP_S_L_N(n, 1, HOTENDS) PREHEAT_ITEMS(1,n); ACTION_ITEM(MSG_PREHEAT_1_ALL, []() { #if HAS_HEATED_BED _preheat_bed(0); @@ -139,7 +139,7 @@ void _lcd_preheat(const int16_t endnum, const int16_t temph, const int16_t tempb #if HAS_HEATED_BED _PREHEAT_ITEMS(2,0); #endif - for (uint8_t n = 1; n < HOTENDS; n++) PREHEAT_ITEMS(2,n); + LOOP_S_L_N(n, 1, HOTENDS) PREHEAT_ITEMS(2,n); ACTION_ITEM(MSG_PREHEAT_2_ALL, []() { #if HAS_HEATED_BED _preheat_bed(1); diff --git a/Marlin/src/lcd/menu/menu_tmc.cpp b/Marlin/src/lcd/menu/menu_tmc.cpp index 0350d788eb..296a132e14 100644 --- a/Marlin/src/lcd/menu/menu_tmc.cpp +++ b/Marlin/src/lcd/menu/menu_tmc.cpp @@ -26,7 +26,7 @@ #include "../../inc/MarlinConfigPre.h" -#if HAS_TRINAMIC && HAS_LCD_MENU +#if HAS_TRINAMIC_CONFIG && HAS_LCD_MENU #include "menu.h" #include "../../module/stepper/indirection.h" @@ -249,4 +249,4 @@ void menu_tmc() { END_MENU(); } -#endif // HAS_TRINAMIC +#endif // HAS_TRINAMIC_CONFIG diff --git a/Marlin/src/lcd/menu/menu_tune.cpp b/Marlin/src/lcd/menu/menu_tune.cpp index 9221d77005..216decf718 100644 --- a/Marlin/src/lcd/menu/menu_tune.cpp +++ b/Marlin/src/lcd/menu/menu_tune.cpp @@ -222,7 +222,7 @@ void menu_tune() { EDIT_ITEM(int3, MSG_FLOW, &planner.flow_percentage[active_extruder], 10, 999, []{ planner.refresh_e_factor(active_extruder); }); // Flow En: #if EXTRUDERS > 1 - for (uint8_t n = 0; n < EXTRUDERS; n++) + LOOP_L_N(n, EXTRUDERS) EDIT_ITEM_N(int3, n, MSG_FLOW_N, &planner.flow_percentage[n], 10, 999, []{ planner.refresh_e_factor(MenuItemBase::itemIndex); }); #endif #endif @@ -234,7 +234,7 @@ void menu_tune() { #if EXTRUDERS == 1 EDIT_ITEM(float52, MSG_ADVANCE_K, &planner.extruder_advance_K[0], 0, 999); #elif EXTRUDERS > 1 - for (uint8_t n = 0; n < EXTRUDERS; n++) + LOOP_L_N(n, EXTRUDERS) EDIT_ITEM_N(float52, n, MSG_ADVANCE_K_E, &planner.extruder_advance_K[n], 0, 999); #endif #endif diff --git a/Marlin/src/lcd/ultralcd.cpp b/Marlin/src/lcd/ultralcd.cpp index 422c8b0b81..48129b61ae 100644 --- a/Marlin/src/lcd/ultralcd.cpp +++ b/Marlin/src/lcd/ultralcd.cpp @@ -103,7 +103,7 @@ MarlinUI ui; #include "../feature/bedlevel/bedlevel.h" #endif -#if HAS_TRINAMIC +#if HAS_TRINAMIC_CONFIG #include "../feature/tmc_util.h" #endif @@ -391,7 +391,7 @@ bool MarlinUI::get_blink() { void _reprapworld_keypad_move(const AxisEnum axis, const int16_t dir) { move_menu_scale = REPRAPWORLD_KEYPAD_MOVE_STEP; - encoderPosition = dir; + ui.encoderPosition = dir; switch (axis) { case X_AXIS: lcd_move_x(); break; case Y_AXIS: lcd_move_y(); break; @@ -1136,7 +1136,7 @@ void MarlinUI::update() { thermalManager.current_ADCKey_raw = HAL_ADC_RANGE; thermalManager.ADCKey_count = 0; if (currentkpADCValue < adc_other_button) - for (uint8_t i = 0; i < ADC_KEY_NUM; i++) { + LOOP_L_N(i, ADC_KEY_NUM) { const uint16_t lo = pgm_read_word(&stADCKeyTable[i].ADCKeyValueMin), hi = pgm_read_word(&stADCKeyTable[i].ADCKeyValueMax); if (WITHIN(currentkpADCValue, lo, hi)) return pgm_read_byte(&stADCKeyTable[i].ADCKeyNo); @@ -1149,27 +1149,6 @@ void MarlinUI::update() { #if HAS_ENCODER_ACTION - #if DISABLED(ADC_KEYPAD) && (ENABLED(REPRAPWORLD_KEYPAD) || !HAS_DIGITAL_BUTTONS) - - /** - * Setup Rotary Encoder Bit Values (for two pin encoders to indicate movement) - * These values are independent of which pins are used for EN_A and EN_B indications - * The rotary encoder part is also independent to the chipset used for the LCD - */ - #define GET_SHIFT_BUTTON_STATES(DST) \ - uint8_t new_##DST = 0; \ - WRITE(SHIFT_LD, LOW); \ - WRITE(SHIFT_LD, HIGH); \ - for (int8_t i = 0; i < 8; i++) { \ - new_##DST >>= 1; \ - if (READ(SHIFT_OUT)) SBI(new_##DST, 7); \ - WRITE(SHIFT_CLK, HIGH); \ - WRITE(SHIFT_CLK, LOW); \ - } \ - DST = ~new_##DST; //invert it, because a pressed switch produces a logical 0 - - #endif - /** * Read encoder buttons from the hardware registers * Warning: This function is called from interrupt context! @@ -1267,15 +1246,25 @@ void MarlinUI::update() { #endif #if HAS_SHIFT_ENCODER - - GET_SHIFT_BUTTON_STATES(( - #if ENABLED(REPRAPWORLD_KEYPAD) - keypad_buttons - #else - buttons - #endif - )); - + /** + * Set up Rotary Encoder bit values (for two pin encoders to indicate movement). + * These values are independent of which pins are used for EN_A / EN_B indications. + * The rotary encoder part is also independent of the LCD chipset. + */ + uint8_t val = 0; + WRITE(SHIFT_LD, LOW); + WRITE(SHIFT_LD, HIGH); + LOOP_L_N(i, 8) { + val >>= 1; + if (READ(SHIFT_OUT)) SBI(val, 7); + WRITE(SHIFT_CLK, HIGH); + WRITE(SHIFT_CLK, LOW); + } + #if ENABLED(REPRAPWORLD_KEYPAD) + keypad_buttons = ~val; + #else + buttons = ~val; + #endif #endif } // next_button_update_ms @@ -1320,7 +1309,7 @@ void MarlinUI::update() { #if HAS_DISPLAY #if ENABLED(EXTENSIBLE_UI) - #include "extensible_ui/ui_api.h" + #include "extui/ui_api.h" #endif //////////////////////////////////////////// diff --git a/Marlin/src/lcd/ultralcd.h b/Marlin/src/lcd/ultralcd.h index f614e2009b..1bcf9956fe 100644 --- a/Marlin/src/lcd/ultralcd.h +++ b/Marlin/src/lcd/ultralcd.h @@ -27,10 +27,18 @@ #include "../libs/buzzer.h" #endif -#define HAS_ENCODER_ACTION (HAS_LCD_MENU || ENABLED(ULTIPANEL_FEEDMULTIPLY)) -#define HAS_ENCODER_WHEEL ((!HAS_ADC_BUTTONS && ENABLED(NEWPANEL)) || BUTTONS_EXIST(EN1, EN2)) -#define HAS_DIGITAL_BUTTONS (HAS_ENCODER_WHEEL || ANY_BUTTON(ENC, BACK, UP, DWN, LFT, RT)) -#define HAS_SHIFT_ENCODER (!HAS_ADC_BUTTONS && (ENABLED(REPRAPWORLD_KEYPAD) || (HAS_SPI_LCD && DISABLED(NEWPANEL)))) +#if HAS_LCD_MENU || ENABLED(ULTIPANEL_FEEDMULTIPLY) + #define HAS_ENCODER_ACTION 1 +#endif +#if (!HAS_ADC_BUTTONS && ENABLED(NEWPANEL)) || BUTTONS_EXIST(EN1, EN2) + #define HAS_ENCODER_WHEEL 1 +#endif +#if HAS_ENCODER_WHEEL || ANY_BUTTON(ENC, BACK, UP, DWN, LFT, RT) + #define HAS_DIGITAL_BUTTONS 1 +#endif +#if !HAS_ADC_BUTTONS && (ENABLED(REPRAPWORLD_KEYPAD) || (HAS_SPI_LCD && DISABLED(NEWPANEL))) + #define HAS_SHIFT_ENCODER 1 +#endif // I2C buttons must be read in the main thread #define HAS_SLOW_BUTTONS EITHER(LCD_I2C_VIKI, LCD_I2C_PANELOLU2) @@ -337,6 +345,9 @@ public: #endif #if ENABLED(SHOW_BOOTSCREEN) + #ifndef BOOTSCREEN_TIMEOUT + #define BOOTSCREEN_TIMEOUT 2500 + #endif static void draw_marlin_bootscreen(const bool line2=false); static void show_marlin_bootscreen(); static void show_bootscreen(); diff --git a/Marlin/src/libs/L64XX/L64XX_Marlin.cpp b/Marlin/src/libs/L64XX/L64XX_Marlin.cpp index 37fbf021d1..ad70537141 100644 --- a/Marlin/src/libs/L64XX/L64XX_Marlin.cpp +++ b/Marlin/src/libs/L64XX/L64XX_Marlin.cpp @@ -508,7 +508,7 @@ uint8_t L64XX_Marlin::get_user_input(uint8_t &driver_count, L64XX_axis_t axis_in // Work on the drivers // - for (uint8_t k = 0; k < driver_count; k++) { + LOOP_L_N(k, driver_count) { uint8_t not_found = true; for (j = 1; j <= L64XX::chain[0]; j++) { PGM_P const str = (PGM_P)pgm_read_ptr(&index_to_axis[L64XX::chain[j]]); diff --git a/Marlin/src/libs/buzzer.cpp b/Marlin/src/libs/buzzer.cpp index 35631708c4..3b0a239178 100644 --- a/Marlin/src/libs/buzzer.cpp +++ b/Marlin/src/libs/buzzer.cpp @@ -28,7 +28,7 @@ #include "../module/temperature.h" #if ENABLED(EXTENSIBLE_UI) - #include "../lcd/extensible_ui/ui_api.h" + #include "../lcd/extui/ui_api.h" #endif Buzzer::state_t Buzzer::state; diff --git a/Marlin/src/libs/nozzle.cpp b/Marlin/src/libs/nozzle.cpp index 58ba57e425..ecbfeb331e 100644 --- a/Marlin/src/libs/nozzle.cpp +++ b/Marlin/src/libs/nozzle.cpp @@ -54,7 +54,7 @@ Nozzle nozzle; #endif // Start the stroke pattern - for (uint8_t i = 0; i < (strokes >> 1); i++) { + LOOP_L_N(i, strokes >> 1) { do_blocking_move_to_xy(end); do_blocking_move_to_xy(start); } @@ -91,7 +91,7 @@ Nozzle nozzle; const bool horiz = ABS(diff.x) >= ABS(diff.y); // Do a horizontal wipe? const float P = (horiz ? diff.x : diff.y) / zigs; // Period of each zig / zag const xyz_pos_t *side; - for (uint8_t j = 0; j < strokes; j++) { + LOOP_L_N(j, strokes) { for (int8_t i = 0; i < zigs; i++) { side = (i & 1) ? &end : &start; if (horiz) @@ -134,8 +134,8 @@ Nozzle nozzle; do_blocking_move_to(start); #endif - for (uint8_t s = 0; s < strokes; s++) - for (uint8_t i = 0; i < NOZZLE_CLEAN_CIRCLE_FN; i++) + LOOP_L_N(s, strokes) + LOOP_L_N(i, NOZZLE_CLEAN_CIRCLE_FN) do_blocking_move_to_xy( middle.x + sin((RADIANS(360) / NOZZLE_CLEAN_CIRCLE_FN) * i) * radius, middle.y + cos((RADIANS(360) / NOZZLE_CLEAN_CIRCLE_FN) * i) * radius diff --git a/Marlin/src/libs/numtostr.cpp b/Marlin/src/libs/numtostr.cpp index e5ddc14748..3b641e0dd3 100644 --- a/Marlin/src/libs/numtostr.cpp +++ b/Marlin/src/libs/numtostr.cpp @@ -33,7 +33,7 @@ char conv[8] = { 0 }; #define MINUSOR(n, alt) (n >= 0 ? (alt) : (n = -n, '-')) // Convert a full-range unsigned 8bit int to a percentage -const char* ui8tostr4pct(const uint8_t i) { +const char* ui8tostr4pctrj(const uint8_t i) { const uint8_t n = ui8_to_percent(i); conv[3] = RJDIGIT(n, 100); conv[4] = RJDIGIT(n, 10); @@ -43,7 +43,7 @@ const char* ui8tostr4pct(const uint8_t i) { } // Convert unsigned 8bit int to string 123 format -const char* ui8tostr3(const uint8_t i) { +const char* ui8tostr3rj(const uint8_t i) { conv[4] = RJDIGIT(i, 100); conv[5] = RJDIGIT(i, 10); conv[6] = DIGIMOD(i, 1); @@ -51,7 +51,7 @@ const char* ui8tostr3(const uint8_t i) { } // Convert signed 8bit int to rj string with 123 or -12 format -const char* i8tostr3(const int8_t x) { +const char* i8tostr3rj(const int8_t x) { int xx = x; conv[4] = MINUSOR(xx, RJDIGIT(xx, 100)); conv[5] = RJDIGIT(xx, 10); @@ -88,7 +88,7 @@ const char* i8tostr3(const int8_t x) { #endif // Convert unsigned 16bit int to string 12345 format -const char* ui16tostr5(const uint16_t xx) { +const char* ui16tostr5rj(const uint16_t xx) { conv[2] = RJDIGIT(xx, 10000); conv[3] = RJDIGIT(xx, 1000); conv[4] = RJDIGIT(xx, 100); @@ -98,7 +98,7 @@ const char* ui16tostr5(const uint16_t xx) { } // Convert unsigned 16bit int to string 1234 format -const char* ui16tostr4(const uint16_t xx) { +const char* ui16tostr4rj(const uint16_t xx) { conv[3] = RJDIGIT(xx, 1000); conv[4] = RJDIGIT(xx, 100); conv[5] = RJDIGIT(xx, 10); @@ -107,7 +107,7 @@ const char* ui16tostr4(const uint16_t xx) { } // Convert unsigned 16bit int to string 123 format -const char* ui16tostr3(const uint16_t xx) { +const char* ui16tostr3rj(const uint16_t xx) { conv[4] = RJDIGIT(xx, 100); conv[5] = RJDIGIT(xx, 10); conv[6] = DIGIMOD(xx, 1); @@ -115,7 +115,7 @@ const char* ui16tostr3(const uint16_t xx) { } // Convert signed 16bit int to rj string with 123 or -12 format -const char* i16tostr3(const int16_t x) { +const char* i16tostr3rj(const int16_t x) { int xx = x; conv[4] = MINUSOR(xx, RJDIGIT(xx, 100)); conv[5] = RJDIGIT(xx, 10); @@ -136,7 +136,7 @@ const char* i16tostr3left(const int16_t i) { } // Convert signed 16bit int to rj string with 1234, _123, -123, _-12, or __-1 format -const char* i16tostr4sign(const int16_t i) { +const char* i16tostr4signrj(const int16_t i) { const bool neg = i < 0; const int ii = neg ? -i : i; if (i >= 1000) { @@ -174,7 +174,7 @@ const char* ftostr12ns(const float &f) { return &conv[3]; } -// Convert signed float to fixed-length string with 12.34 / -2.34 format or 123.45 / -23.45 format +// Convert signed float to fixed-length string with 12.34 / -2.34 or 023.45 / -23.45 format const char* ftostr42_52(const float &f) { if (f <= -10 || f >= 100) return ftostr52(f); // need more digits long i = (f * 1000 + (f < 0 ? -5: 5)) / 10; @@ -198,12 +198,38 @@ const char* ftostr52(const float &f) { return &conv[1]; } +// Convert signed float to fixed-length string with 12.345 / -2.345 or 023.456 / -23.456 format +const char* ftostr43_53(const float &f) { + if (f <= -10 || f >= 100) return ftostr53(f); // need more digits + long i = (f * 10000 + (f < 0 ? -5: 5)) / 10; + conv[1] = (f >= 0 && f < 10) ? ' ' : MINUSOR(i, DIGIMOD(i, 10000)); + conv[2] = DIGIMOD(i, 1000); + conv[3] = '.'; + conv[4] = DIGIMOD(i, 100); + conv[5] = DIGIMOD(i, 10); + conv[6] = DIGIMOD(i, 1); + return &conv[1]; +} + +// Convert signed float to fixed-length string with 023.456 / -23.456 format +const char* ftostr53(const float &f) { + long i = (f * 10000 + (f < 0 ? -5: 5)) / 10; + conv[0] = MINUSOR(i, DIGIMOD(i, 100000)); + conv[1] = DIGIMOD(i, 10000); + conv[2] = DIGIMOD(i, 1000); + conv[3] = '.'; + conv[4] = DIGIMOD(i, 100); + conv[5] = DIGIMOD(i, 10); + conv[6] = DIGIMOD(i, 1); + return &conv[0]; +} + #if ENABLED(LCD_DECIMAL_SMALL_XY) // Convert float to rj string with 1234, _123, -123, _-12, 12.3, _1.2, or -1.2 format const char* ftostr4sign(const float &f) { const int i = (f * 100 + (f < 0 ? -5: 5)) / 10; - if (!WITHIN(i, -99, 999)) return i16tostr4sign((int)f); + if (!WITHIN(i, -99, 999)) return i16tostr4signrj((int)f); const bool neg = i < 0; const int ii = neg ? -i : i; conv[3] = neg ? '-' : (ii >= 100 ? DIGIMOD(ii, 100) : ' '); @@ -255,7 +281,7 @@ const char* ftostr54sign(const float &f, char plus/*=' '*/) { // Convert unsigned float to rj string with 12345 format const char* ftostr5rj(const float &f) { const long i = ((f < 0 ? -f : f) * 10 + 5) / 10; - return ui16tostr5(i); + return ui16tostr5rj(i); } // Convert signed float to string with +1234.5 format @@ -284,7 +310,7 @@ const char* ftostr52sign(const float &f) { return conv; } -// Convert unsigned float to string with 1234.5 format omitting trailing zeros +// Convert unsigned float to string with ____4.5, __34.5, _234.5, 1234.5 format const char* ftostr51rj(const float &f) { const long i = ((f < 0 ? -f : f) * 100 + 5) / 10; conv[0] = ' '; diff --git a/Marlin/src/libs/numtostr.h b/Marlin/src/libs/numtostr.h index ee29b26ab0..d5453e8176 100644 --- a/Marlin/src/libs/numtostr.h +++ b/Marlin/src/libs/numtostr.h @@ -24,13 +24,13 @@ #include // Convert a full-range unsigned 8bit int to a percentage -const char* ui8tostr4pct(const uint8_t i); +const char* ui8tostr4pctrj(const uint8_t i); // Convert uint8_t to string with 123 format -const char* ui8tostr3(const uint8_t i); +const char* ui8tostr3rj(const uint8_t i); // Convert int8_t to string with 123 format -const char* i8tostr3(const int8_t x); +const char* i8tostr3rj(const int8_t x); #if HAS_PRINT_PROGRESS_PERMYRIAD // Convert 16-bit unsigned permyriad value to percent: 100 / 23 / 23.4 / 3.45 @@ -38,22 +38,22 @@ const char* i8tostr3(const int8_t x); #endif // Convert uint16_t to string with 12345 format -const char* ui16tostr5(const uint16_t x); +const char* ui16tostr5rj(const uint16_t x); // Convert uint16_t to string with 1234 format -const char* ui16tostr4(const uint16_t x); +const char* ui16tostr4rj(const uint16_t x); // Convert uint16_t to string with 123 format -const char* ui16tostr3(const uint16_t x); +const char* ui16tostr3rj(const uint16_t x); // Convert int16_t to string with 123 format -const char* i16tostr3(const int16_t x); +const char* i16tostr3rj(const int16_t x); // Convert unsigned int to lj string with 123 format const char* i16tostr3left(const int16_t xx); // Convert signed int to rj string with _123, -123, _-12, or __-1 format -const char* i16tostr4sign(const int16_t x); +const char* i16tostr4signrj(const int16_t x); // Convert unsigned float to string with 1.23 format const char* ftostr12ns(const float &x); @@ -64,6 +64,12 @@ const char* ftostr42_52(const float &x); // Convert signed float to fixed-length string with 023.45 / -23.45 format const char* ftostr52(const float &x); +// Convert signed float to fixed-length string with 12.345 / -2.345 or 023.456 / -23.456 format +const char* ftostr43_53(const float &x); + +// Convert signed float to fixed-length string with 023.456 / -23.456 format +const char* ftostr53(const float &x); + // Convert float to fixed-length string with +123.4 / -123.4 format const char* ftostr41sign(const float &x); @@ -91,7 +97,7 @@ const char* ftostr51rj(const float &x); #include "../core/macros.h" // Convert float to rj string with 123 or -12 format -FORCE_INLINE const char* ftostr3(const float &x) { return i16tostr3(int16_t(x + (x < 0 ? -0.5f : 0.5f))); } +FORCE_INLINE const char* ftostr3(const float &x) { return i16tostr3rj(int16_t(x + (x < 0 ? -0.5f : 0.5f))); } #include "../inc/MarlinConfigPre.h" @@ -100,5 +106,5 @@ FORCE_INLINE const char* ftostr3(const float &x) { return i16tostr3(int16_t(x + const char* ftostr4sign(const float &fx); #else // Convert float to rj string with 1234, _123, -123, __12, _-12, ___1, or __-1 format - FORCE_INLINE const char* ftostr4sign(const float &x) { return i16tostr4sign(int16_t(x + (x < 0 ? -0.5f : 0.5f))); } + FORCE_INLINE const char* ftostr4sign(const float &x) { return i16tostr4signrj(int16_t(x + (x < 0 ? -0.5f : 0.5f))); } #endif diff --git a/Marlin/src/libs/stopwatch.cpp b/Marlin/src/libs/stopwatch.cpp index fe80b17462..6b01158cb9 100644 --- a/Marlin/src/libs/stopwatch.cpp +++ b/Marlin/src/libs/stopwatch.cpp @@ -25,7 +25,7 @@ #include "../inc/MarlinConfig.h" #if ENABLED(EXTENSIBLE_UI) - #include "../lcd/extensible_ui/ui_api.h" + #include "../lcd/extui/ui_api.h" #endif Stopwatch::State Stopwatch::state; diff --git a/Marlin/src/libs/vector_3.cpp b/Marlin/src/libs/vector_3.cpp index d2af0f3d56..c0da29e702 100644 --- a/Marlin/src/libs/vector_3.cpp +++ b/Marlin/src/libs/vector_3.cpp @@ -96,8 +96,8 @@ void apply_rotation_xyz(const matrix_3x3 &matrix, float &_x, float &_y, float &_ // Reset to identity. No rotate or translate. void matrix_3x3::set_to_identity() { - for (uint8_t i = 0; i < 3; i++) - for (uint8_t j = 0; j < 3; j++) + LOOP_L_N(i, 3) + LOOP_L_N(j, 3) vectors[i][j] = float(i == j); } @@ -134,8 +134,8 @@ matrix_3x3 matrix_3x3::create_look_at(const vector_3 &target) { // Get a transposed copy of the matrix matrix_3x3 matrix_3x3::transpose(const matrix_3x3 &original) { matrix_3x3 new_matrix; - for (uint8_t i = 0; i < 3; i++) - for (uint8_t j = 0; j < 3; j++) + LOOP_L_N(i, 3) + LOOP_L_N(j, 3) new_matrix.vectors[i][j] = original.vectors[j][i]; return new_matrix; } @@ -145,8 +145,8 @@ void matrix_3x3::debug(PGM_P const title) { serialprintPGM(title); SERIAL_EOL(); } - for (uint8_t i = 0; i < 3; i++) { - for (uint8_t j = 0; j < 3; j++) { + LOOP_L_N(i, 3) { + LOOP_L_N(j, 3) { if (vectors[i][j] >= 0.0) SERIAL_CHAR('+'); SERIAL_ECHO_F(vectors[i][j], 6); SERIAL_CHAR(' '); diff --git a/Marlin/src/module/configuration_store.cpp b/Marlin/src/module/configuration_store.cpp index 3fe38d4ade..eb77325094 100644 --- a/Marlin/src/module/configuration_store.cpp +++ b/Marlin/src/module/configuration_store.cpp @@ -71,7 +71,7 @@ #endif #if ENABLED(EXTENSIBLE_UI) - #include "../lcd/extensible_ui/ui_api.h" + #include "../lcd/extui/ui_api.h" #endif #if HAS_SERVOS @@ -87,7 +87,7 @@ #include "../feature/fwretract.h" #if ENABLED(POWER_LOSS_RECOVERY) - #include "../feature/power_loss_recovery.h" + #include "../feature/powerloss.h" #endif #include "../feature/pause.h" @@ -101,7 +101,7 @@ #endif #if ENABLED(EXTRA_LIN_ADVANCE_K) - extern float saved_extruder_advance_K[EXTRUDERS]; + extern float other_extruder_advance_K[EXTRUDERS]; #endif #if EXTRUDERS > 1 @@ -113,13 +113,13 @@ #include "../feature/bltouch.h" #endif -#if HAS_TRINAMIC +#if HAS_TRINAMIC_CONFIG #include "stepper/indirection.h" #include "../feature/tmc_util.h" #endif #if ENABLED(PROBE_TEMP_COMPENSATION) - #include "../feature/probe_temp_compensation.h" + #include "../feature/probe_temp_comp.h" #endif #pragma pack(push, 1) // No padding between variables @@ -181,11 +181,8 @@ typedef struct SettingsDataStruct { // float mbl_z_offset; // mbl.z_offset uint8_t mesh_num_x, mesh_num_y; // GRID_MAX_POINTS_X, GRID_MAX_POINTS_Y - #if ENABLED(MESH_BED_LEVELING) - float mbl_z_values[GRID_MAX_POINTS_X][GRID_MAX_POINTS_Y]; // mbl.z_values - #else - float mbl_z_values[3][3]; - #endif + float mbl_z_values[TERN(MESH_BED_LEVELING, GRID_MAX_POINTS_X, 3)] // mbl.z_values + [TERN(MESH_BED_LEVELING, GRID_MAX_POINTS_Y, 3)]; // // HAS_BED_PROBE @@ -313,7 +310,7 @@ typedef struct SettingsDataStruct { float planner_filament_size[EXTRUDERS]; // M200 T D planner.filament_size[] // - // HAS_TRINAMIC + // HAS_TRINAMIC_CONFIG // tmc_stepper_current_t tmc_stepper_current; // M906 X Y Z X2 Y2 Z2 Z3 Z4 E0 E1 E2 E3 E4 E5 tmc_hybrid_threshold_t tmc_hybrid_threshold; // M913 X Y Z X2 Y2 Z2 Z3 Z4 E0 E1 E2 E3 E4 E5 @@ -525,7 +522,7 @@ void MarlinSettings::postprocess() { * M500 - Store Configuration */ bool MarlinSettings::save() { - float dummy = 0; + float dummyf = 0; char ver[4] = "ERR"; uint16_t working_crc = 0; @@ -533,11 +530,10 @@ void MarlinSettings::postprocess() { EEPROM_START(); eeprom_error = false; - #if ENABLED(FLASH_EEPROM_EMULATION) - EEPROM_SKIP(ver); // Flash doesn't allow rewriting without erase - #else - EEPROM_WRITE(ver); // invalidate data first - #endif + + // Write or Skip version. (Flash doesn't allow rewrite without erase.) + TERN(FLASH_EEPROM_EMULATION, EEPROM_SKIP, EEPROM_WRITE)(ver); + EEPROM_SKIP(working_crc); // Skip the checksum slot working_crc = 0; // clear before first "real data" @@ -556,20 +552,18 @@ void MarlinSettings::postprocess() { #if HAS_CLASSIC_JERK EEPROM_WRITE(planner.max_jerk); #if HAS_LINEAR_E_JERK - dummy = float(DEFAULT_EJERK); - EEPROM_WRITE(dummy); + dummyf = float(DEFAULT_EJERK); + EEPROM_WRITE(dummyf); #endif #else const xyze_pos_t planner_max_jerk = { 10, 10, 0.4, float(DEFAULT_EJERK) }; EEPROM_WRITE(planner_max_jerk); #endif - #if DISABLED(CLASSIC_JERK) - EEPROM_WRITE(planner.junction_deviation_mm); - #else - dummy = 0.02f; - EEPROM_WRITE(dummy); + #if ENABLED(CLASSIC_JERK) + dummyf = 0.02f; #endif + EEPROM_WRITE(TERN(CLASSIC_JERK, dummyf, planner.junction_deviation_mm)); } // @@ -589,7 +583,7 @@ void MarlinSettings::postprocess() { #if HAS_HOTEND_OFFSET // Skip hotend 0 which must be 0 - for (uint8_t e = 1; e < HOTENDS; e++) + LOOP_S_L_N(e, 1, HOTENDS) EEPROM_WRITE(hotend_offset[e]); #endif } @@ -617,13 +611,7 @@ void MarlinSettings::postprocess() { // Global Leveling // { - const float zfh = ( - #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) - planner.z_fade_height - #else - 10.0 - #endif - ); + const float zfh = TERN(ENABLE_LEVELING_FADE_HEIGHT, planner.z_fade_height, 10.0f); EEPROM_WRITE(zfh); } @@ -632,23 +620,25 @@ void MarlinSettings::postprocess() { // { #if ENABLED(MESH_BED_LEVELING) - // Compile time test that sizeof(mbl.z_values) is as expected static_assert( sizeof(mbl.z_values) == (GRID_MAX_POINTS) * sizeof(mbl.z_values[0][0]), "MBL Z array is the wrong size." ); - const uint8_t mesh_num_x = GRID_MAX_POINTS_X, mesh_num_y = GRID_MAX_POINTS_Y; - EEPROM_WRITE(mbl.z_offset); - EEPROM_WRITE(mesh_num_x); - EEPROM_WRITE(mesh_num_y); + #else + dummyf = 0; + #endif + + const uint8_t mesh_num_x = TERN(MESH_BED_LEVELING, GRID_MAX_POINTS_X, 3), + mesh_num_y = TERN(MESH_BED_LEVELING, GRID_MAX_POINTS_Y, 3); + + EEPROM_WRITE(TERN(MESH_BED_LEVELING, mbl.z_offset, dummyf)); + EEPROM_WRITE(mesh_num_x); + EEPROM_WRITE(mesh_num_y); + + #if ENABLED(MESH_BED_LEVELING) EEPROM_WRITE(mbl.z_values); - #else // For disabled MBL write a default mesh - dummy = 0; - const uint8_t mesh_num_x = 3, mesh_num_y = 3; - EEPROM_WRITE(dummy); // z_offset - EEPROM_WRITE(mesh_num_x); - EEPROM_WRITE(mesh_num_y); - for (uint8_t q = mesh_num_x * mesh_num_y; q--;) EEPROM_WRITE(dummy); + #else + for (uint8_t q = mesh_num_x * mesh_num_y; q--;) EEPROM_WRITE(dummyf); #endif } @@ -672,8 +662,8 @@ void MarlinSettings::postprocess() { #if ABL_PLANAR EEPROM_WRITE(planner.bed_level_matrix); #else - dummy = 0; - for (uint8_t q = 9; q--;) EEPROM_WRITE(dummy); + dummyf = 0; + for (uint8_t q = 9; q--;) EEPROM_WRITE(dummyf); #endif } @@ -682,27 +672,26 @@ void MarlinSettings::postprocess() { // { #if ENABLED(AUTO_BED_LEVELING_BILINEAR) - // Compile time test that sizeof(z_values) is as expected static_assert( sizeof(z_values) == (GRID_MAX_POINTS) * sizeof(z_values[0][0]), "Bilinear Z array is the wrong size." ); - const uint8_t grid_max_x = GRID_MAX_POINTS_X, grid_max_y = GRID_MAX_POINTS_Y; - EEPROM_WRITE(grid_max_x); // 1 byte - EEPROM_WRITE(grid_max_y); // 1 byte - EEPROM_WRITE(bilinear_grid_spacing); // 2 ints - EEPROM_WRITE(bilinear_start); // 2 ints + #else + const xy_pos_t bilinear_start{0}, bilinear_grid_spacing{0}; + #endif + + const uint8_t grid_max_x = TERN(AUTO_BED_LEVELING_BILINEAR, GRID_MAX_POINTS_X, 3), + grid_max_y = TERN(AUTO_BED_LEVELING_BILINEAR, GRID_MAX_POINTS_Y, 3); + EEPROM_WRITE(grid_max_x); + EEPROM_WRITE(grid_max_y); + EEPROM_WRITE(bilinear_grid_spacing); + EEPROM_WRITE(bilinear_start); + + #if ENABLED(AUTO_BED_LEVELING_BILINEAR) EEPROM_WRITE(z_values); // 9-256 floats #else - // For disabled Bilinear Grid write an empty 3x3 grid - const uint8_t grid_max_x = 3, grid_max_y = 3; - const xy_pos_t bilinear_start{0}, bilinear_grid_spacing{0}; - dummy = 0; - EEPROM_WRITE(grid_max_x); - EEPROM_WRITE(grid_max_y); - EEPROM_WRITE(bilinear_grid_spacing); - EEPROM_WRITE(bilinear_start); - for (uint16_t q = grid_max_x * grid_max_y; q--;) EEPROM_WRITE(dummy); + dummyf = 0; + for (uint16_t q = grid_max_x * grid_max_y; q--;) EEPROM_WRITE(dummyf); #endif } @@ -711,16 +700,10 @@ void MarlinSettings::postprocess() { // { _FIELD_TEST(planner_leveling_active); - - #if ENABLED(AUTO_BED_LEVELING_UBL) - EEPROM_WRITE(planner.leveling_active); - EEPROM_WRITE(ubl.storage_slot); - #else - const bool ubl_active = false; - const int8_t storage_slot = -1; - EEPROM_WRITE(ubl_active); - EEPROM_WRITE(storage_slot); - #endif // AUTO_BED_LEVELING_UBL + const bool ubl_active = TERN(AUTO_BED_LEVELING_UBL, planner.leveling_active, false); + const int8_t storage_slot = TERN(AUTO_BED_LEVELING_UBL, ubl.storage_slot, -1); + EEPROM_WRITE(ubl_active); + EEPROM_WRITE(storage_slot); } // @@ -728,7 +711,6 @@ void MarlinSettings::postprocess() { // { _FIELD_TEST(servo_angles); - #if !HAS_SERVO_ANGLES uint16_t servo_angles[EEPROM_NUM_SERVOS][2] = { { 0, 0 } }; #endif @@ -753,11 +735,7 @@ void MarlinSettings::postprocess() { // { _FIELD_TEST(bltouch_last_written_mode); - #if ENABLED(BLTOUCH) - const bool &bltouch_last_written_mode = bltouch.last_written_mode; - #else - constexpr bool bltouch_last_written_mode = false; - #endif + const bool bltouch_last_written_mode = TERN(BLTOUCH, bltouch.last_written_mode, false); EEPROM_WRITE(bltouch_last_written_mode); } @@ -781,35 +759,21 @@ void MarlinSettings::postprocess() { _FIELD_TEST(x2_endstop_adj); // Write dual endstops in X, Y, Z order. Unused = 0.0 - dummy = 0; - #if ENABLED(X_DUAL_ENDSTOPS) - EEPROM_WRITE(endstops.x2_endstop_adj); // 1 float - #else - EEPROM_WRITE(dummy); - #endif - - #if ENABLED(Y_DUAL_ENDSTOPS) - EEPROM_WRITE(endstops.y2_endstop_adj); // 1 float - #else - EEPROM_WRITE(dummy); - #endif - - #if ENABLED(Z_MULTI_ENDSTOPS) - EEPROM_WRITE(endstops.z2_endstop_adj); // 1 float - #else - EEPROM_WRITE(dummy); - #endif + dummyf = 0; + EEPROM_WRITE(TERN(X_DUAL_ENDSTOPS, endstops.x2_endstop_adj, dummyf)); // 1 float + EEPROM_WRITE(TERN(Y_DUAL_ENDSTOPS, endstops.y2_endstop_adj, dummyf)); // 1 float + EEPROM_WRITE(TERN(Z_MULTI_ENDSTOPS, endstops.z2_endstop_adj, dummyf)); // 1 float #if ENABLED(Z_MULTI_ENDSTOPS) && NUM_Z_STEPPER_DRIVERS >= 3 EEPROM_WRITE(endstops.z3_endstop_adj); // 1 float #else - EEPROM_WRITE(dummy); + EEPROM_WRITE(dummyf); #endif #if ENABLED(Z_MULTI_ENDSTOPS) && NUM_Z_STEPPER_DRIVERS >= 4 EEPROM_WRITE(endstops.z4_endstop_adj); // 1 float #else - EEPROM_WRITE(dummy); + EEPROM_WRITE(dummyf); #endif #endif @@ -851,8 +815,8 @@ void MarlinSettings::postprocess() { HOTEND_LOOP() { PIDCF_t pidcf = { #if DISABLED(PIDTEMP) - DUMMY_PID_VALUE, DUMMY_PID_VALUE, DUMMY_PID_VALUE, - DUMMY_PID_VALUE, DUMMY_PID_VALUE + NAN, NAN, NAN, + NAN, NAN #else PID_PARAM(Kp, e), unscalePID_i(PID_PARAM(Ki, e)), @@ -865,12 +829,10 @@ void MarlinSettings::postprocess() { } _FIELD_TEST(lpq_len); - #if ENABLED(PID_EXTRUSION_SCALING) - EEPROM_WRITE(thermalManager.lpq_len); - #else + #if DISABLED(PID_EXTRUSION_SCALING) const int16_t lpq_len = 20; - EEPROM_WRITE(lpq_len); #endif + EEPROM_WRITE(TERN(PID_EXTRUSION_SCALING, thermalManager.lpq_len, lpq_len)); } // @@ -881,7 +843,7 @@ void MarlinSettings::postprocess() { const PID_t bed_pid = { #if DISABLED(PIDTEMPBED) - DUMMY_PID_VALUE, DUMMY_PID_VALUE, DUMMY_PID_VALUE + NAN, NAN, NAN #else // Store the unscaled PID values thermalManager.temp_bed.pid.Kp, @@ -911,8 +873,6 @@ void MarlinSettings::postprocess() { const int16_t lcd_contrast = #if HAS_LCD_CONTRAST ui.contrast - #elif defined(DEFAULT_LCD_CONTRAST) - DEFAULT_LCD_CONTRAST #else 127 #endif @@ -925,14 +885,7 @@ void MarlinSettings::postprocess() { // { _FIELD_TEST(recovery_enabled); - - const bool recovery_enabled = - #if ENABLED(POWER_LOSS_RECOVERY) - recovery.enabled - #else - true - #endif - ; + const bool recovery_enabled = TERN(POWER_LOSS_RECOVERY, recovery.enabled, ENABLED(PLR_ENABLED_DEFAULT)); EEPROM_WRITE(recovery_enabled); } @@ -941,19 +894,15 @@ void MarlinSettings::postprocess() { // { _FIELD_TEST(fwretract_settings); - - #if ENABLED(FWRETRACT) - EEPROM_WRITE(fwretract.settings); - #else + #if DISABLED(FWRETRACT) const fwretract_settings_t autoretract_defaults = { 3, 45, 0, 0, 0, 13, 0, 8 }; - EEPROM_WRITE(autoretract_defaults); #endif - #if BOTH(FWRETRACT, FWRETRACT_AUTORETRACT) - EEPROM_WRITE(fwretract.autoretract_enabled); - #else + EEPROM_WRITE(TERN(FWRETRACT, fwretract.settings, autoretract_defaults)); + + #if DISABLED(FWRETRACT_AUTORETRACT) const bool autoretract_enabled = false; - EEPROM_WRITE(autoretract_enabled); #endif + EEPROM_WRITE(TERN(FWRETRACT_AUTORETRACT, fwretract.autoretract_enabled, autoretract_enabled)); } // @@ -970,9 +919,9 @@ void MarlinSettings::postprocess() { #else const bool volumetric_enabled = false; - dummy = DEFAULT_NOMINAL_FILAMENT_DIA; + dummyf = DEFAULT_NOMINAL_FILAMENT_DIA; EEPROM_WRITE(volumetric_enabled); - for (uint8_t q = EXTRUDERS; q--;) EEPROM_WRITE(dummy); + for (uint8_t q = EXTRUDERS; q--;) EEPROM_WRITE(dummyf); #endif } @@ -985,7 +934,7 @@ void MarlinSettings::postprocess() { tmc_stepper_current_t tmc_stepper_current = { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 }; - #if HAS_TRINAMIC + #if HAS_TRINAMIC_CONFIG #if AXIS_IS_TMC(X) tmc_stepper_current.X = stepperX.getMilliamps(); #endif @@ -1245,8 +1194,8 @@ void MarlinSettings::postprocess() { #if ENABLED(LIN_ADVANCE) EEPROM_WRITE(planner.extruder_advance_K); #else - dummy = 0; - for (uint8_t q = _MAX(EXTRUDERS, 1); q--;) EEPROM_WRITE(dummy); + dummyf = 0; + for (uint8_t q = _MAX(EXTRUDERS, 1); q--;) EEPROM_WRITE(dummyf); #endif } @@ -1270,12 +1219,10 @@ void MarlinSettings::postprocess() { _FIELD_TEST(coordinate_system); - #if ENABLED(CNC_COORDINATE_SYSTEMS) - EEPROM_WRITE(gcode.coordinate_system); - #else + #if DISABLED(CNC_COORDINATE_SYSTEMS) const xyz_pos_t coordinate_system[MAX_COORDINATE_SYSTEMS] = { { 0 } }; - EEPROM_WRITE(coordinate_system); #endif + EEPROM_WRITE(TERN(CNC_COORDINATE_SYSTEMS, gcode.coordinate_system, coordinate_system)); // // Skew correction factors @@ -1403,7 +1350,7 @@ void MarlinSettings::postprocess() { eeprom_error = true; } else { - float dummy = 0; + float dummyf = 0; working_crc = 0; // Init to 0. Accumulated by EEPROM_READ _FIELD_TEST(esteppers); @@ -1442,17 +1389,13 @@ void MarlinSettings::postprocess() { #if HAS_CLASSIC_JERK EEPROM_READ(planner.max_jerk); #if HAS_LINEAR_E_JERK - EEPROM_READ(dummy); + EEPROM_READ(dummyf); #endif #else - for (uint8_t q = 4; q--;) EEPROM_READ(dummy); + for (uint8_t q = 4; q--;) EEPROM_READ(dummyf); #endif - #if DISABLED(CLASSIC_JERK) - EEPROM_READ(planner.junction_deviation_mm); - #else - EEPROM_READ(dummy); - #endif + EEPROM_READ(TERN(CLASSIC_JERK, dummyf, planner.junction_deviation_mm)); } // @@ -1477,7 +1420,7 @@ void MarlinSettings::postprocess() { { #if HAS_HOTEND_OFFSET // Skip hotend 0 which must be 0 - for (uint8_t e = 1; e < HOTENDS; e++) + LOOP_S_L_N(e, 1, HOTENDS) EEPROM_READ(hotend_offset[e]); #endif } @@ -1504,25 +1447,19 @@ void MarlinSettings::postprocess() { // // Global Leveling // - { - #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) - EEPROM_READ(new_z_fade_height); - #else - EEPROM_READ(dummy); - #endif - } + EEPROM_READ(TERN(ENABLE_LEVELING_FADE_HEIGHT, new_z_fade_height, dummyf)); // // Mesh (Manual) Bed Leveling // { uint8_t mesh_num_x, mesh_num_y; - EEPROM_READ(dummy); + EEPROM_READ(dummyf); EEPROM_READ_ALWAYS(mesh_num_x); EEPROM_READ_ALWAYS(mesh_num_y); #if ENABLED(MESH_BED_LEVELING) - if (!validating) mbl.z_offset = dummy; + if (!validating) mbl.z_offset = dummyf; if (mesh_num_x == GRID_MAX_POINTS_X && mesh_num_y == GRID_MAX_POINTS_Y) { // EEPROM data fits the current mesh EEPROM_READ(mbl.z_values); @@ -1530,11 +1467,11 @@ void MarlinSettings::postprocess() { else { // EEPROM data is stale if (!validating) mbl.reset(); - for (uint16_t q = mesh_num_x * mesh_num_y; q--;) EEPROM_READ(dummy); + for (uint16_t q = mesh_num_x * mesh_num_y; q--;) EEPROM_READ(dummyf); } #else // MBL is disabled - skip the stored data - for (uint16_t q = mesh_num_x * mesh_num_y; q--;) EEPROM_READ(dummy); + for (uint16_t q = mesh_num_x * mesh_num_y; q--;) EEPROM_READ(dummyf); #endif // MESH_BED_LEVELING } @@ -1558,7 +1495,7 @@ void MarlinSettings::postprocess() { #if ABL_PLANAR EEPROM_READ(planner.bed_level_matrix); #else - for (uint8_t q = 9; q--;) EEPROM_READ(dummy); + for (uint8_t q = 9; q--;) EEPROM_READ(dummyf); #endif } @@ -1567,8 +1504,8 @@ void MarlinSettings::postprocess() { // { uint8_t grid_max_x, grid_max_y; - EEPROM_READ_ALWAYS(grid_max_x); // 1 byte - EEPROM_READ_ALWAYS(grid_max_y); // 1 byte + EEPROM_READ_ALWAYS(grid_max_x); // 1 byte + EEPROM_READ_ALWAYS(grid_max_y); // 1 byte #if ENABLED(AUTO_BED_LEVELING_BILINEAR) if (grid_max_x == GRID_MAX_POINTS_X && grid_max_y == GRID_MAX_POINTS_Y) { if (!validating) set_bed_leveling_enabled(false); @@ -1583,7 +1520,7 @@ void MarlinSettings::postprocess() { xy_pos_t bgs, bs; EEPROM_READ(bgs); EEPROM_READ(bs); - for (uint16_t q = grid_max_x * grid_max_y; q--;) EEPROM_READ(dummy); + for (uint16_t q = grid_max_x * grid_max_y; q--;) EEPROM_READ(dummyf); } } @@ -1592,16 +1529,15 @@ void MarlinSettings::postprocess() { // { _FIELD_TEST(planner_leveling_active); - #if ENABLED(AUTO_BED_LEVELING_UBL) - EEPROM_READ(planner.leveling_active); - EEPROM_READ(ubl.storage_slot); + const bool &planner_leveling_active = planner.leveling_active; + const uint8_t &ubl_storage_slot = ubl.storage_slot; #else bool planner_leveling_active; uint8_t ubl_storage_slot; - EEPROM_READ(planner_leveling_active); - EEPROM_READ(ubl_storage_slot); #endif + EEPROM_READ(planner_leveling_active); + EEPROM_READ(ubl_storage_slot); } // @@ -1609,7 +1545,6 @@ void MarlinSettings::postprocess() { // { _FIELD_TEST(servo_angles); - #if ENABLED(EDITABLE_SERVO_ANGLES) uint16_t (&servo_angles_arr)[EEPROM_NUM_SERVOS][2] = servo_angles; #else @@ -1664,30 +1599,19 @@ void MarlinSettings::postprocess() { _FIELD_TEST(x2_endstop_adj); - #if ENABLED(X_DUAL_ENDSTOPS) - EEPROM_READ(endstops.x2_endstop_adj); // 1 float - #else - EEPROM_READ(dummy); - #endif - #if ENABLED(Y_DUAL_ENDSTOPS) - EEPROM_READ(endstops.y2_endstop_adj); // 1 float - #else - EEPROM_READ(dummy); - #endif - #if ENABLED(Z_MULTI_ENDSTOPS) - EEPROM_READ(endstops.z2_endstop_adj); // 1 float - #else - EEPROM_READ(dummy); - #endif + EEPROM_READ(TERN(X_DUAL_ENDSTOPS, endstops.x2_endstop_adj, dummyf)); // 1 float + EEPROM_READ(TERN(Y_DUAL_ENDSTOPS, endstops.y2_endstop_adj, dummyf)); // 1 float + EEPROM_READ(TERN(Z_MULTI_ENDSTOPS, endstops.z2_endstop_adj, dummyf)); // 1 float + #if ENABLED(Z_MULTI_ENDSTOPS) && NUM_Z_STEPPER_DRIVERS >= 3 EEPROM_READ(endstops.z3_endstop_adj); // 1 float #else - EEPROM_READ(dummy); + EEPROM_READ(dummyf); #endif #if ENABLED(Z_MULTI_ENDSTOPS) && NUM_Z_STEPPER_DRIVERS >= 4 EEPROM_READ(endstops.z4_endstop_adj); // 1 float #else - EEPROM_READ(dummy); + EEPROM_READ(dummyf); #endif #endif @@ -1727,7 +1651,7 @@ void MarlinSettings::postprocess() { PIDCF_t pidcf; EEPROM_READ(pidcf); #if ENABLED(PIDTEMP) - if (!validating && pidcf.Kp != DUMMY_PID_VALUE) { + if (!validating && !isnan(pidcf.Kp)) { // Scale PID values since EEPROM values are unscaled PID_PARAM(Kp, e) = pidcf.Kp; PID_PARAM(Ki, e) = scalePID_i(pidcf.Ki); @@ -1749,11 +1673,11 @@ void MarlinSettings::postprocess() { { _FIELD_TEST(lpq_len); #if ENABLED(PID_EXTRUSION_SCALING) - EEPROM_READ(thermalManager.lpq_len); + const int16_t &lpq_len = thermalManager.lpq_len; #else int16_t lpq_len; - EEPROM_READ(lpq_len); #endif + EEPROM_READ(lpq_len); } // @@ -1763,7 +1687,7 @@ void MarlinSettings::postprocess() { PID_t pid; EEPROM_READ(pid); #if ENABLED(PIDTEMPBED) - if (!validating && pid.Kp != DUMMY_PID_VALUE) { + if (!validating && !isnan(pid.Kp)) { // Scale PID values since EEPROM values are unscaled thermalManager.temp_bed.pid.Kp = pid.Kp; thermalManager.temp_bed.pid.Ki = scalePID_i(pid.Ki); @@ -1800,13 +1724,12 @@ void MarlinSettings::postprocess() { // { _FIELD_TEST(recovery_enabled); - #if ENABLED(POWER_LOSS_RECOVERY) - EEPROM_READ(recovery.enabled); + const bool &recovery_enabled = recovery.enabled; #else bool recovery_enabled; - EEPROM_READ(recovery_enabled); #endif + EEPROM_READ(recovery_enabled); } // @@ -1862,7 +1785,7 @@ void MarlinSettings::postprocess() { tmc_stepper_current_t currents; EEPROM_READ(currents); - #if HAS_TRINAMIC + #if HAS_TRINAMIC_CONFIG #define SET_CURR(Q) stepper##Q.rms_current(currents.Q ? currents.Q : Q##_CURRENT) if (!validating) { @@ -2034,7 +1957,7 @@ void MarlinSettings::postprocess() { tmc_stealth_enabled_t tmc_stealth_enabled; EEPROM_READ(tmc_stealth_enabled); - #if HAS_TRINAMIC + #if HAS_TRINAMIC_CONFIG #define SET_STEPPING_MODE(ST) stepper##ST.stored.stealthChop_enabled = tmc_stealth_enabled.ST; stepper##ST.refresh_stepping_mode(); if (!validating) { @@ -2670,7 +2593,7 @@ void MarlinSettings::reset() { // #if ENABLED(POWER_LOSS_RECOVERY) - recovery.enable(true); + recovery.enable(ENABLED(PLR_ENABLED_DEFAULT)); #endif // @@ -2717,7 +2640,7 @@ void MarlinSettings::reset() { LOOP_L_N(i, EXTRUDERS) { planner.extruder_advance_K[i] = LIN_ADVANCE_K; #if ENABLED(EXTRA_LIN_ADVANCE_K) - saved_extruder_advance_K[i] = LIN_ADVANCE_K; + other_extruder_advance_K[i] = LIN_ADVANCE_K; #endif } #endif @@ -2788,7 +2711,7 @@ void MarlinSettings::reset() { #define CONFIG_ECHO_MSG(STR) do{ CONFIG_ECHO_START(); SERIAL_ECHOLNPGM(STR); }while(0) #define CONFIG_ECHO_HEADING(STR) config_heading(forReplay, PSTR(STR)) - #if HAS_TRINAMIC + #if HAS_TRINAMIC_CONFIG inline void say_M906(const bool forReplay) { CONFIG_ECHO_START(); SERIAL_ECHOPGM(" M906"); } #if HAS_STEALTHCHOP void say_M569(const bool forReplay, const char * const etc=nullptr, const bool newLine = false) { @@ -2992,7 +2915,7 @@ void MarlinSettings::reset() { #if HAS_HOTEND_OFFSET CONFIG_ECHO_HEADING("Hotend offsets:"); CONFIG_ECHO_START(); - for (uint8_t e = 1; e < HOTENDS; e++) { + LOOP_S_L_N(e, 1, HOTENDS) { SERIAL_ECHOPAIR_P( PSTR(" M218 T"), (int)e, SP_X_STR, LINEAR_UNIT(hotend_offset[e].x), @@ -3298,7 +3221,7 @@ void MarlinSettings::reset() { #endif #endif - #if HAS_TRINAMIC + #if HAS_TRINAMIC_CONFIG /** * TMC stepper driver current @@ -3599,7 +3522,7 @@ void MarlinSettings::reset() { #endif // HAS_STEALTHCHOP - #endif // HAS_TRINAMIC + #endif // HAS_TRINAMIC_CONFIG /** * Linear Advance diff --git a/Marlin/src/module/endstops.cpp b/Marlin/src/module/endstops.cpp index 58de4a8d05..1c8384cc53 100644 --- a/Marlin/src/module/endstops.cpp +++ b/Marlin/src/module/endstops.cpp @@ -481,7 +481,7 @@ void _O2 Endstops::report_states() { print_es_state(READ(FIL_RUNOUT_PIN) != FIL_RUNOUT_INVERTING, PSTR(STR_FILAMENT_RUNOUT_SENSOR)); #else #define _CASE_RUNOUT(N) case N: pin = FIL_RUNOUT##N##_PIN; break; - for (uint8_t i = 1; i <= NUM_RUNOUT_SENSORS; i++) { + LOOP_S_LE_N(i, 1, NUM_RUNOUT_SENSORS) { pin_t pin; switch (i) { default: continue; diff --git a/Marlin/src/module/motion.cpp b/Marlin/src/module/motion.cpp index 9f6cbf1b38..c1d8fceaa0 100644 --- a/Marlin/src/module/motion.cpp +++ b/Marlin/src/module/motion.cpp @@ -104,7 +104,7 @@ xyze_pos_t current_position = { X_HOME_POS, Y_HOME_POS, Z_HOME_POS }; /** * Cartesian Destination * The destination for a move, filled in by G-code movement commands, - * and expected by functions like 'prepare_move_to_destination'. + * and expected by functions like 'prepare_line_to_destination'. * G-codes can set destination using 'get_destination_from_command' */ xyze_pos_t destination; // {0} @@ -206,17 +206,53 @@ xyz_pos_t cartes; /** * Output the current position to serial */ -void report_current_position() { - const xyz_pos_t lpos = current_position.asLogical(); - SERIAL_ECHOPAIR("X:", lpos.x, " Y:", lpos.y, " Z:", lpos.z, " E:", current_position.e); +inline void report_more_positions() { stepper.report_positions(); - #if IS_SCARA scara_report_positions(); #endif } +// Report the logical position for a given machine position +inline void report_logical_position(const xyze_pos_t &rpos) { + const xyze_pos_t lpos = rpos.asLogical(); + SERIAL_ECHOPAIR_P(X_LBL, lpos.x, SP_Y_LBL, lpos.y, SP_Z_LBL, lpos.z, SP_E_LBL, lpos.e); + report_more_positions(); +} + +// Report the real current position according to the steppers. +// Forward kinematics and un-leveling are applied. +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 + #if HAS_LEVELING + , true + #endif + ); + #endif + + report_logical_position(npos); +} + +// Report the logical current position according to the most recent G-code command +void report_current_position() { report_logical_position(current_position); } + +/** + * Report the logical current position according to the most recent G-code command. + * The planner.position always corresponds to the last G-code too. This makes M114 + * suitable for debugging kinematics and leveling while avoiding planner sync that + * definitively interrupts the printing flow. + */ +void report_current_position_projected() { + report_logical_position(current_position); + stepper.report_a_position(planner.position); +} + /** * sync_plan_position * @@ -241,11 +277,7 @@ void sync_plan_position_e() { planner.set_e_position_mm(current_position.e); } */ void get_cartesian_from_steppers() { #if ENABLED(DELTA) - forward_kinematics_DELTA( - planner.get_axis_position_mm(A_AXIS), - planner.get_axis_position_mm(B_AXIS), - planner.get_axis_position_mm(C_AXIS) - ); + forward_kinematics_DELTA(planner.get_axis_positions_mm()); #else #if IS_SCARA forward_kinematics_SCARA( @@ -272,20 +304,21 @@ void get_cartesian_from_steppers() { */ void set_current_from_steppers_for_axis(const AxisEnum axis) { get_cartesian_from_steppers(); + xyze_pos_t pos = cartes; + pos.e = planner.get_axis_position_mm(E_AXIS); #if HAS_POSITION_MODIFIERS - xyze_pos_t pos = { cartes.x, cartes.y, cartes.z, current_position.e }; planner.unapply_modifiers(pos #if HAS_LEVELING , true #endif ); - const xyze_pos_t &cartes = pos; #endif + if (axis == ALL_AXES) - current_position = cartes; + current_position = pos; else - current_position[axis] = cartes[axis]; + current_position[axis] = pos[axis]; } /** @@ -339,7 +372,7 @@ void _internal_move_to_destination(const feedRate_t &fr_mm_s/*=0.0f*/ prepare_fast_move_to_destination(); else #endif - prepare_move_to_destination(); + prepare_line_to_destination(); feedrate_mm_s = old_feedrate; feedrate_percentage = old_pct; @@ -587,7 +620,7 @@ void restore_feedrate_and_scaling() { #endif if (DEBUGGING(LEVELING)) - SERIAL_ECHOLNPAIR("Axis ", axis_codes[axis], " min:", soft_endstop.min[axis], " max:", soft_endstop.max[axis]); + SERIAL_ECHOLNPAIR("Axis ", XYZ_CHAR(axis), " min:", soft_endstop.min[axis], " max:", soft_endstop.max[axis]); } /** @@ -621,7 +654,7 @@ void restore_feedrate_and_scaling() { ) { const float dist_2 = HYPOT2(target.x - offs.x, target.y - offs.y); if (dist_2 > delta_max_radius_2) - target *= delta_max_radius / SQRT(dist_2); // 200 / 300 = 0.66 + target *= float(delta_max_radius / SQRT(dist_2)); // 200 / 300 = 0.66 } #else @@ -659,6 +692,16 @@ void restore_feedrate_and_scaling() { #endif // HAS_SOFTWARE_ENDSTOPS #if !UBL_SEGMENTED + +FORCE_INLINE void segment_idle(millis_t &next_idle_ms) { + const millis_t ms = millis(); + if (ELAPSED(ms, next_idle_ms)) { + next_idle_ms = ms + 200UL; + return idle(); + } + thermalManager.manage_heater(); // Returns immediately on most calls +} + #if IS_KINEMATIC #if IS_SCARA @@ -678,7 +721,7 @@ void restore_feedrate_and_scaling() { /** * Prepare a linear move in a DELTA or SCARA setup. * - * Called from prepare_move_to_destination as the + * Called from prepare_line_to_destination as the * default Delta/SCARA segmenter. * * This calls planner.buffer_line several times, adding @@ -751,17 +794,10 @@ void restore_feedrate_and_scaling() { xyze_pos_t raw = current_position; // Calculate and execute the segments + millis_t next_idle_ms = millis() + 200UL; while (--segments) { - - static millis_t next_idle_ms = millis() + 200UL; - thermalManager.manage_heater(); // This returns immediately if not really needed. - if (ELAPSED(millis(), next_idle_ms)) { - next_idle_ms = millis() + 200UL; - idle(); - } - + segment_idle(next_idle_ms); raw += segment_distance; - if (!planner.buffer_line(raw, scaled_fr_mm_s, active_extruder, cartesian_segment_mm #if ENABLED(SCARA_FEEDRATE_SCALING) , inv_duration @@ -830,13 +866,9 @@ void restore_feedrate_and_scaling() { xyze_pos_t raw = current_position; // Calculate and execute the segments + millis_t next_idle_ms = millis() + 200UL; while (--segments) { - static millis_t next_idle_ms = millis() + 200UL; - thermalManager.manage_heater(); // This returns immediately if not really needed. - if (ELAPSED(millis(), next_idle_ms)) { - next_idle_ms = millis() + 200UL; - idle(); - } + segment_idle(next_idle_ms); raw += segment_distance; if (!planner.buffer_line(raw, fr_mm_s, active_extruder, cartesian_segment_mm #if ENABLED(SCARA_FEEDRATE_SCALING) @@ -865,7 +897,7 @@ void restore_feedrate_and_scaling() { * * Return true if 'current_position' was set to 'destination' */ - inline bool prepare_move_to_destination_cartesian() { + inline bool line_to_destination_cartesian() { const float scaled_fr_mm_s = MMS_SCALED(feedrate_mm_s); #if HAS_MESH if (planner.leveling_active && planner.leveling_active_at_z(destination.z)) { @@ -1008,7 +1040,7 @@ void restore_feedrate_and_scaling() { * * Before exit, current_position is set to destination. */ -void prepare_move_to_destination() { +void prepare_line_to_destination() { apply_motion_limits(destination); #if EITHER(PREVENT_COLD_EXTRUSION, PREVENT_LENGTHY_EXTRUDE) @@ -1058,12 +1090,12 @@ void prepare_move_to_destination() { #if IS_KINEMATIC // UBL using Kinematic / Cartesian cases as a workaround for now. ubl.line_to_destination_segmented(MMS_SCALED(feedrate_mm_s)) #else - prepare_move_to_destination_cartesian() + line_to_destination_cartesian() #endif #elif IS_KINEMATIC line_to_destination_kinematic() #else - prepare_move_to_destination_cartesian() + line_to_destination_cartesian() #endif ) return; @@ -1176,15 +1208,9 @@ feedRate_t get_homing_bump_feedrate(const AxisEnum axis) { #if ENABLED(SPI_ENDSTOPS) switch (axis) { - #if X_SPI_SENSORLESS - case X_AXIS: endstops.tmc_spi_homing.x = true; break; - #endif - #if Y_SPI_SENSORLESS - case Y_AXIS: endstops.tmc_spi_homing.y = true; break; - #endif - #if Z_SPI_SENSORLESS - case Z_AXIS: endstops.tmc_spi_homing.z = true; break; - #endif + case X_AXIS: if (ENABLED(X_SPI_SENSORLESS)) endstops.tmc_spi_homing.x = true; break; + case Y_AXIS: if (ENABLED(Y_SPI_SENSORLESS)) endstops.tmc_spi_homing.y = true; break; + case Z_AXIS: if (ENABLED(Z_SPI_SENSORLESS)) endstops.tmc_spi_homing.z = true; break; default: break; } #endif @@ -1248,15 +1274,9 @@ feedRate_t get_homing_bump_feedrate(const AxisEnum axis) { #if ENABLED(SPI_ENDSTOPS) switch (axis) { - #if X_SPI_SENSORLESS - case X_AXIS: endstops.tmc_spi_homing.x = false; break; - #endif - #if Y_SPI_SENSORLESS - case Y_AXIS: endstops.tmc_spi_homing.y = false; break; - #endif - #if Z_SPI_SENSORLESS - case Z_AXIS: endstops.tmc_spi_homing.z = false; break; - #endif + case X_AXIS: if (ENABLED(X_SPI_SENSORLESS)) endstops.tmc_spi_homing.x = false; break; + case Y_AXIS: if (ENABLED(Y_SPI_SENSORLESS)) endstops.tmc_spi_homing.y = false; break; + case Z_AXIS: if (ENABLED(Z_SPI_SENSORLESS)) endstops.tmc_spi_homing.z = false; break; default: break; } #endif @@ -1280,16 +1300,8 @@ void do_homing_move(const AxisEnum axis, const float distance, const feedRate_t #if HOMING_Z_WITH_PROBE && HAS_HEATED_BED && ENABLED(WAIT_FOR_BED_HEATER) // Wait for bed to heat back up between probing points - if (axis == Z_AXIS && distance < 0 && thermalManager.isHeatingBed()) { - serialprintPGM(probe.msg_wait_for_bed_heating); - #if HAS_DISPLAY - LCD_MESSAGEPGM(MSG_BED_HEATING); - #endif - thermalManager.wait_for_bed(); - #if HAS_DISPLAY - ui.reset_status(); - #endif - } + if (axis == Z_AXIS && distance < 0) + thermalManager.wait_for_bed_heating(); #endif // Only do some things when moving towards an endstop @@ -1324,7 +1336,7 @@ void do_homing_move(const AxisEnum axis, const float distance, const feedRate_t current_position[axis] = distance; line_to_current_position(real_fr_mm_s); #else - abce_pos_t target = { planner.get_axis_position_mm(A_AXIS), planner.get_axis_position_mm(B_AXIS), planner.get_axis_position_mm(C_AXIS), planner.get_axis_position_mm(E_AXIS) }; + abce_pos_t target = planner.get_axis_positions_mm(); target[axis] = 0; planner.set_machine_position_mm(target); target[axis] = distance; @@ -1448,13 +1460,13 @@ void set_axis_is_at_home(const AxisEnum axis) { /** * Set an axis' to be unhomed. */ -void set_axis_is_not_at_home(const AxisEnum axis) { - if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR(">>> set_axis_is_not_at_home(", axis_codes[axis], ")"); +void set_axis_not_trusted(const AxisEnum axis) { + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR(">>> set_axis_not_trusted(", axis_codes[axis], ")"); CBI(axis_known_position, axis); CBI(axis_homed, axis); - if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("<<< set_axis_is_not_at_home(", axis_codes[axis], ")"); + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("<<< set_axis_not_trusted(", axis_codes[axis], ")"); #if ENABLED(I2C_POSITION_ENCODERS) I2CPEM.unhomed(axis); @@ -1779,7 +1791,7 @@ void homeaxis(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 ", axis_codes[axis], " home_offset = ", home_offset[axis], " position_shift = ", position_shift[axis]); + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("Axis ", XYZ_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 c50da25a3e..f6a75a91a7 100644 --- a/Marlin/src/module/motion.h +++ b/Marlin/src/module/motion.h @@ -30,10 +30,6 @@ #include "../inc/MarlinConfig.h" -#if HAS_BED_PROBE - #include "probe.h" -#endif - #if IS_SCARA #include "scara.h" #endif @@ -58,7 +54,7 @@ FORCE_INLINE bool homing_needed() { } // Error margin to work around float imprecision -constexpr float slop = 0.0001; +constexpr float fslop = 0.0001; extern bool relative_mode; @@ -166,7 +162,9 @@ typedef struct { xyz_pos_t min, max; } axis_limits_t; #define update_software_endstops(...) NOOP #endif +void report_real_position(); void report_current_position(); +void report_current_position_projected(); void get_cartesian_from_steppers(); void set_current_from_steppers_for_axis(const AxisEnum axis); @@ -186,7 +184,7 @@ void sync_plan_position_e(); */ void line_to_current_position(const feedRate_t &fr_mm_s=feedrate_mm_s); -void prepare_move_to_destination(); +void prepare_line_to_destination(); void _internal_move_to_destination(const feedRate_t &fr_mm_s=0.0f #if IS_KINEMATIC @@ -246,7 +244,7 @@ bool axis_unhomed_error(uint8_t axis_bits=0x07); void set_axis_is_at_home(const AxisEnum axis); -void set_axis_is_not_at_home(const AxisEnum axis); +void set_axis_not_trusted(const AxisEnum axis); void homeaxis(const AxisEnum axis); @@ -306,7 +304,7 @@ void homeaxis(const AxisEnum axis); // Return true if the given point is within the printable area inline bool position_is_reachable(const float &rx, const float &ry, const float inset=0) { #if ENABLED(DELTA) - return HYPOT2(rx, ry) <= sq(DELTA_PRINTABLE_RADIUS - inset + slop); + return HYPOT2(rx, ry) <= sq(DELTA_PRINTABLE_RADIUS - inset + fslop); #elif IS_SCARA const float R2 = HYPOT2(rx - SCARA_OFFSET_X, ry - SCARA_OFFSET_Y); return ( @@ -322,67 +320,24 @@ void homeaxis(const AxisEnum axis); return position_is_reachable(pos.x, pos.y, inset); } - #if HAS_BED_PROBE - - #if HAS_PROBE_XY_OFFSET - - // Return true if the both nozzle and the probe can reach the given point. - // Note: This won't work on SCARA since the probe offset rotates with the arm. - inline bool position_is_reachable_by_probe(const float &rx, const float &ry) { - return position_is_reachable(rx - probe.offset_xy.x, ry - probe.offset_xy.y) - && position_is_reachable(rx, ry, ABS(MIN_PROBE_EDGE)); - } - - #else - - FORCE_INLINE bool position_is_reachable_by_probe(const float &rx, const float &ry) { - return position_is_reachable(rx, ry, MIN_PROBE_EDGE); - } - - #endif - - #endif // HAS_BED_PROBE - #else // CARTESIAN // Return true if the given position is within the machine bounds. inline bool position_is_reachable(const float &rx, const float &ry) { - if (!WITHIN(ry, Y_MIN_POS - slop, Y_MAX_POS + slop)) return false; + if (!WITHIN(ry, Y_MIN_POS - fslop, Y_MAX_POS + fslop)) return false; #if ENABLED(DUAL_X_CARRIAGE) if (active_extruder) - return WITHIN(rx, X2_MIN_POS - slop, X2_MAX_POS + slop); + return WITHIN(rx, X2_MIN_POS - fslop, X2_MAX_POS + fslop); else - return WITHIN(rx, X1_MIN_POS - slop, X1_MAX_POS + slop); + return WITHIN(rx, X1_MIN_POS - fslop, X1_MAX_POS + fslop); #else - return WITHIN(rx, X_MIN_POS - slop, X_MAX_POS + slop); + return WITHIN(rx, X_MIN_POS - fslop, X_MAX_POS + fslop); #endif } inline bool position_is_reachable(const xy_pos_t &pos) { return position_is_reachable(pos.x, pos.y); } - #if HAS_BED_PROBE - - /** - * Return whether the given position is within the bed, and whether the nozzle - * can reach the position required to put the probe at the given position. - * - * Example: For a probe offset of -10,+10, then for the probe to reach 0,0 the - * nozzle must be be able to reach +10,-10. - */ - inline bool position_is_reachable_by_probe(const float &rx, const float &ry) { - return position_is_reachable(rx - probe.offset_xy.x, ry - probe.offset_xy.y) - && WITHIN(rx, probe.min_x() - slop, probe.max_x() + slop) - && WITHIN(ry, probe.min_y() - slop, probe.max_y() + slop); - } - - #endif // HAS_BED_PROBE - #endif // CARTESIAN -#if !HAS_BED_PROBE - FORCE_INLINE bool position_is_reachable_by_probe(const float &rx, const float &ry) { return position_is_reachable(rx, ry); } -#endif -FORCE_INLINE bool position_is_reachable_by_probe(const xy_pos_t &pos) { return position_is_reachable_by_probe(pos.x, pos.y); } - /** * Duplication mode */ @@ -420,11 +375,13 @@ FORCE_INLINE bool position_is_reachable_by_probe(const xy_pos_t &pos) { return p FORCE_INLINE int x_home_dir(const uint8_t extruder) { return extruder ? X2_HOME_DIR : X_HOME_DIR; } -#elif ENABLED(MULTI_NOZZLE_DUPLICATION) +#else - enum DualXMode : char { - DXC_DUPLICATION_MODE = 2 - }; + #if ENABLED(MULTI_NOZZLE_DUPLICATION) + enum DualXMode : char { DXC_DUPLICATION_MODE = 2 }; + #endif + + FORCE_INLINE int x_home_dir(const uint8_t) { return home_dir(X_AXIS); } #endif diff --git a/Marlin/src/module/planner.cpp b/Marlin/src/module/planner.cpp index 2067ecc23f..7417749088 100644 --- a/Marlin/src/module/planner.cpp +++ b/Marlin/src/module/planner.cpp @@ -101,7 +101,7 @@ #endif #if ENABLED(POWER_LOSS_RECOVERY) - #include "../feature/power_loss_recovery.h" + #include "../feature/powerloss.h" #endif #if HAS_CUTTER @@ -1408,7 +1408,7 @@ void Planner::check_axes_activity() { * The multiplier converts a given E value into a length. */ void Planner::calculate_volumetric_multipliers() { - for (uint8_t i = 0; i < COUNT(filament_size); i++) { + LOOP_L_N(i, COUNT(filament_size)) { volumetric_multiplier[i] = calculate_volumetric_multiplier(filament_size[i]); refresh_e_factor(i); } @@ -1991,7 +1991,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move, #if ENABLED(DISABLE_INACTIVE_EXTRUDER) // Enable only the selected extruder - for (uint8_t i = 0; i < EXTRUDERS; i++) + LOOP_L_N(i, EXTRUDERS) if (g_uc_extruder_last_move[i] > 0) g_uc_extruder_last_move[i]--; #if HAS_DUPLICATION_MODE @@ -2404,12 +2404,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move, #endif { const float jerk = ABS(current_speed[i]), // cs : Starting from zero, change in speed for this axis - maxj = (max_jerk[i] // mj : The max jerk setting for this axis - #ifdef TRAVEL_EXTRA_XYJERK - + (i == X_AXIS || i == Y_AXIS ? extra_xyjerk : 0) - #endif - ); - + 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? if (limited) { // limited already? const float mjerk = nominal_speed * maxj; // ns*mj @@ -2461,11 +2456,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move, : // v_exit <= v_entry coasting axis reversal ( (v_entry < 0 || v_exit > 0) ? (v_entry - v_exit) : _MAX(-v_exit, v_entry) ); - const float maxj = (max_jerk[axis] - #ifdef TRAVEL_EXTRA_XYJERK - + (axis == X_AXIS || axis == Y_AXIS ? extra_xyjerk : 0) - #endif - ); + const float maxj = (max_jerk[axis] + (axis == X_AXIS || axis == Y_AXIS ? extra_xyjerk : 0.0f)); if (jerk > maxj) { v_factor *= maxj / jerk; @@ -2628,21 +2619,24 @@ bool Planner::buffer_segment(const float &a, const float &b, const float &c, con SERIAL_ECHOPAIR("->", target.a); SERIAL_ECHOPAIR(") B:", b); #else - SERIAL_ECHOPAIR(" X:", a); + SERIAL_ECHOPAIR_P(SP_X_LBL, a); SERIAL_ECHOPAIR(" (", position.x); SERIAL_ECHOPAIR("->", target.x); - SERIAL_ECHOPAIR(") Y:", b); + SERIAL_CHAR(')'); + SERIAL_ECHOPAIR_P(SP_Y_LBL, b); #endif SERIAL_ECHOPAIR(" (", position.y); SERIAL_ECHOPAIR("->", target.y); #if ENABLED(DELTA) SERIAL_ECHOPAIR(") C:", c); #else - SERIAL_ECHOPAIR(") Z:", c); + SERIAL_CHAR(')'); + SERIAL_ECHOPAIR_P(SP_Z_LBL, c); #endif SERIAL_ECHOPAIR(" (", position.z); SERIAL_ECHOPAIR("->", target.z); - SERIAL_ECHOPAIR(") E:", e); + SERIAL_CHAR(')'); + SERIAL_ECHOPAIR_P(SP_E_LBL, e); SERIAL_ECHOPAIR(" (", position.e); SERIAL_ECHOPAIR("->", target.e); SERIAL_ECHOLNPGM(")"); diff --git a/Marlin/src/module/planner.h b/Marlin/src/module/planner.h index 6942ec6028..ae104eb354 100644 --- a/Marlin/src/module/planner.h +++ b/Marlin/src/module/planner.h @@ -289,6 +289,12 @@ class Planner { static float extruder_advance_K[EXTRUDERS]; #endif + /** + * The current position of the tool in absolute steps + * Recalculated if any axis_steps_per_mm are changed by gcode + */ + static xyze_long_t position; + #if HAS_POSITION_FLOAT static xyze_pos_t position_float; #endif @@ -305,12 +311,6 @@ class Planner { private: - /** - * The current position of the tool in absolute steps - * Recalculated if any axis_steps_per_mm are changed by gcode - */ - static xyze_long_t position; - /** * Speed of previous path line segment */ @@ -403,7 +403,7 @@ class Planner { FORCE_INLINE static void set_filament_size(const uint8_t e, const float &v) { filament_size[e] = v; // make sure all extruders have some sane value for the filament size - for (uint8_t i = 0; i < COUNT(filament_size); i++) + LOOP_L_N(i, COUNT(filament_size)) if (!filament_size[i]) filament_size[i] = DEFAULT_NOMINAL_FILAMENT_DIA; } @@ -725,6 +725,16 @@ class Planner { */ static float get_axis_position_mm(const AxisEnum axis); + static inline abce_pos_t get_axis_positions_mm() { + const abce_pos_t out = { + get_axis_position_mm(A_AXIS), + get_axis_position_mm(B_AXIS), + get_axis_position_mm(C_AXIS), + get_axis_position_mm(E_AXIS) + }; + return out; + } + // SCARA AB axes are in degrees, not mm #if IS_SCARA FORCE_INLINE static float get_axis_position_degrees(const AxisEnum axis) { return get_axis_position_mm(axis); } @@ -797,7 +807,7 @@ class Planner { FORCE_INLINE static void recalculate_max_e_jerk() { #define GET_MAX_E_JERK(N) SQRT(SQRT(0.5) * junction_deviation_mm * (N) * RECIPROCAL(1.0 - SQRT(0.5))) #if ENABLED(DISTINCT_E_FACTORS) - for (uint8_t i = 0; i < EXTRUDERS; i++) + LOOP_L_N(i, EXTRUDERS) max_e_jerk[i] = GET_MAX_E_JERK(settings.max_acceleration_mm_per_s2[E_AXIS_N(i)]); #else max_e_jerk = GET_MAX_E_JERK(settings.max_acceleration_mm_per_s2[E_AXIS]); diff --git a/Marlin/src/module/printcounter.cpp b/Marlin/src/module/printcounter.cpp index 3fa09c8834..4b4d4b60ad 100644 --- a/Marlin/src/module/printcounter.cpp +++ b/Marlin/src/module/printcounter.cpp @@ -30,7 +30,7 @@ Stopwatch print_job_timer; // Global Print Job Timer instance #else // PRINTCOUNTER #if ENABLED(EXTENSIBLE_UI) - #include "../lcd/extensible_ui/ui_api.h" + #include "../lcd/extui/ui_api.h" #endif #include "printcounter.h" diff --git a/Marlin/src/module/printcounter.h b/Marlin/src/module/printcounter.h index 1630de988d..261cdf058b 100644 --- a/Marlin/src/module/printcounter.h +++ b/Marlin/src/module/printcounter.h @@ -28,7 +28,7 @@ // Print debug messages with M111 S2 //#define DEBUG_PRINTCOUNTER -#if EITHER(I2C_EEPROM, SPI_EEPROM) +#if USE_REAL_EEPROM // round up address to next page boundary (assuming 32 byte pages) #define STATS_EEPROM_ADDRESS 0x40 #else @@ -57,7 +57,7 @@ class PrintCounter: public Stopwatch { private: typedef Stopwatch super; - #if EITHER(I2C_EEPROM, SPI_EEPROM) || defined(CPU_32_BIT) + #if USE_REAL_EEPROM || defined(CPU_32_BIT) typedef uint32_t eeprom_address_t; #else typedef uint16_t eeprom_address_t; diff --git a/Marlin/src/module/probe.cpp b/Marlin/src/module/probe.cpp index 858dcae747..962c230775 100644 --- a/Marlin/src/module/probe.cpp +++ b/Marlin/src/module/probe.cpp @@ -78,7 +78,7 @@ #endif #if ENABLED(EXTENSIBLE_UI) - #include "../lcd/extensible_ui/ui_api.h" + #include "../lcd/extui/ui_api.h" #endif #define DEBUG_OUT ENABLED(DEBUG_LEVELING_FEATURE) @@ -89,7 +89,7 @@ Probe probe; xyz_pos_t Probe::offset; // Initialized by settings.load() #if HAS_PROBE_XY_OFFSET - const xyz_pos_t &Probe::offset_xy = probe.offset; + const xyz_pos_t &Probe::offset_xy = Probe::offset; #endif #if ENABLED(Z_PROBE_SLED) @@ -455,10 +455,6 @@ bool Probe::set_deployed(const bool deploy) { * @return true to indicate an error */ -#if HAS_BED_PROBE && HAS_HEATED_BED && ENABLED(WAIT_FOR_BED_HEATER) - const char Probe::msg_wait_for_bed_heating[25] PROGMEM = "Wait for bed heating...\n"; -#endif - /** * @brief Move down until the probe triggers or the low limit is reached * @@ -473,13 +469,7 @@ bool Probe::probe_down_to_z(const float z, const feedRate_t fr_mm_s) { if (DEBUGGING(LEVELING)) DEBUG_POS(">>> Probe::probe_down_to_z", current_position); #if HAS_HEATED_BED && ENABLED(WAIT_FOR_BED_HEATER) - // Wait for bed to heat back up between probing points - if (thermalManager.isHeatingBed()) { - serialprintPGM(msg_wait_for_bed_heating); - LCD_MESSAGEPGM(MSG_BED_HEATING); - thermalManager.wait_for_bed(); - ui.reset_status(); - } + thermalManager.wait_for_bed_heating(); #endif #if ENABLED(BLTOUCH) && DISABLED(BLTOUCH_HS_MODE) @@ -634,7 +624,7 @@ float Probe::run_z_probe(const bool sanity_check/*=true*/) { #if EXTRA_PROBING // Insert Z measurement into probes[]. Keep it sorted ascending. - for (uint8_t i = 0; i <= p; i++) { // Iterate the saved Zs to insert the new Z + LOOP_LE_N(i, p) { // Iterate the saved Zs to insert the new Z if (i == p || probes[i] > z) { // Last index or new Z is smaller than this Z for (int8_t m = p; --m >= i;) probes[m + 1] = probes[m]; // Shift items down after the insertion point probes[i] = z; // Insert the new Z measurement @@ -672,7 +662,7 @@ float Probe::run_z_probe(const bool sanity_check/*=true*/) { max_avg_idx--; else min_avg_idx++; // Return the average value of all remaining probes. - for (uint8_t i = min_avg_idx; i <= max_avg_idx; i++) + LOOP_S_LE_N(i, min_avg_idx, max_avg_idx) probes_z_sum += probes[i]; #endif @@ -727,7 +717,7 @@ float Probe::probe_at_point(const float &rx, const float &ry, const ProbePtRaise // TODO: Adapt for SCARA, where the offset rotates xyz_pos_t npos = { rx, ry }; if (probe_relative) { // The given position is in terms of the probe - if (!position_is_reachable_by_probe(npos)) { + if (!can_reach(npos)) { if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("Position Not Reachable"); return NAN; } diff --git a/Marlin/src/module/probe.h b/Marlin/src/module/probe.h index 6f17090e69..083867ab48 100644 --- a/Marlin/src/module/probe.h +++ b/Marlin/src/module/probe.h @@ -27,6 +27,8 @@ #include "../inc/MarlinConfig.h" +#include "motion.h" + #if HAS_BED_PROBE enum ProbePtRaise : uint8_t { PROBE_PT_NONE, // No raise or stow after run_z_probe @@ -45,16 +47,46 @@ public: static bool set_deployed(const bool deploy); + + #if IS_KINEMATIC + + #if HAS_PROBE_XY_OFFSET + // Return true if the both nozzle and the probe can reach the given point. + // Note: This won't work on SCARA since the probe offset rotates with the arm. + static inline bool can_reach(const float &rx, const float &ry) { + return position_is_reachable(rx - offset_xy.x, ry - offset_xy.y) // The nozzle can go where it needs to go? + && position_is_reachable(rx, ry, ABS(MIN_PROBE_EDGE)); // Can the nozzle also go near there? + } + #else + FORCE_INLINE static bool can_reach(const float &rx, const float &ry) { + return position_is_reachable(rx, ry, MIN_PROBE_EDGE); + } + #endif + + #else + + /** + * Return whether the given position is within the bed, and whether the nozzle + * can reach the position required to put the probe at the given position. + * + * Example: For a probe offset of -10,+10, then for the probe to reach 0,0 the + * nozzle must be be able to reach +10,-10. + */ + static inline bool can_reach(const float &rx, const float &ry) { + return position_is_reachable(rx - offset_xy.x, ry - offset_xy.y) + && WITHIN(rx, min_x() - fslop, max_x() + fslop) + && WITHIN(ry, min_y() - fslop, max_y() + fslop); + } + + #endif + #ifdef Z_AFTER_PROBING static void move_z_after_probing(); #endif static float probe_at_point(const float &rx, const float &ry, const ProbePtRaise raise_after=PROBE_PT_NONE, const uint8_t verbose_level=0, const bool probe_relative=true, const bool sanity_check=true); static inline float probe_at_point(const xy_pos_t &pos, const ProbePtRaise raise_after=PROBE_PT_NONE, const uint8_t verbose_level=0, const bool probe_relative=true, const bool sanity_check=true) { - return probe_at_point(pos.x, pos.y, raise_after, verbose_level, probe_relative); + return probe_at_point(pos.x, pos.y, raise_after, verbose_level, probe_relative, sanity_check); } - #if HAS_HEATED_BED && ENABLED(WAIT_FOR_BED_HEATER) - static const char msg_wait_for_bed_heating[25]; - #endif #else @@ -62,8 +94,22 @@ public: static bool set_deployed(const bool) { return false; } + FORCE_INLINE static bool can_reach(const float &rx, const float &ry) { return position_is_reachable(rx, ry); } + #endif + FORCE_INLINE static bool can_reach(const xy_pos_t &pos) { return can_reach(pos.x, pos.y); } + + FORCE_INLINE static bool good_bounds(const xy_pos_t &lf, const xy_pos_t &rb) { + return ( + #if IS_KINEMATIC + can_reach(lf.x, 0) && can_reach(rb.x, 0) && can_reach(0, lf.y) && can_reach(0, rb.y) + #else + can_reach(lf) && can_reach(rb) + #endif + ); + } + // Use offset_xy for read only access // More optimal the XY offset is known to always be zero. #if HAS_PROBE_XY_OFFSET @@ -131,7 +177,7 @@ public: // Retrieve three points to probe the bed. Any type exposing set(X,Y) may be used. template static inline void get_three_points(T points[3]) { - #if ENABLED(HAS_FIXED_3POINT) + #if HAS_FIXED_3POINT points[0].set(PROBE_PT_1_X, PROBE_PT_1_Y); points[1].set(PROBE_PT_2_X, PROBE_PT_2_Y); points[2].set(PROBE_PT_3_X, PROBE_PT_3_Y); diff --git a/Marlin/src/module/scara.cpp b/Marlin/src/module/scara.cpp index f7eb8d192b..5fbbfd65a6 100644 --- a/Marlin/src/module/scara.cpp +++ b/Marlin/src/module/scara.cpp @@ -53,11 +53,13 @@ void scara_set_axis_is_at_home(const AxisEnum axis) { current_position[axis] = cartes[axis]; #else // MP_SCARA uses a Cartesian XY home position - // SERIAL_ECHOLNPAIR("homeposition X:", homeposition.x, " Y:", homeposition.y); + // SERIAL_ECHOPGM("homeposition"); + // SERIAL_ECHOLNPAIR_P(SP_X_LBL, homeposition.x, SP_Y_LBL, homeposition.y); current_position[axis] = homeposition[axis]; #endif - // SERIAL_ECHOLNPAIR("Cartesian X:", current_position.x, " Y:", current_position.y); + // SERIAL_ECHOPGM("Cartesian"); + // SERIAL_ECHOLNPAIR_P(SP_X_LBL, current_position.x, SP_Y_LBL, current_position.y); update_software_endstops(axis); } } diff --git a/Marlin/src/module/stepper.cpp b/Marlin/src/module/stepper.cpp index 68639d40f0..ed48b83d5a 100644 --- a/Marlin/src/module/stepper.cpp +++ b/Marlin/src/module/stepper.cpp @@ -130,7 +130,7 @@ Stepper stepper; // Singleton #endif #if ENABLED(POWER_LOSS_RECOVERY) - #include "../feature/power_loss_recovery.h" + #include "../feature/powerloss.h" #endif // public: @@ -2116,7 +2116,7 @@ void Stepper::init() { #if MB(ALLIGATOR) const float motor_current[] = MOTOR_CURRENT; unsigned int digipot_motor = 0; - for (uint8_t i = 0; i < 3 + EXTRUDERS; i++) { + LOOP_L_N(i, 3 + EXTRUDERS) { digipot_motor = 255 * (motor_current[i] / 2.5); dac084s085::setValue(i, digipot_motor); } @@ -2448,6 +2448,19 @@ int32_t Stepper::triggered_position(const AxisEnum axis) { return v; } +void Stepper::report_a_position(const xyz_long_t &pos) { + #if CORE_IS_XY || CORE_IS_XZ || ENABLED(DELTA) || IS_SCARA + SERIAL_ECHOPAIR(STR_COUNT_A, pos.x, " B:", pos.y); + #else + SERIAL_ECHOPAIR_P(PSTR(STR_COUNT_X), pos.x, SP_Y_LBL, pos.y); + #endif + #if CORE_IS_XZ || CORE_IS_YZ || ENABLED(DELTA) + SERIAL_ECHOLNPAIR(" C:", pos.z); + #else + SERIAL_ECHOLNPAIR_P(SP_Z_LBL, pos.z); + #endif +} + void Stepper::report_positions() { #ifdef __AVR__ @@ -2461,16 +2474,7 @@ void Stepper::report_positions() { if (was_enabled) wake_up(); #endif - #if CORE_IS_XY || CORE_IS_XZ || ENABLED(DELTA) || IS_SCARA - SERIAL_ECHOPAIR(STR_COUNT_A, pos.x, " B:", pos.y); - #else - SERIAL_ECHOPAIR(STR_COUNT_X, pos.x, " Y:", pos.y); - #endif - #if CORE_IS_XZ || CORE_IS_YZ || ENABLED(DELTA) - SERIAL_ECHOLNPAIR(" C:", pos.z); - #else - SERIAL_ECHOLNPAIR(" Z:", pos.z); - #endif + report_a_position(pos); } #if ENABLED(BABYSTEPPING) @@ -2752,7 +2756,7 @@ void Stepper::report_positions() { SPI.begin(); SET_OUTPUT(DIGIPOTSS_PIN); - for (uint8_t i = 0; i < COUNT(digipot_motor_current); i++) { + LOOP_L_N(i, COUNT(digipot_motor_current)) { //digitalPotWrite(digipot_ch[i], digipot_motor_current[i]); digipot_current(i, digipot_motor_current[i]); } diff --git a/Marlin/src/module/stepper.h b/Marlin/src/module/stepper.h index 6671b946df..46c6c1c16a 100644 --- a/Marlin/src/module/stepper.h +++ b/Marlin/src/module/stepper.h @@ -411,6 +411,7 @@ class Stepper { static void set_axis_position(const AxisEnum a, const int32_t &v); // Report the positions of the steppers, in steps + static void report_a_position(const xyz_long_t &pos); static void report_positions(); // Quickly stop all steppers diff --git a/Marlin/src/module/stepper/TMC26X.h b/Marlin/src/module/stepper/TMC26X.h index d44bc19a74..39192cea25 100644 --- a/Marlin/src/module/stepper/TMC26X.h +++ b/Marlin/src/module/stepper/TMC26X.h @@ -32,7 +32,7 @@ #include #if defined(STM32GENERIC) && defined(STM32F7) - #include "../../HAL/HAL_STM32_F4_F7/STM32F7/TMC2660.h" + #include "../../HAL/STM32_F4_F7/STM32F7/TMC2660.h" #else #include #endif diff --git a/Marlin/src/module/stepper/indirection.cpp b/Marlin/src/module/stepper/indirection.cpp index d468a2afdd..2ddbfe62e3 100644 --- a/Marlin/src/module/stepper/indirection.cpp +++ b/Marlin/src/module/stepper/indirection.cpp @@ -33,7 +33,7 @@ #include "indirection.h" void restore_stepper_drivers() { - #if HAS_TRINAMIC + #if HAS_TRINAMIC_CONFIG restore_trinamic_drivers(); #endif } @@ -47,7 +47,7 @@ void reset_stepper_drivers() { L64xxManager.init_to_defaults(); #endif - #if HAS_TRINAMIC + #if HAS_TRINAMIC_CONFIG reset_trinamic_drivers(); #endif } diff --git a/Marlin/src/module/stepper/indirection.h b/Marlin/src/module/stepper/indirection.h index 295c3aca2e..0b36a5d0c0 100644 --- a/Marlin/src/module/stepper/indirection.h +++ b/Marlin/src/module/stepper/indirection.h @@ -40,7 +40,7 @@ #include "TMC26X.h" #endif -#if HAS_TRINAMIC +#if HAS_TRINAMIC_CONFIG #include "trinamic.h" #endif @@ -185,18 +185,18 @@ void reset_stepper_drivers(); // Called by settings.load / settings.reset #ifndef Z4_ENABLE_INIT #define Z4_ENABLE_INIT() SET_OUTPUT(Z4_ENABLE_PIN) #define Z4_ENABLE_WRITE(STATE) WRITE(Z4_ENABLE_PIN,STATE) - #define Z4_ENABLE_READ() READ(Z4_ENABLE_PIN) + #define Z4_ENABLE_READ() bool(READ(Z4_ENABLE_PIN)) #endif #ifndef Z4_DIR_INIT #define Z4_DIR_INIT() SET_OUTPUT(Z4_DIR_PIN) #define Z4_DIR_WRITE(STATE) WRITE(Z4_DIR_PIN,STATE) - #define Z4_DIR_READ() READ(Z4_DIR_PIN) + #define Z4_DIR_READ() bool(READ(Z4_DIR_PIN)) #endif - #define Z4_STEP_INIT SET_OUTPUT(Z4_STEP_PIN) + #define Z4_STEP_INIT() SET_OUTPUT(Z4_STEP_PIN) #ifndef Z4_STEP_WRITE #define Z4_STEP_WRITE(STATE) WRITE(Z4_STEP_PIN,STATE) #endif - #define Z4_STEP_READ READ(Z4_STEP_PIN) + #define Z4_STEP_READ() bool(READ(Z4_STEP_PIN)) #else #define Z4_DIR_WRITE(STATE) NOOP #endif diff --git a/Marlin/src/module/stepper/trinamic.cpp b/Marlin/src/module/stepper/trinamic.cpp index 0b14aaf647..14598f9c73 100644 --- a/Marlin/src/module/stepper/trinamic.cpp +++ b/Marlin/src/module/stepper/trinamic.cpp @@ -27,7 +27,7 @@ #include "../../inc/MarlinConfig.h" -#if HAS_TRINAMIC +#if HAS_TRINAMIC_CONFIG #include "trinamic.h" #include "../stepper.h" @@ -818,4 +818,4 @@ void reset_trinamic_drivers() { stepper.set_directions(); } -#endif // HAS_TRINAMIC +#endif // HAS_TRINAMIC_CONFIG diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index 7cee5fb1ea..d0b1ddf0a3 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -33,7 +33,7 @@ #include "../core/language.h" #include "../HAL/shared/Delay.h" #if ENABLED(EXTENSIBLE_UI) - #include "../lcd/extensible_ui/ui_api.h" + #include "../lcd/extui/ui_api.h" #endif #if ENABLED(MAX6675_IS_MAX31865) @@ -80,7 +80,7 @@ #endif #if ENABLED(EMERGENCY_PARSER) - #include "../feature/emergency_parser.h" + #include "../feature/e_parser.h" #endif #if ENABLED(PRINTER_EVENT_LEDS) @@ -101,11 +101,13 @@ #if HOTEND_USES_THERMISTOR #if ENABLED(TEMP_SENSOR_1_AS_REDUNDANT) - static void* heater_ttbl_map[2] = { (void*)HEATER_0_TEMPTABLE, (void*)HEATER_1_TEMPTABLE }; + static const void* heater_ttbl_map[2] = { (void*)HEATER_0_TEMPTABLE, (void*)HEATER_1_TEMPTABLE }; static constexpr uint8_t heater_ttbllen_map[2] = { HEATER_0_TEMPTABLE_LEN, HEATER_1_TEMPTABLE_LEN }; #else - static void* heater_ttbl_map[HOTENDS] = ARRAY_BY_HOTENDS((void*)HEATER_0_TEMPTABLE, (void*)HEATER_1_TEMPTABLE, (void*)HEATER_2_TEMPTABLE, (void*)HEATER_3_TEMPTABLE, (void*)HEATER_4_TEMPTABLE, (void*)HEATER_5_TEMPTABLE); - static constexpr uint8_t heater_ttbllen_map[HOTENDS] = ARRAY_BY_HOTENDS(HEATER_0_TEMPTABLE_LEN, HEATER_1_TEMPTABLE_LEN, HEATER_2_TEMPTABLE_LEN, HEATER_3_TEMPTABLE_LEN, HEATER_4_TEMPTABLE_LEN, HEATER_5_TEMPTABLE_LEN); + #define NEXT_TEMPTABLE(N) ,HEATER_##N##_TEMPTABLE + #define NEXT_TEMPTABLE_LEN(N) ,HEATER_##N##_TEMPTABLE_LEN + static const void* heater_ttbl_map[HOTENDS] = ARRAY_BY_HOTENDS(HEATER_0_TEMPTABLE REPEAT_S(1, HOTENDS, NEXT_TEMPTABLE)); + static constexpr uint8_t heater_ttbllen_map[HOTENDS] = ARRAY_BY_HOTENDS(HEATER_0_TEMPTABLE_LEN REPEAT_S(1, HOTENDS, NEXT_TEMPTABLE_LEN)); #endif #endif @@ -706,7 +708,7 @@ int16_t Temperature::getHeaterPower(const heater_ind_t heater_id) { }while(0) uint8_t fanDone = 0; - for (uint8_t f = 0; f < COUNT(fanBit); f++) { + LOOP_L_N(f, COUNT(fanBit)) { const uint8_t realFan = pgm_read_byte(&fanBit[f]); if (TEST(fanDone, realFan)) continue; const bool fan_on = TEST(fanState, realFan); @@ -1028,10 +1030,6 @@ void Temperature::manage_heater() { if (!inited) return watchdog_refresh(); #endif - #if BOTH(PROBING_HEATERS_OFF, BED_LIMIT_SWITCHING) - static bool last_pause_state; - #endif - #if ENABLED(EMERGENCY_PARSER) if (emergency_parser.killed_by_M112) kill(M112_KILL_STR, nullptr, true); #endif @@ -1123,16 +1121,21 @@ void Temperature::manage_heater() { } #endif // WATCH_BED + #define PAUSE_CHANGE_REQD BOTH(PROBING_HEATERS_OFF, BED_LIMIT_SWITCHING) + #if PAUSE_CHANGE_REQD + static bool last_pause_state; + #endif + do { #if DISABLED(PIDTEMPBED) if (PENDING(ms, next_bed_check_ms) - #if BOTH(PROBING_HEATERS_OFF, BED_LIMIT_SWITCHING) + #if PAUSE_CHANGE_REQD && paused == last_pause_state #endif ) break; next_bed_check_ms = ms + BED_CHECK_INTERVAL; - #if BOTH(PROBING_HEATERS_OFF, BED_LIMIT_SWITCHING) + #if PAUSE_CHANGE_REQD last_pause_state = paused; #endif #endif @@ -1232,8 +1235,8 @@ void Temperature::manage_heater() { UNUSED(ms); } -#define TEMP_AD595(RAW) ((RAW) * 5.0 * 100.0 / 1024.0 / (OVERSAMPLENR) * (TEMP_SENSOR_AD595_GAIN) + TEMP_SENSOR_AD595_OFFSET) -#define TEMP_AD8495(RAW) ((RAW) * 6.6 * 100.0 / 1024.0 / (OVERSAMPLENR) * (TEMP_SENSOR_AD8495_GAIN) + TEMP_SENSOR_AD8495_OFFSET) +#define TEMP_AD595(RAW) ((RAW) * 5.0 * 100.0 / float(HAL_ADC_RANGE) / (OVERSAMPLENR) * (TEMP_SENSOR_AD595_GAIN) + TEMP_SENSOR_AD595_OFFSET) +#define TEMP_AD8495(RAW) ((RAW) * 6.6 * 100.0 / float(HAL_ADC_RANGE) / (OVERSAMPLENR) * (TEMP_SENSOR_AD8495_GAIN) + TEMP_SENSOR_AD8495_OFFSET) /** * Bisect search for the range of the 'raw' value, then interpolate @@ -1660,10 +1663,9 @@ void Temperature::init() { #endif #if MB(RUMBA) + // Disable RUMBA JTAG in case the thermocouple extension is plugged on top of JTAG connector #define _AD(N) ANY(HEATER_##N##_USES_AD595, HEATER_##N##_USES_AD8495) - #if _AD(0) || _AD(1) || _AD(2) /* RUMBA has 3 E plugs // || _AD(3) || _AD(4) || _AD(5) || _AD(6) || _AD(7) */ \ - || _AD(BED) || _AD(CHAMBER) - // Disable RUMBA JTAG in case the thermocouple extension is plugged on top of JTAG connector + #if _AD(0) || _AD(1) || _AD(2) || _AD(BED) || _AD(CHAMBER) MCUCR = _BV(JTD); MCUCR = _BV(JTD); #endif @@ -2420,7 +2422,7 @@ void Temperature::readings_ready() { #endif // HOTENDS > 1 }; - for (uint8_t e = 0; e < COUNT(temp_dir); e++) { + LOOP_L_N(e, COUNT(temp_dir)) { const int8_t tdir = temp_dir[e]; if (tdir) { const int16_t rawtemp = temp_hotend[e].raw * tdir; // normal direction, +rawtemp, else -rawtemp @@ -3360,6 +3362,15 @@ void Temperature::tick() { return wait_for_heatup; } + void Temperature::wait_for_bed_heating() { + if (isHeatingBed()) { + SERIAL_ECHOLNPGM("Wait for bed heating..."); + LCD_MESSAGEPGM(MSG_BED_HEATING); + wait_for_bed(); + ui.reset_status(); + } + } + #endif // HAS_HEATED_BED #if HAS_HEATED_CHAMBER diff --git a/Marlin/src/module/temperature.h b/Marlin/src/module/temperature.h index 66d6bd56e1..24e0054496 100644 --- a/Marlin/src/module/temperature.h +++ b/Marlin/src/module/temperature.h @@ -74,8 +74,6 @@ hotend_pid_t; typedef IF<(LPQ_MAX_LEN > 255), uint16_t, uint8_t>::type lpq_ptr_t; #endif -#define DUMMY_PID_VALUE 3000.0f - #if ENABLED(PIDTEMP) #define _PID_Kp(H) Temperature::temp_hotend[H].pid.Kp #define _PID_Ki(H) Temperature::temp_hotend[H].pid.Ki @@ -92,9 +90,9 @@ hotend_pid_t; #define _PID_Kf(H) 0 #endif #else - #define _PID_Kp(H) DUMMY_PID_VALUE - #define _PID_Ki(H) DUMMY_PID_VALUE - #define _PID_Kd(H) DUMMY_PID_VALUE + #define _PID_Kp(H) NAN + #define _PID_Ki(H) NAN + #define _PID_Kd(H) NAN #define _PID_Kc(H) 1 #endif @@ -701,6 +699,8 @@ class Temperature { #endif ); + static void wait_for_bed_heating(); + #endif // HAS_HEATED_BED #if HAS_TEMP_PROBE diff --git a/Marlin/src/module/tool_change.cpp b/Marlin/src/module/tool_change.cpp index 021878c1ea..0d91669973 100644 --- a/Marlin/src/module/tool_change.cpp +++ b/Marlin/src/module/tool_change.cpp @@ -74,7 +74,7 @@ #endif #if ENABLED(PRUSA_MMU2) - #include "../feature/prusa_MMU2/mmu2.h" + #include "../feature/mmu2/mmu2.h" #endif #if HAS_LCD_MENU @@ -251,7 +251,7 @@ inline void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_a #elif ENABLED(PARKING_EXTRUDER) void pe_solenoid_init() { - for (uint8_t n = 0; n <= 1; ++n) + LOOP_LE_N(n, 1) #if ENABLED(PARKING_EXTRUDER_SOLENOIDS_INVERT) pe_activate_solenoid(n); #else @@ -368,11 +368,16 @@ inline void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_a #if ENABLED(SWITCHING_TOOLHEAD) + inline void swt_lock(const bool locked=true) { + const uint16_t swt_angles[2] = SWITCHING_TOOLHEAD_SERVO_ANGLES; + MOVE_SERVO(SWITCHING_TOOLHEAD_SERVO_NR, swt_angles[locked ? 0 : 1]); + } + + void swt_init() { swt_lock(); } + inline void switching_toolhead_tool_change(const uint8_t new_tool, bool no_move/*=false*/) { if (no_move) return; - constexpr uint16_t angles[2] = SWITCHING_TOOLHEAD_SERVO_ANGLES; - constexpr float toolheadposx[] = SWITCHING_TOOLHEAD_X_POS; const float placexpos = toolheadposx[active_extruder], grabxpos = toolheadposx[new_tool]; @@ -406,7 +411,7 @@ inline void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_a planner.synchronize(); if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("(2) Unlock and Place Toolhead"); - MOVE_SERVO(SWITCHING_TOOLHEAD_SERVO_NR, angles[1]); + swt_lock(false); safe_delay(500); current_position.y = SWITCHING_TOOLHEAD_Y_POS; @@ -451,7 +456,7 @@ inline void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_a // Wait for move to finish, pause 0.2s, move servo, pause 0.5s planner.synchronize(); safe_delay(200); - MOVE_SERVO(SWITCHING_TOOLHEAD_SERVO_NR, angles[0]); + swt_lock(); safe_delay(500); current_position.y -= SWITCHING_TOOLHEAD_Y_CLEAR; diff --git a/Marlin/src/module/tool_change.h b/Marlin/src/module/tool_change.h index 025d2997d1..17c173d052 100644 --- a/Marlin/src/module/tool_change.h +++ b/Marlin/src/module/tool_change.h @@ -97,6 +97,10 @@ void est_init(); #endif +#if ENABLED(SWITCHING_TOOLHEAD) + void swt_init(); +#endif + /** * Perform a tool-change, which may result in moving the * previous tool out of the way and the new tool into place. diff --git a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_1.h b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_1.h index 15b6349409..104f40fdf1 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_1.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_1.h @@ -103,7 +103,7 @@ // Trinamic driver support -#if HAS_TRINAMIC +#if HAS_TRINAMIC_CONFIG // Using TMC devices in intelligent mode requires extra connections to each device. Unfortunately // the SKR does not have many free pins (especially if a display is in use). The SPI-based devices // will require 3 connections (clock, mosi, miso), plus a chip select line (CS) for each driver. 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 316049d6b1..3fb66aa156 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h @@ -79,14 +79,20 @@ #define Z_MIN_PIN P1_00 // PWRDET #endif #else - #define Z_STOP_PIN P1_27 // Z-STOP + #ifndef Z_STOP_PIN + #define Z_STOP_PIN P1_27 // Z-STOP + #endif #endif // // Z Probe (when not Z_MIN_PIN) // #ifndef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN P0_10 + #if Z_STOP_PIN != P1_27 + #define Z_MIN_PROBE_PIN P1_27 + #else + #define Z_MIN_PROBE_PIN P0_10 + #endif #endif // diff --git a/Marlin/src/pins/lpc1768/pins_BTT_SKR_common.h b/Marlin/src/pins/lpc1768/pins_BTT_SKR_common.h index fc08a60b91..e84d3de2b1 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_common.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_common.h @@ -58,8 +58,9 @@ #ifndef TEMP_BED_PIN #define TEMP_BED_PIN P0_23_A0 // A0 (T0) - (67) - TEMP_BED_PIN #endif + #if HOTENDS == 1 && TEMP_SENSOR_PROBE - #define TEMP_PROBE_PIN P0_25_A2 // TEMP_1_PIN + #define TEMP_PROBE_PIN TEMP_1_PIN #endif // diff --git a/Marlin/src/pins/lpc1769/pins_COHESION3D_REMIX.h b/Marlin/src/pins/lpc1769/pins_COHESION3D_REMIX.h index ea40c01c08..58bf0d6e71 100644 --- a/Marlin/src/pins/lpc1769/pins_COHESION3D_REMIX.h +++ b/Marlin/src/pins/lpc1769/pins_COHESION3D_REMIX.h @@ -46,6 +46,13 @@ #define Z_MIN_PIN P1_28 // 10k pullup to 3.3V #define Z_MAX_PIN P1_29 // 10k pullup to 3.3V +// +// Z Probe (when not Z_MIN_PIN) +// +#ifndef Z_MIN_PROBE_PIN + #define Z_MIN_PROBE_PIN P1_29 +#endif + // // Steppers // diff --git a/Marlin/src/pins/mega/pins_GT2560_V3.h b/Marlin/src/pins/mega/pins_GT2560_V3.h index 4d6cee56f4..566e88705d 100644 --- a/Marlin/src/pins/mega/pins_GT2560_V3.h +++ b/Marlin/src/pins/mega/pins_GT2560_V3.h @@ -22,7 +22,7 @@ #pragma once /** - * GT2560 V3.0 pin assignment + * GT2560 RevB + GT2560 V3.0 + GT2560 V3.1 + GT2560 V4.0 pin assignment */ #if !defined(__AVR_ATmega1280__) && !defined(__AVR_ATmega2560__) diff --git a/Marlin/src/pins/pins.h b/Marlin/src/pins/pins.h index ce03a3468d..64b9e85ba8 100644 --- a/Marlin/src/pins/pins.h +++ b/Marlin/src/pins/pins.h @@ -35,7 +35,7 @@ * These numbers are the same in any pin mapping. */ -#define MAX_EXTRUDERS 6 +#define MAX_EXTRUDERS 8 #if MB(RAMPS_13_EFB, RAMPS_14_EFB, RAMPS_PLUS_EFB, RAMPS_14_RE_ARM_EFB, RAMPS_SMART_EFB, RAMPS_DUO_EFB, RAMPS4DUE_EFB) #define IS_RAMPS_EFB @@ -56,138 +56,138 @@ // #if MB(RAMPS_OLD) - #include "ramps/pins_RAMPS_OLD.h" // ATmega1280, ATmega2560 env:megaatmega1280 env:megaatmega2560 + #include "ramps/pins_RAMPS_OLD.h" // ATmega1280, ATmega2560 env:mega1280 env:mega2560 #elif MB(RAMPS_13_EFB) - #include "ramps/pins_RAMPS_13.h" // ATmega1280, ATmega2560 env:megaatmega1280 env:megaatmega2560 + #include "ramps/pins_RAMPS_13.h" // ATmega1280, ATmega2560 env:mega1280 env:mega2560 #elif MB(RAMPS_13_EEB) - #include "ramps/pins_RAMPS_13.h" // ATmega1280, ATmega2560 env:megaatmega1280 env:megaatmega2560 + #include "ramps/pins_RAMPS_13.h" // ATmega1280, ATmega2560 env:mega1280 env:mega2560 #elif MB(RAMPS_13_EFF) - #include "ramps/pins_RAMPS_13.h" // ATmega1280, ATmega2560 env:megaatmega1280 env:megaatmega2560 + #include "ramps/pins_RAMPS_13.h" // ATmega1280, ATmega2560 env:mega1280 env:mega2560 #elif MB(RAMPS_13_EEF) - #include "ramps/pins_RAMPS_13.h" // ATmega1280, ATmega2560 env:megaatmega1280 env:megaatmega2560 + #include "ramps/pins_RAMPS_13.h" // ATmega1280, ATmega2560 env:mega1280 env:mega2560 #elif MB(RAMPS_13_SF) - #include "ramps/pins_RAMPS_13.h" // ATmega1280, ATmega2560 env:megaatmega1280 env:megaatmega2560 + #include "ramps/pins_RAMPS_13.h" // ATmega1280, ATmega2560 env:mega1280 env:mega2560 #elif MB(RAMPS_14_EFB) - #include "ramps/pins_RAMPS.h" // ATmega1280, ATmega2560 env:megaatmega1280 env:megaatmega2560 + #include "ramps/pins_RAMPS.h" // ATmega1280, ATmega2560 env:mega1280 env:mega2560 #elif MB(RAMPS_14_EEB) - #include "ramps/pins_RAMPS.h" // ATmega1280, ATmega2560 env:megaatmega1280 env:megaatmega2560 + #include "ramps/pins_RAMPS.h" // ATmega1280, ATmega2560 env:mega1280 env:mega2560 #elif MB(RAMPS_14_EFF) - #include "ramps/pins_RAMPS.h" // ATmega1280, ATmega2560 env:megaatmega1280 env:megaatmega2560 + #include "ramps/pins_RAMPS.h" // ATmega1280, ATmega2560 env:mega1280 env:mega2560 #elif MB(RAMPS_14_EEF) - #include "ramps/pins_RAMPS.h" // ATmega1280, ATmega2560 env:megaatmega1280 env:megaatmega2560 + #include "ramps/pins_RAMPS.h" // ATmega1280, ATmega2560 env:mega1280 env:mega2560 #elif MB(RAMPS_14_SF) - #include "ramps/pins_RAMPS.h" // ATmega1280, ATmega2560 env:megaatmega1280 env:megaatmega2560 + #include "ramps/pins_RAMPS.h" // ATmega1280, ATmega2560 env:mega1280 env:mega2560 #elif MB(RAMPS_PLUS_EFB) - #include "ramps/pins_RAMPS_PLUS.h" // ATmega1280, ATmega2560 env:megaatmega1280 env:megaatmega2560 + #include "ramps/pins_RAMPS_PLUS.h" // ATmega1280, ATmega2560 env:mega1280 env:mega2560 #elif MB(RAMPS_PLUS_EEB) - #include "ramps/pins_RAMPS_PLUS.h" // ATmega1280, ATmega2560 env:megaatmega1280 env:megaatmega2560 + #include "ramps/pins_RAMPS_PLUS.h" // ATmega1280, ATmega2560 env:mega1280 env:mega2560 #elif MB(RAMPS_PLUS_EFF) - #include "ramps/pins_RAMPS_PLUS.h" // ATmega1280, ATmega2560 env:megaatmega1280 env:megaatmega2560 + #include "ramps/pins_RAMPS_PLUS.h" // ATmega1280, ATmega2560 env:mega1280 env:mega2560 #elif MB(RAMPS_PLUS_EEF) - #include "ramps/pins_RAMPS_PLUS.h" // ATmega1280, ATmega2560 env:megaatmega1280 env:megaatmega2560 + #include "ramps/pins_RAMPS_PLUS.h" // ATmega1280, ATmega2560 env:mega1280 env:mega2560 #elif MB(RAMPS_PLUS_SF) - #include "ramps/pins_RAMPS_PLUS.h" // ATmega1280, ATmega2560 env:megaatmega1280 env:megaatmega2560 + #include "ramps/pins_RAMPS_PLUS.h" // ATmega1280, ATmega2560 env:mega1280 env:mega2560 // // RAMPS Derivatives - ATmega1280, ATmega2560 // #elif MB(3DRAG) - #include "ramps/pins_3DRAG.h" // ATmega1280, ATmega2560 env:megaatmega1280 env:megaatmega2560 + #include "ramps/pins_3DRAG.h" // ATmega1280, ATmega2560 env:mega1280 env:mega2560 #elif MB(K8200) - #include "ramps/pins_K8200.h" // ATmega1280, ATmega2560 env:megaatmega1280 env:megaatmega2560 (3DRAG) + #include "ramps/pins_K8200.h" // ATmega1280, ATmega2560 env:mega1280 env:mega2560 (3DRAG) #elif MB(K8400) - #include "ramps/pins_K8400.h" // ATmega1280, ATmega2560 env:megaatmega1280 env:megaatmega2560 (3DRAG) + #include "ramps/pins_K8400.h" // ATmega1280, ATmega2560 env:mega1280 env:mega2560 (3DRAG) #elif MB(K8800) - #include "ramps/pins_K8800.h" // ATmega1280, ATmega2560 env:megaatmega1280 env:megaatmega2560 (3DRAG) + #include "ramps/pins_K8800.h" // ATmega1280, ATmega2560 env:mega1280 env:mega2560 (3DRAG) #elif MB(BAM_DICE) - #include "ramps/pins_RAMPS.h" // ATmega1280, ATmega2560 env:megaatmega1280 env:megaatmega2560 + #include "ramps/pins_RAMPS.h" // ATmega1280, ATmega2560 env:mega1280 env:mega2560 #elif MB(BAM_DICE_DUE) - #include "ramps/pins_BAM_DICE_DUE.h" // ATmega1280, ATmega2560 env:megaatmega1280 env:megaatmega2560 + #include "ramps/pins_BAM_DICE_DUE.h" // ATmega1280, ATmega2560 env:mega1280 env:mega2560 #elif MB(MKS_BASE) - #include "ramps/pins_MKS_BASE_10.h" // ATmega2560 env:megaatmega2560 + #include "ramps/pins_MKS_BASE_10.h" // ATmega2560 env:mega2560 #elif MB(MKS_BASE_14) - #include "ramps/pins_MKS_BASE_14.h" // ATmega2560 env:megaatmega2560 + #include "ramps/pins_MKS_BASE_14.h" // ATmega2560 env:mega2560 #elif MB(MKS_BASE_15) - #include "ramps/pins_MKS_BASE_15.h" // ATmega2560 env:megaatmega2560 + #include "ramps/pins_MKS_BASE_15.h" // ATmega2560 env:mega2560 #elif MB(MKS_BASE_16) - #include "ramps/pins_MKS_BASE_16.h" // ATmega2560 env:megaatmega2560 + #include "ramps/pins_MKS_BASE_16.h" // ATmega2560 env:mega2560 #elif MB(MKS_BASE_HEROIC) - #include "ramps/pins_MKS_BASE_HEROIC.h" // ATmega2560 env:megaatmega2560 + #include "ramps/pins_MKS_BASE_HEROIC.h" // ATmega2560 env:mega2560 #elif MB(MKS_GEN_13) - #include "ramps/pins_MKS_GEN_13.h" // ATmega1280, ATmega2560 env:megaatmega1280 env:megaatmega2560 + #include "ramps/pins_MKS_GEN_13.h" // ATmega1280, ATmega2560 env:mega1280 env:mega2560 #elif MB(MKS_GEN_L) - #include "ramps/pins_MKS_GEN_L.h" // ATmega1280, ATmega2560 env:megaatmega1280 env:megaatmega2560 + #include "ramps/pins_MKS_GEN_L.h" // ATmega1280, ATmega2560 env:mega1280 env:mega2560 #elif MB(KFB_2) - #include "ramps/pins_BIQU_KFB_2.h" // ATmega2560 env:megaatmega2560 + #include "ramps/pins_BIQU_KFB_2.h" // ATmega2560 env:mega2560 #elif MB(ZRIB_V20) - #include "ramps/pins_ZRIB_V20.h" // ATmega1280, ATmega2560 env:megaatmega1280 env:megaatmega2560 (MKS_GEN_13) + #include "ramps/pins_ZRIB_V20.h" // ATmega1280, ATmega2560 env:mega1280 env:mega2560 (MKS_GEN_13) #elif MB(FELIX2) - #include "ramps/pins_FELIX2.h" // ATmega1280, ATmega2560 env:megaatmega1280 env:megaatmega2560 + #include "ramps/pins_FELIX2.h" // ATmega1280, ATmega2560 env:mega1280 env:mega2560 #elif MB(RIGIDBOARD) - #include "ramps/pins_RIGIDBOARD.h" // ATmega1280, ATmega2560 env:megaatmega1280 env:megaatmega2560 + #include "ramps/pins_RIGIDBOARD.h" // ATmega1280, ATmega2560 env:mega1280 env:mega2560 #elif MB(RIGIDBOARD_V2) - #include "ramps/pins_RIGIDBOARD_V2.h" // ATmega1280, ATmega2560 env:megaatmega1280 env:megaatmega2560 + #include "ramps/pins_RIGIDBOARD_V2.h" // ATmega1280, ATmega2560 env:mega1280 env:mega2560 #elif MB(SAINSMART_2IN1) - #include "ramps/pins_SAINSMART_2IN1.h" // ATmega1280, ATmega2560 env:megaatmega1280 env:megaatmega2560 + #include "ramps/pins_SAINSMART_2IN1.h" // ATmega1280, ATmega2560 env:mega1280 env:mega2560 #elif MB(ULTIMAKER) - #include "ramps/pins_ULTIMAKER.h" // ATmega1280, ATmega2560 env:megaatmega1280 env:megaatmega2560 + #include "ramps/pins_ULTIMAKER.h" // ATmega1280, ATmega2560 env:mega1280 env:mega2560 #elif MB(ULTIMAKER_OLD) - #include "ramps/pins_ULTIMAKER_OLD.h" // ATmega1280, ATmega2560 env:megaatmega1280 env:megaatmega2560 + #include "ramps/pins_ULTIMAKER_OLD.h" // ATmega1280, ATmega2560 env:mega1280 env:mega2560 #elif MB(AZTEEG_X3) - #include "ramps/pins_AZTEEG_X3.h" // ATmega2560 env:megaatmega2560 + #include "ramps/pins_AZTEEG_X3.h" // ATmega2560 env:mega2560 #elif MB(AZTEEG_X3_PRO) - #include "ramps/pins_AZTEEG_X3_PRO.h" // ATmega2560 env:megaatmega2560 + #include "ramps/pins_AZTEEG_X3_PRO.h" // ATmega2560 env:mega2560 #elif MB(ULTIMAIN_2) - #include "ramps/pins_ULTIMAIN_2.h" // ATmega2560 env:megaatmega2560 + #include "ramps/pins_ULTIMAIN_2.h" // ATmega2560 env:mega2560 #elif MB(FORMBOT_RAPTOR) - #include "ramps/pins_FORMBOT_RAPTOR.h" // ATmega2560 env:megaatmega2560 + #include "ramps/pins_FORMBOT_RAPTOR.h" // ATmega2560 env:mega2560 #elif MB(FORMBOT_RAPTOR2) - #include "ramps/pins_FORMBOT_RAPTOR2.h" // ATmega2560 env:megaatmega2560 + #include "ramps/pins_FORMBOT_RAPTOR2.h" // ATmega2560 env:mega2560 #elif MB(FORMBOT_TREX2PLUS) - #include "ramps/pins_FORMBOT_TREX2PLUS.h" // ATmega2560 env:megaatmega2560 + #include "ramps/pins_FORMBOT_TREX2PLUS.h" // ATmega2560 env:mega2560 #elif MB(FORMBOT_TREX3) - #include "ramps/pins_FORMBOT_TREX3.h" // ATmega2560 env:megaatmega2560 + #include "ramps/pins_FORMBOT_TREX3.h" // ATmega2560 env:mega2560 #elif MB(RUMBA) - #include "ramps/pins_RUMBA.h" // ATmega2560 env:megaatmega2560 + #include "ramps/pins_RUMBA.h" // ATmega2560 env:mega2560 #elif MB(RUMBA_RAISE3D) - #include "ramps/pins_RUMBA_RAISE3D.h" // ATmega2560 env:megaatmega2560 + #include "ramps/pins_RUMBA_RAISE3D.h" // ATmega2560 env:mega2560 #elif MB(RL200) - #include "ramps/pins_RL200.h" // ATmega2560 env:megaatmega2560 + #include "ramps/pins_RL200.h" // ATmega2560 env:mega2560 #elif MB(BQ_ZUM_MEGA_3D) - #include "ramps/pins_BQ_ZUM_MEGA_3D.h" // ATmega2560 env:megaatmega2560 + #include "ramps/pins_BQ_ZUM_MEGA_3D.h" // ATmega2560 env:mega2560 #elif MB(MAKEBOARD_MINI) - #include "ramps/pins_MAKEBOARD_MINI.h" // ATmega2560 env:megaatmega2560 + #include "ramps/pins_MAKEBOARD_MINI.h" // ATmega2560 env:mega2560 #elif MB(TRIGORILLA_13) - #include "ramps/pins_TRIGORILLA_13.h" // ATmega2560 env:megaatmega2560 + #include "ramps/pins_TRIGORILLA_13.h" // ATmega2560 env:mega2560 #elif MB(TRIGORILLA_14) - #include "ramps/pins_TRIGORILLA_14.h" // ATmega2560 env:megaatmega2560 + #include "ramps/pins_TRIGORILLA_14.h" // ATmega2560 env:mega2560 #elif MB(TRIGORILLA_14_11) - #include "ramps/pins_TRIGORILLA_14.h" // ATmega2560 env:megaatmega2560 + #include "ramps/pins_TRIGORILLA_14.h" // ATmega2560 env:mega2560 #elif MB(RAMPS_ENDER_4) - #include "ramps/pins_RAMPS_ENDER_4.h" // ATmega2560 env:megaatmega2560 + #include "ramps/pins_RAMPS_ENDER_4.h" // ATmega2560 env:mega2560 #elif MB(RAMPS_CREALITY) - #include "ramps/pins_RAMPS_CREALITY.h" // ATmega2560 env:megaatmega2560 + #include "ramps/pins_RAMPS_CREALITY.h" // ATmega2560 env:mega2560 #elif MB(RAMPS_DAGOMA) - #include "ramps/pins_RAMPS_DAGOMA.h" // ATmega2560 env:megaatmega2560 + #include "ramps/pins_RAMPS_DAGOMA.h" // ATmega2560 env:mega2560 #elif MB(FYSETC_F6_13) #include "ramps/pins_FYSETC_F6_13.h" // ATmega2560 env:FYSETC_F6_13 #elif MB(FYSETC_F6_14) #include "ramps/pins_FYSETC_F6_14.h" // ATmega2560 env:FYSETC_F6_14 #elif MB(DUPLICATOR_I3_PLUS) - #include "ramps/pins_DUPLICATOR_I3_PLUS.h" // ATmega2560 env:megaatmega2560 + #include "ramps/pins_DUPLICATOR_I3_PLUS.h" // ATmega2560 env:mega2560 #elif MB(VORON) - #include "ramps/pins_VORON.h" // ATmega2560 env:megaatmega2560 + #include "ramps/pins_VORON.h" // ATmega2560 env:mega2560 #elif MB(TRONXY_V3_1_0) - #include "ramps/pins_TRONXY_V3_1_0.h" // ATmega2560 env:megaatmega2560 + #include "ramps/pins_TRONXY_V3_1_0.h" // ATmega2560 env:mega2560 #elif MB(Z_BOLT_X_SERIES) - #include "ramps/pins_Z_BOLT_X_SERIES.h" // ATmega2560 env:megaatmega2560 + #include "ramps/pins_Z_BOLT_X_SERIES.h" // ATmega2560 env:mega2560 #elif MB(TT_OSCAR) - #include "ramps/pins_TT_OSCAR.h" // ATmega2560 env:megaatmega2560 + #include "ramps/pins_TT_OSCAR.h" // ATmega2560 env:mega2560 #elif MB(TANGO) - #include "ramps/pins_TANGO.h" // ATmega2560 env:megaatmega2560 + #include "ramps/pins_TANGO.h" // ATmega2560 env:mega2560 #elif MB(MKS_GEN_L_V2) - #include "ramps/pins_MKS_GEN_L_V2.h" // ATmega2560 env:megaatmega2560 + #include "ramps/pins_MKS_GEN_L_V2.h" // ATmega2560 env:mega2560 // // RAMBo and derivatives @@ -209,114 +209,114 @@ // #elif MB(CNCONTROLS_11) - #include "mega/pins_CNCONTROLS_11.h" // ATmega1280, ATmega2560 env:megaatmega1280 env:megaatmega2560 + #include "mega/pins_CNCONTROLS_11.h" // ATmega1280, ATmega2560 env:mega1280 env:mega2560 #elif MB(CNCONTROLS_12) - #include "mega/pins_CNCONTROLS_12.h" // ATmega1280, ATmega2560 env:megaatmega1280 env:megaatmega2560 + #include "mega/pins_CNCONTROLS_12.h" // ATmega1280, ATmega2560 env:mega1280 env:mega2560 #elif MB(CNCONTROLS_15) - #include "mega/pins_CNCONTROLS_15.h" // ATmega1280, ATmega2560 env:megaatmega1280 env:megaatmega2560 + #include "mega/pins_CNCONTROLS_15.h" // ATmega1280, ATmega2560 env:mega1280 env:mega2560 #elif MB(MIGHTYBOARD_REVE) - #include "mega/pins_MIGHTYBOARD_REVE.h" // ATmega1280, ATmega2560 env:megaatmega1280 env:megaatmega2560 + #include "mega/pins_MIGHTYBOARD_REVE.h" // ATmega1280, ATmega2560 env:mega1280 env:mega2560 #elif MB(CHEAPTRONIC) - #include "mega/pins_CHEAPTRONIC.h" // ATmega2560 env:megaatmega2560 + #include "mega/pins_CHEAPTRONIC.h" // ATmega2560 env:mega2560 #elif MB(CHEAPTRONIC_V2) - #include "mega/pins_CHEAPTRONICv2.h" // ATmega2560 env:megaatmega2560 + #include "mega/pins_CHEAPTRONICv2.h" // ATmega2560 env:mega2560 #elif MB(MEGATRONICS) - #include "mega/pins_MEGATRONICS.h" // ATmega2560 env:megaatmega2560 + #include "mega/pins_MEGATRONICS.h" // ATmega2560 env:mega2560 #elif MB(MEGATRONICS_2) - #include "mega/pins_MEGATRONICS_2.h" // ATmega2560 env:megaatmega2560 + #include "mega/pins_MEGATRONICS_2.h" // ATmega2560 env:mega2560 #elif MB(MEGATRONICS_3, MEGATRONICS_31, MEGATRONICS_32) - #include "mega/pins_MEGATRONICS_3.h" // ATmega2560 env:megaatmega2560 + #include "mega/pins_MEGATRONICS_3.h" // ATmega2560 env:mega2560 #elif MB(ELEFU_3) - #include "mega/pins_ELEFU_3.h" // ATmega2560 env:megaatmega2560 + #include "mega/pins_ELEFU_3.h" // ATmega2560 env:mega2560 #elif MB(LEAPFROG) - #include "mega/pins_LEAPFROG.h" // ATmega1280, ATmega2560 env:megaatmega1280 env:megaatmega2560 + #include "mega/pins_LEAPFROG.h" // ATmega1280, ATmega2560 env:mega1280 env:mega2560 #elif MB(MEGACONTROLLER) - #include "mega/pins_MEGACONTROLLER.h" // ATmega2560 env:megaatmega2560 + #include "mega/pins_MEGACONTROLLER.h" // ATmega2560 env:mega2560 #elif MB(GT2560_REV_A) - #include "mega/pins_GT2560_REV_A.h" // ATmega1280, ATmega2560 env:megaatmega1280 env:megaatmega2560 + #include "mega/pins_GT2560_REV_A.h" // ATmega1280, ATmega2560 env:mega1280 env:mega2560 #elif MB(GT2560_REV_A_PLUS) - #include "mega/pins_GT2560_REV_A_PLUS.h" // ATmega1280, ATmega2560 env:megaatmega1280 env:megaatmega2560 + #include "mega/pins_GT2560_REV_A_PLUS.h" // ATmega1280, ATmega2560 env:mega1280 env:mega2560 #elif MB(GT2560_V3) - #include "mega/pins_GT2560_V3.h" // ATmega2560 env:megaatmega2560 + #include "mega/pins_GT2560_V3.h" // ATmega2560 env:mega2560 #elif MB(GT2560_V3_MC2) - #include "mega/pins_GT2560_V3_MC2.h" // ATmega2560 env:megaatmega2560 + #include "mega/pins_GT2560_V3_MC2.h" // ATmega2560 env:mega2560 #elif MB(GT2560_V3_A20) - #include "mega/pins_GT2560_V3_A20.h" // ATmega2560 env:megaatmega2560 + #include "mega/pins_GT2560_V3_A20.h" // ATmega2560 env:mega2560 #elif MB(EINSTART_S) - #include "mega/pins_EINSTART-S.h" // ATmega1280, ATmega2560 env:megaatmega1280 env:megaatmega2560 + #include "mega/pins_EINSTART-S.h" // ATmega1280, ATmega2560 env:mega1280 env:mega2560 #elif MB(WANHAO_ONEPLUS) - #include "mega/pins_WANHAO_ONEPLUS.h" // ATmega2560 env:megaatmega2560 + #include "mega/pins_WANHAO_ONEPLUS.h" // ATmega2560 env:mega2560 #elif MB(OVERLORD) - #include "mega/pins_OVERLORD.h" // ATmega2560 env:megaatmega2560 + #include "mega/pins_OVERLORD.h" // ATmega2560 env:mega2560 #elif MB(HJC2560C_REV2) - #include "mega/pins_HJC2560C_REV2.h" // ATmega2560 env:megaatmega2560 + #include "mega/pins_HJC2560C_REV2.h" // ATmega2560 env:mega2560 #elif MB(LEAPFROG_XEED2015) - #include "mega/pins_LEAPFROG_XEED2015.h" // ATmega2560 env:megaatmega2560 + #include "mega/pins_LEAPFROG_XEED2015.h" // ATmega2560 env:mega2560 #elif MB(PICA) - #include "mega/pins_PICA.h" // ATmega2560 env:megaatmega2560 + #include "mega/pins_PICA.h" // ATmega2560 env:mega2560 #elif MB(PICA_REVB) - #include "mega/pins_PICAOLD.h" // ATmega2560 env:megaatmega2560 + #include "mega/pins_PICAOLD.h" // ATmega2560 env:mega2560 // // ATmega1281, ATmega2561 // #elif MB(MINITRONICS) - #include "mega/pins_MINITRONICS.h" // ATmega1281 env:megaatmega1280 + #include "mega/pins_MINITRONICS.h" // ATmega1281 env:mega1280 #elif MB(SILVER_GATE) - #include "mega/pins_SILVER_GATE.h" // ATmega2561 env:megaatmega2560 + #include "mega/pins_SILVER_GATE.h" // ATmega2561 env:mega2560 // // Sanguinololu and Derivatives - ATmega644P, ATmega1284P // #elif MB(SANGUINOLOLU_11) - #include "sanguino/pins_SANGUINOLOLU_11.h" // ATmega644P, ATmega1284P env:sanguino_atmega644p env:sanguino_atmega1284p + #include "sanguino/pins_SANGUINOLOLU_11.h" // ATmega644P, ATmega1284P env:sanguino644p env:sanguino1284p #elif MB(SANGUINOLOLU_12) - #include "sanguino/pins_SANGUINOLOLU_12.h" // ATmega644P, ATmega1284P env:sanguino_atmega644p env:sanguino_atmega1284p + #include "sanguino/pins_SANGUINOLOLU_12.h" // ATmega644P, ATmega1284P env:sanguino644p env:sanguino1284p #elif MB(MELZI) - #include "sanguino/pins_MELZI.h" // ATmega644P, ATmega1284P env:sanguino_atmega644p env:sanguino_atmega1284p + #include "sanguino/pins_MELZI.h" // ATmega644P, ATmega1284P env:sanguino644p env:sanguino1284p #elif MB(MELZI_MAKR3D) - #include "sanguino/pins_MELZI_MAKR3D.h" // ATmega644P, ATmega1284P env:sanguino_atmega644p env:sanguino_atmega1284p + #include "sanguino/pins_MELZI_MAKR3D.h" // ATmega644P, ATmega1284P env:sanguino644p env:sanguino1284p #elif MB(MELZI_CREALITY) - #include "sanguino/pins_MELZI_CREALITY.h" // ATmega644P, ATmega1284P env:sanguino_atmega644p env:sanguino_atmega1284p + #include "sanguino/pins_MELZI_CREALITY.h" // ATmega644P, ATmega1284P env:sanguino644p env:sanguino1284p #elif MB(MELZI_MALYAN) - #include "sanguino/pins_MELZI_MALYAN.h" // ATmega644P, ATmega1284P env:sanguino_atmega644p env:sanguino_atmega1284p + #include "sanguino/pins_MELZI_MALYAN.h" // ATmega644P, ATmega1284P env:sanguino644p env:sanguino1284p #elif MB(MELZI_TRONXY) - #include "sanguino/pins_MELZI_TRONXY.h" // ATmega644P, ATmega1284P env:sanguino_atmega644p env:sanguino_atmega1284p + #include "sanguino/pins_MELZI_TRONXY.h" // ATmega644P, ATmega1284P env:sanguino644p env:sanguino1284p #elif MB(STB_11) - #include "sanguino/pins_STB_11.h" // ATmega644P, ATmega1284P env:sanguino_atmega644p env:sanguino_atmega1284p + #include "sanguino/pins_STB_11.h" // ATmega644P, ATmega1284P env:sanguino644p env:sanguino1284p #elif MB(AZTEEG_X1) - #include "sanguino/pins_AZTEEG_X1.h" // ATmega644P, ATmega1284P env:sanguino_atmega644p env:sanguino_atmega1284p + #include "sanguino/pins_AZTEEG_X1.h" // ATmega644P, ATmega1284P env:sanguino644p env:sanguino1284p // // Other ATmega644P, ATmega644, ATmega1284P // #elif MB(GEN3_MONOLITHIC) - #include "sanguino/pins_GEN3_MONOLITHIC.h" // ATmega644P env:sanguino_atmega644p + #include "sanguino/pins_GEN3_MONOLITHIC.h" // ATmega644P env:sanguino644p #elif MB(GEN3_PLUS) - #include "sanguino/pins_GEN3_PLUS.h" // ATmega644P, ATmega1284P env:sanguino_atmega644p env:sanguino_atmega1284p + #include "sanguino/pins_GEN3_PLUS.h" // ATmega644P, ATmega1284P env:sanguino644p env:sanguino1284p #elif MB(GEN6) - #include "sanguino/pins_GEN6.h" // ATmega644P, ATmega1284P env:sanguino_atmega644p env:sanguino_atmega1284p + #include "sanguino/pins_GEN6.h" // ATmega644P, ATmega1284P env:sanguino644p env:sanguino1284p #elif MB(GEN6_DELUXE) - #include "sanguino/pins_GEN6_DELUXE.h" // ATmega644P, ATmega1284P env:sanguino_atmega644p env:sanguino_atmega1284p + #include "sanguino/pins_GEN6_DELUXE.h" // ATmega644P, ATmega1284P env:sanguino644p env:sanguino1284p #elif MB(GEN7_CUSTOM) - #include "sanguino/pins_GEN7_CUSTOM.h" // ATmega644P, ATmega644, ATmega1284P env:sanguino_atmega644p env:sanguino_atmega1284p + #include "sanguino/pins_GEN7_CUSTOM.h" // ATmega644P, ATmega644, ATmega1284P env:sanguino644p env:sanguino1284p #elif MB(GEN7_12) - #include "sanguino/pins_GEN7_12.h" // ATmega644P, ATmega644, ATmega1284P env:sanguino_atmega644p env:sanguino_atmega1284p + #include "sanguino/pins_GEN7_12.h" // ATmega644P, ATmega644, ATmega1284P env:sanguino644p env:sanguino1284p #elif MB(GEN7_13) - #include "sanguino/pins_GEN7_13.h" // ATmega644P, ATmega644, ATmega1284P env:sanguino_atmega644p env:sanguino_atmega1284p + #include "sanguino/pins_GEN7_13.h" // ATmega644P, ATmega644, ATmega1284P env:sanguino644p env:sanguino1284p #elif MB(GEN7_14) - #include "sanguino/pins_GEN7_14.h" // ATmega644P, ATmega644, ATmega1284P env:sanguino_atmega644p env:sanguino_atmega1284p + #include "sanguino/pins_GEN7_14.h" // ATmega644P, ATmega644, ATmega1284P env:sanguino644p env:sanguino1284p #elif MB(OMCA_A) - #include "sanguino/pins_OMCA_A.h" // ATmega644 env:sanguino_atmega644p + #include "sanguino/pins_OMCA_A.h" // ATmega644 env:sanguino644p #elif MB(OMCA) - #include "sanguino/pins_OMCA.h" // ATmega644P, ATmega644 env:sanguino_atmega644p + #include "sanguino/pins_OMCA.h" // ATmega644P, ATmega644 env:sanguino644p #elif MB(ANET_10) - #include "sanguino/pins_ANET_10.h" // ATmega1284P env:sanguino_atmega1284p + #include "sanguino/pins_ANET_10.h" // ATmega1284P env:sanguino1284p #elif MB(SETHI) - #include "sanguino/pins_SETHI.h" // ATmega644P, ATmega644, ATmega1284P env:sanguino_atmega644p env:sanguino_atmega1284p + #include "sanguino/pins_SETHI.h" // ATmega644P, ATmega644, ATmega1284P env:sanguino644p env:sanguino1284p // // Teensyduino - AT90USB1286, AT90USB1286P @@ -491,13 +491,13 @@ #elif MB(MKS_ROBIN_LITE) #include "stm32/pins_MKS_ROBIN_LITE.h" // STM32F1 env:mks_robin_lite #elif MB(BTT_SKR_MINI_V1_1) - #include "stm32/pins_BTT_SKR_MINI_V1_1.h" // STM32F1 env:STM32F103RC_bigtree env:STM32F103RC_bigtree_512K env:STM32F103RC_bigtree_USB env:STM32F103RC_bigtree_512K_USB + #include "stm32/pins_BTT_SKR_MINI_V1_1.h" // STM32F1 env:STM32F103RC_btt env:STM32F103RC_btt_512K env:STM32F103RC_btt_USB env:STM32F103RC_btt_512K_USB #elif MB(BTT_SKR_MINI_E3_V1_0) - #include "stm32/pins_BTT_SKR_MINI_E3_V1_0.h" // STM32F1 env:STM32F103RC_bigtree env:STM32F103RC_bigtree_512K env:STM32F103RC_bigtree_USB env:STM32F103RC_bigtree_512K_USB + #include "stm32/pins_BTT_SKR_MINI_E3_V1_0.h" // STM32F1 env:STM32F103RC_btt env:STM32F103RC_btt_512K env:STM32F103RC_btt_USB env:STM32F103RC_btt_512K_USB #elif MB(BTT_SKR_MINI_E3_V1_2) - #include "stm32/pins_BTT_SKR_MINI_E3_V1_2.h" // STM32F1 env:STM32F103RC_bigtree env:STM32F103RC_bigtree_512K env:STM32F103RC_bigtree_USB env:STM32F103RC_bigtree_512K_USB + #include "stm32/pins_BTT_SKR_MINI_E3_V1_2.h" // STM32F1 env:STM32F103RC_btt env:STM32F103RC_btt_512K env:STM32F103RC_btt_USB env:STM32F103RC_btt_512K_USB #elif MB(BTT_SKR_E3_DIP) - #include "stm32/pins_BTT_SKR_E3_DIP.h" // STM32F1 env:STM32F103RE_bigtree env:STM32F103RE_bigtree_USB env:STM32F103RC_bigtree env:STM32F103RC_bigtree_512K env:STM32F103RC_bigtree_USB env:STM32F103RC_bigtree_512K_USB + #include "stm32/pins_BTT_SKR_E3_DIP.h" // STM32F1 env:STM32F103RE_btt env:STM32F103RE_btt_USB env:STM32F103RC_btt env:STM32F103RC_btt_512K env:STM32F103RC_btt_USB env:STM32F103RC_btt_512K_USB #elif MB(JGAURORA_A5S_A1) #include "stm32/pins_JGAURORA_A5S_A1.h" // STM32F1 env:jgaurora_a5s_a1 #elif MB(FYSETC_AIO_II) @@ -862,6 +862,43 @@ #define E7_ENABLE_PIN -1 #endif +// +// Destroy unused CS pins +// +#if !AXIS_HAS_SPI(X) + #undef X_CS_PIN +#endif +#if !AXIS_HAS_SPI(Y) + #undef Y_CS_PIN +#endif +#if !AXIS_HAS_SPI(Z) + #undef Z_CS_PIN +#endif +#if E_STEPPERS && !AXIS_HAS_SPI(E0) + #undef E0_CS_PIN +#endif +#if E_STEPPERS > 1 && !AXIS_HAS_SPI(E1) + #undef E1_CS_PIN +#endif +#if E_STEPPERS > 2 && !AXIS_HAS_SPI(E2) + #undef E2_CS_PIN +#endif +#if E_STEPPERS > 3 && !AXIS_HAS_SPI(E3) + #undef E3_CS_PIN +#endif +#if E_STEPPERS > 4 && !AXIS_HAS_SPI(E4) + #undef E4_CS_PIN +#endif +#if E_STEPPERS > 5 && !AXIS_HAS_SPI(E5) + #undef E5_CS_PIN +#endif +#if E_STEPPERS > 6 && !AXIS_HAS_SPI(E6) + #undef E6_CS_PIN +#endif +#if E_STEPPERS > 7 && !AXIS_HAS_SPI(E7) + #undef E7_CS_PIN +#endif + #ifndef X_CS_PIN #define X_CS_PIN -1 #endif @@ -1170,6 +1207,9 @@ #if HAS_FILAMENT_SENSOR #define FIL_RUNOUT1_PIN FIL_RUNOUT_PIN +#else + #undef FIL_RUNOUT_PIN + #undef FIL_RUNOUT1_PIN #endif #ifndef LCD_PINS_D4 diff --git a/Marlin/src/pins/pinsDebug.h b/Marlin/src/pins/pinsDebug.h index f247c7cacf..c08acd3836 100644 --- a/Marlin/src/pins/pinsDebug.h +++ b/Marlin/src/pins/pinsDebug.h @@ -207,17 +207,32 @@ static void print_input_or_output(const bool isout) { } // pretty report with PWM info -inline void report_pin_state_extended(pin_t pin, bool ignore, bool extended = false, const char *start_string = "") { +inline void report_pin_state_extended(pin_t pin, const bool ignore, const bool extended=false, PGM_P const start_string=nullptr) { char buffer[MAX_NAME_LENGTH + 1]; // for the sprintf statements bool found = false, multi_name_pin = false; - for (uint8_t x = 0; x < COUNT(pin_array); x++) { // scan entire array and report all instances of this pin + auto alt_pin_echo = [](const pin_t &pin) { + #if AVR_AT90USB1286_FAMILY + // Use FastIO for pins Teensy doesn't expose + if (pin == 46) { + print_input_or_output(IS_OUTPUT(46)); + SERIAL_CHAR('0' + READ(46)); + return false; + } + else if (pin == 47) { + print_input_or_output(IS_OUTPUT(47)); + SERIAL_CHAR('0' + READ(47)); + return false; + } + #endif + return true; + }; + + LOOP_L_N(x, COUNT(pin_array)) { // scan entire array and report all instances of this pin if (GET_ARRAY_PIN(x) == pin) { - if (found) multi_name_pin = true; - found = true; - if (!multi_name_pin) { // report digital and analog pin number only on the first time through - sprintf_P(buffer, PSTR("%sPIN: "), start_string); // digital pin number - SERIAL_ECHO(buffer); + if (!found) { // report digital and analog pin number only on the first time through + if (start_string) serialprintPGM(start_string); + serialprintPGM(PSTR("PIN: ")); PRINT_PIN(pin); PRINT_PORT(pin); if (int8_t(DIGITAL_PIN_TO_ANALOG_PIN(pin)) >= 0) { @@ -228,27 +243,14 @@ inline void report_pin_state_extended(pin_t pin, bool ignore, bool extended = fa } else { SERIAL_CHAR('.'); - SERIAL_ECHO_SP(MULTI_NAME_PAD + strlen(start_string)); // add padding if not the first instance found + SERIAL_ECHO_SP(MULTI_NAME_PAD + (start_string ? strlen_P(start_string) : 0)); // add padding if not the first instance found } PRINT_ARRAY_NAME(x); if (extended) { if (pin_is_protected(pin) && !ignore) SERIAL_ECHOPGM("protected "); else { - #if AVR_AT90USB1286_FAMILY //Teensy IDEs don't know about these pins so must use FASTIO - if (pin == 46 || pin == 47) { - if (pin == 46) { - print_input_or_output(IS_OUTPUT(46)); - SERIAL_CHAR('0' + READ(46)); - } - else if (pin == 47) { - print_input_or_output(IS_OUTPUT(47)); - SERIAL_CHAR('0' + READ(47)); - } - } - else - #endif - { + if (alt_pin_echo(pin)) { if (!GET_ARRAY_IS_DIGITAL(x)) { sprintf_P(buffer, PSTR("Analog in = %5ld"), (long)analogRead(DIGITAL_PIN_TO_ANALOG_PIN(pin))); SERIAL_ECHO(buffer); @@ -274,12 +276,14 @@ inline void report_pin_state_extended(pin_t pin, bool ignore, bool extended = fa } } SERIAL_EOL(); + multi_name_pin = found; + found = true; } // end of IF } // end of for loop if (!found) { - sprintf_P(buffer, PSTR("%sPIN: "), start_string); - SERIAL_ECHO(buffer); + if (start_string) serialprintPGM(start_string); + serialprintPGM(PSTR("PIN: ")); PRINT_PIN(pin); PRINT_PORT(pin); if (int8_t(DIGITAL_PIN_TO_ANALOG_PIN(pin)) >= 0) { @@ -290,21 +294,8 @@ inline void report_pin_state_extended(pin_t pin, bool ignore, bool extended = fa SERIAL_ECHO_SP(8); // add padding if not an analog pin SERIAL_ECHOPGM(""); if (extended) { - #if AVR_AT90USB1286_FAMILY //Teensy IDEs don't know about these pins so must use FASTIO - if (pin == 46 || pin == 47) { - SERIAL_ECHO_SP(12); - if (pin == 46) { - print_input_or_output(IS_OUTPUT(46)); - SERIAL_CHAR('0' + READ(46)); - } - else { - print_input_or_output(IS_OUTPUT(47)); - SERIAL_CHAR('0' + READ(47)); - } - } - else - #endif - { + + if (alt_pin_echo(pin)) { if (pwm_status(pin)) { // do nothing } diff --git a/Marlin/src/pins/pinsDebug_list.h b/Marlin/src/pins/pinsDebug_list.h index dae4bde450..28478973fb 100644 --- a/Marlin/src/pins/pinsDebug_list.h +++ b/Marlin/src/pins/pinsDebug_list.h @@ -168,6 +168,18 @@ #if defined(BTN_UP) && BTN_UP >= 0 REPORT_NAME_DIGITAL(__LINE__, BTN_UP) #endif +#if PIN_EXISTS(JOY_X) + REPORT_NAME_DIGITAL(__LINE__, JOY_X_PIN) +#endif +#if PIN_EXISTS(JOY_Y) + REPORT_NAME_DIGITAL(__LINE__, JOY_Y_PIN) +#endif +#if PIN_EXISTS(JOY_Z) + REPORT_NAME_DIGITAL(__LINE__, JOY_Z_PIN) +#endif +#if PIN_EXISTS(JOY_EN) + REPORT_NAME_DIGITAL(__LINE__, JOY_EN_PIN) +#endif #if PIN_EXISTS(CASE_LIGHT) REPORT_NAME_DIGITAL(__LINE__, CASE_LIGHT_PIN) #endif @@ -547,6 +559,18 @@ #if PIN_EXISTS(FAN7) REPORT_NAME_DIGITAL(__LINE__, FAN7_PIN) #endif +#if PIN_EXISTS(FAN_MUX0) + REPORT_NAME_DIGITAL(__LINE__, FAN_MUX0_PIN) +#endif +#if PIN_EXISTS(FAN_MUX1) + REPORT_NAME_DIGITAL(__LINE__, FAN_MUX1_PIN) +#endif +#if PIN_EXISTS(FAN_MUX2) + REPORT_NAME_DIGITAL(__LINE__, FAN_MUX2_PIN) +#endif +#if PIN_EXISTS(POWER_LOSS) + REPORT_NAME_DIGITAL(__LINE__, POWER_LOSS_PIN) +#endif #if PIN_EXISTS(FIL_RUNOUT) REPORT_NAME_DIGITAL(__LINE__, FIL_RUNOUT_PIN) #endif @@ -565,6 +589,12 @@ #if PIN_EXISTS(FIL_RUNOUT6) REPORT_NAME_DIGITAL(__LINE__, FIL_RUNOUT6_PIN) #endif +#if PIN_EXISTS(FIL_RUNOUT7) + REPORT_NAME_DIGITAL(__LINE__, FIL_RUNOUT7_PIN) +#endif +#if PIN_EXISTS(FIL_RUNOUT8) + REPORT_NAME_DIGITAL(__LINE__, FIL_RUNOUT8_PIN) +#endif #if PIN_EXISTS(HEATER_0) REPORT_NAME_DIGITAL(__LINE__, HEATER_0_PIN) #endif @@ -592,6 +622,9 @@ #if PIN_EXISTS(HEATER_BED) REPORT_NAME_DIGITAL(__LINE__, HEATER_BED_PIN) #endif +#if PIN_EXISTS(HEATER_CHAMBER) + REPORT_NAME_DIGITAL(__LINE__, HEATER_CHAMBER_PIN) +#endif #if PIN_EXISTS(HOME) REPORT_NAME_DIGITAL(__LINE__, HOME_PIN) #endif @@ -637,9 +670,6 @@ #if PIN_EXISTS(LED_RED) REPORT_NAME_DIGITAL(__LINE__, LED_RED_PIN) #endif -#if PIN_EXISTS(MAX) - REPORT_NAME_DIGITAL(__LINE__, MAX_PIN) -#endif #if PIN_EXISTS(MAX6675_DO) REPORT_NAME_DIGITAL(__LINE__, MAX6675_DO_PIN) #endif @@ -652,6 +682,16 @@ #if PIN_EXISTS(MAX6675_SS2) REPORT_NAME_DIGITAL(__LINE__, MAX6675_SS2_PIN) #endif +#if PIN_EXISTS(MAX7219_CLK) + REPORT_NAME_DIGITAL(__LINE__, MAX7219_CLK_PIN) +#endif +#if PIN_EXISTS(MAX7219_DIN) + REPORT_NAME_DIGITAL(__LINE__, MAX7219_DIN_PIN) +#endif +#if PIN_EXISTS(MAX7219_LOAD) + REPORT_NAME_DIGITAL(__LINE__, MAX7219_LOAD_PIN) +#endif + // #if defined(MISO) && MISO >= 0 // REPORT_NAME_DIGITAL(__LINE__, MISO) // #endif @@ -700,33 +740,12 @@ #if PIN_EXISTS(MOTOR_FAULT) REPORT_NAME_DIGITAL(__LINE__, MOTOR_FAULT_PIN) #endif -#if PIN_EXISTS(ORIG_E0_AUTO_FAN) - REPORT_NAME_DIGITAL(__LINE__, ORIG_E0_AUTO_FAN_PIN) -#endif -#if PIN_EXISTS(ORIG_E1_AUTO_FAN) - REPORT_NAME_DIGITAL(__LINE__, ORIG_E1_AUTO_FAN_PIN) -#endif -#if PIN_EXISTS(ORIG_E2_AUTO_FAN) - REPORT_NAME_DIGITAL(__LINE__, ORIG_E2_AUTO_FAN_PIN) -#endif -#if PIN_EXISTS(ORIG_E3_AUTO_FAN) - REPORT_NAME_DIGITAL(__LINE__, ORIG_E3_AUTO_FAN_PIN) -#endif -#if PIN_EXISTS(ORIG_E4_AUTO_FAN) - REPORT_NAME_DIGITAL(__LINE__, ORIG_E4_AUTO_FAN_PIN) -#endif -#if PIN_EXISTS(ORIG_E5_AUTO_FAN) - REPORT_NAME_DIGITAL(__LINE__, ORIG_E5_AUTO_FAN_PIN) -#endif -#if PIN_EXISTS(ORIG_E6_AUTO_FAN) - REPORT_NAME_DIGITAL(__LINE__, ORIG_E6_AUTO_FAN_PIN) -#endif -#if PIN_EXISTS(ORIG_E7_AUTO_FAN) - REPORT_NAME_DIGITAL(__LINE__, ORIG_E7_AUTO_FAN_PIN) -#endif #if PIN_EXISTS(PHOTOGRAPH) REPORT_NAME_DIGITAL(__LINE__, PHOTOGRAPH_PIN) #endif +#if PIN_EXISTS(CHDK) + REPORT_NAME_DIGITAL(__LINE__, CHDK_PIN) +#endif #if PIN_EXISTS(PS_ON) REPORT_NAME_DIGITAL(__LINE__, PS_ON_PIN) #endif @@ -748,6 +767,12 @@ #if PIN_EXISTS(RAMPS_D9) REPORT_NAME_DIGITAL(__LINE__, RAMPS_D9_PIN) #endif +#if PIN_EXISTS(NEOPIXEL) + REPORT_NAME_DIGITAL(__LINE__, NEOPIXEL_PIN) +#endif +#if PIN_EXISTS(NEOPIXEL2) + REPORT_NAME_DIGITAL(__LINE__, NEOPIXEL2_PIN) +#endif #if PIN_EXISTS(RGB_LED_R) REPORT_NAME_DIGITAL(__LINE__, RGB_LED_R_PIN) #endif @@ -838,6 +863,12 @@ #if PIN_EXISTS(SOL5) REPORT_NAME_DIGITAL(__LINE__, SOL5_PIN) #endif +#if PIN_EXISTS(SOL6) + REPORT_NAME_DIGITAL(__LINE__, SOL6_PIN) +#endif +#if PIN_EXISTS(SOL7) + REPORT_NAME_DIGITAL(__LINE__, SOL7_PIN) +#endif #if defined(SPARE_IO) && SPARE_IO >= 0 REPORT_NAME_DIGITAL(__LINE__, SPARE_IO) #endif @@ -988,6 +1019,9 @@ #if PIN_EXISTS(X_STOP) REPORT_NAME_DIGITAL(__LINE__, X_STOP_PIN) #endif +#if PIN_EXISTS(X2_CS) + REPORT_NAME_DIGITAL(__LINE__, X2_CS_PIN) +#endif #if PIN_EXISTS(X2_DIR) REPORT_NAME_DIGITAL(__LINE__, X2_DIR_PIN) #endif @@ -1048,6 +1082,9 @@ #if PIN_EXISTS(Y_STOP) REPORT_NAME_DIGITAL(__LINE__, Y_STOP_PIN) #endif +#if PIN_EXISTS(Y2_CS) + REPORT_NAME_DIGITAL(__LINE__, Y2_CS_PIN) +#endif #if PIN_EXISTS(Y2_DIR) REPORT_NAME_DIGITAL(__LINE__, Y2_DIR_PIN) #endif @@ -1351,6 +1388,24 @@ #if PIN_EXISTS(TOUCH_INT) REPORT_NAME_DIGITAL(__LINE__, TOUCH_INT_PIN) #endif +#if PIN_EXISTS(USB_CS) + REPORT_NAME_DIGITAL(__LINE__, USB_CS_PIN) +#endif +#if PIN_EXISTS(USB_INTR) + REPORT_NAME_DIGITAL(__LINE__, USB_INTR_PIN) +#endif +#if PIN_EXISTS(MMU2_RST) + REPORT_NAME_DIGITAL(__LINE__, MMU2_RST_PIN) +#endif +#if PIN_EXISTS(CALIBRATION) + REPORT_NAME_DIGITAL(__LINE__, CALIBRATION_PIN) +#endif #if PIN_EXISTS(SMART_EFFECTOR_MOD) REPORT_NAME_DIGITAL(__LINE__, SMART_EFFECTOR_MOD_PIN) #endif +#if PIN_EXISTS(CLOSED_LOOP_ENABLE) + REPORT_NAME_DIGITAL(__LINE__, CLOSED_LOOP_ENABLE_PIN) +#endif +#if PIN_EXISTS(CLOSED_LOOP_MOVE_COMPLETE) + REPORT_NAME_DIGITAL(__LINE__, CLOSED_LOOP_MOVE_COMPLETE_PIN) +#endif diff --git a/Marlin/src/pins/rambo/pins_MINIRAMBO.h b/Marlin/src/pins/rambo/pins_MINIRAMBO.h index 6aabf594ac..50aec546a6 100644 --- a/Marlin/src/pins/rambo/pins_MINIRAMBO.h +++ b/Marlin/src/pins/rambo/pins_MINIRAMBO.h @@ -26,7 +26,7 @@ */ #ifndef __AVR_ATmega2560__ - #error "Oops! Select 'RAMBo' in 'Tools > Board.'" + #error "Oops! Select 'RAMBo' in 'Tools > Board' or the Mega2560 environment in PlatformIO." #endif #if MB(MINIRAMBO_10A) diff --git a/Marlin/src/pins/ramps/pins_FYSETC_F6_13.h b/Marlin/src/pins/ramps/pins_FYSETC_F6_13.h index 475551ad6b..c67f8283b7 100644 --- a/Marlin/src/pins/ramps/pins_FYSETC_F6_13.h +++ b/Marlin/src/pins/ramps/pins_FYSETC_F6_13.h @@ -29,10 +29,6 @@ #error "Oops! Select 'FYSETC F6' in 'Tools > Board.'" #endif -#if ENABLED(SD_DETECT_INVERTED) - //#error "SD_DETECT_INVERTED must be disabled for the FYSETC_F6_13 board." -#endif - #ifndef BOARD_INFO_NAME #define BOARD_INFO_NAME "FYSETC F6 1.3" #endif diff --git a/Marlin/src/pins/ramps/pins_RAMPS.h b/Marlin/src/pins/ramps/pins_RAMPS.h index 82c19dd153..4ec882bcce 100644 --- a/Marlin/src/pins/ramps/pins_RAMPS.h +++ b/Marlin/src/pins/ramps/pins_RAMPS.h @@ -647,7 +647,7 @@ #define NEOPIXEL_PIN 25 #endif - #endif + #endif #elif ENABLED(MINIPANEL) @@ -685,14 +685,7 @@ #define BEEPER_PIN 33 // Buttons are directly attached to AUX-2 - #if ENABLED(REPRAPWORLD_KEYPAD) - #define SHIFT_OUT 40 - #define SHIFT_CLK 44 - #define SHIFT_LD 42 - #define BTN_EN1 64 - #define BTN_EN2 59 - #define BTN_ENC 63 - #elif ENABLED(PANEL_ONE) + #if ENABLED(PANEL_ONE) #define BTN_EN1 59 // AUX2 PIN 3 #define BTN_EN2 63 // AUX2 PIN 4 #define BTN_ENC 49 // AUX3 PIN 7 @@ -711,3 +704,18 @@ #endif // NEWPANEL #endif // HAS_SPI_LCD + +#if ENABLED(REPRAPWORLD_KEYPAD) + #define SHIFT_OUT 40 + #define SHIFT_CLK 44 + #define SHIFT_LD 42 + #ifndef BTN_EN1 + #define BTN_EN1 64 + #endif + #ifndef BTN_EN2 + #define BTN_EN2 59 + #endif + #ifndef BTN_ENC + #define BTN_ENC 63 + #endif +#endif diff --git a/Marlin/src/pins/sensitive_pins.h b/Marlin/src/pins/sensitive_pins.h index 807ee99e23..180bc8d6f6 100644 --- a/Marlin/src/pins/sensitive_pins.h +++ b/Marlin/src/pins/sensitive_pins.h @@ -278,9 +278,9 @@ #endif #define _E6_CS +#define _E6_MS1 #define _E6_MS2 #define _E6_MS3 -#define _E6_MS4 #if E_NEEDED(6) #if PIN_EXISTS(E6_CS) && AXIS_HAS_SPI(E6) @@ -302,9 +302,9 @@ #endif #define _E7_CS +#define _E7_MS1 +#define _E7_MS2 #define _E7_MS3 -#define _E7_MS4 -#define _E7_MS5 #if E_NEEDED(7) #if PIN_EXISTS(E7_CS) && AXIS_HAS_SPI(E7) diff --git a/Marlin/src/pins/stm32/pins_BTT_GTR_V1_0.h b/Marlin/src/pins/stm32/pins_BTT_GTR_V1_0.h index aa2152c84f..0500c5d953 100644 --- a/Marlin/src/pins/stm32/pins_BTT_GTR_V1_0.h +++ b/Marlin/src/pins/stm32/pins_BTT_GTR_V1_0.h @@ -237,8 +237,8 @@ #define TEMP_3_PIN PA3 // T4 <-> E3 #define TEMP_4_PIN PF9 // T5 <-> E4 #define TEMP_5_PIN PF10 // T6 <-> E5 -//#define TEMP_6_PIN PF7 // T7 <-> E6 -//#define TEMP_7_PIN PF5 // T8 <-> E7 +#define TEMP_6_PIN PF7 // T7 <-> E6 +#define TEMP_7_PIN PF5 // T8 <-> E7 #define TEMP_BED_PIN PC0 // T0 <-> Bed @@ -266,8 +266,8 @@ #define HEATER_3_PIN PD15 // Heater3 #define HEATER_4_PIN PD13 // Heater4 #define HEATER_5_PIN PD12 // Heater5 -//#define HEATER_6_PIN PE13 // Heater6 -//#define HEATER_7_PIN PI6 // Heater7 +#define HEATER_6_PIN PE13 // Heater6 +#define HEATER_7_PIN PI6 // Heater7 #define HEATER_BED_PIN PA2 // Hotbed diff --git a/Marlin/src/pins/stm32/pins_BTT_SKR_PRO_V1_1.h b/Marlin/src/pins/stm32/pins_BTT_SKR_PRO_V1_1.h index 8222bbe143..bdee26a51a 100644 --- a/Marlin/src/pins/stm32/pins_BTT_SKR_PRO_V1_1.h +++ b/Marlin/src/pins/stm32/pins_BTT_SKR_PRO_V1_1.h @@ -190,7 +190,7 @@ // Onboard SD card // NOT compatible with LCD // -#if SDCARD_CONNECTION == ONBOARD && !defined(HAS_SPI_LCD) +#if SDCARD_CONNECTION == ONBOARD && !HAS_SPI_LCD #define SOFTWARE_SPI // Use soft SPI for onboard SD #define SDSS PA4 #define SCK_PIN PA5 diff --git a/Marlin/src/pins/stm32/pins_FYSETC_S6.h b/Marlin/src/pins/stm32/pins_FYSETC_S6.h index 16f176a376..5bda7b1c97 100644 --- a/Marlin/src/pins/stm32/pins_FYSETC_S6.h +++ b/Marlin/src/pins/stm32/pins_FYSETC_S6.h @@ -41,6 +41,9 @@ // EEPROM Emulation // #define FLASH_EEPROM_EMULATION +#if ENABLED(FLASH_EEPROM_EMULATION) + #define FLASH_EEPROM_LEVELING +#endif //#define SRAM_EEPROM_EMULATION //#define I2C_EEPROM #ifdef I2C_EEPROM @@ -65,6 +68,7 @@ // // Filament Sensor +// share with X_MAX_PIN // #ifndef FIL_RUNOUT_PIN #define FIL_RUNOUT_PIN PA1 diff --git a/Marlin/src/sd/Sd2Card.cpp b/Marlin/src/sd/Sd2Card.cpp index f82fab1b50..ba233d36f6 100644 --- a/Marlin/src/sd/Sd2Card.cpp +++ b/Marlin/src/sd/Sd2Card.cpp @@ -74,7 +74,7 @@ #else static uint8_t CRC7(const uint8_t* data, uint8_t n) { uint8_t crc = 0; - for (uint8_t i = 0; i < n; i++) { + LOOP_L_N(i, n) { uint8_t d = data[i]; d ^= crc << 1; if (d & 0x80) d ^= 9; @@ -106,7 +106,7 @@ uint8_t Sd2Card::cardCommand(const uint8_t cmd, const uint32_t arg) { d[5] = CRC7(d, 5); // Send message - for (uint8_t k = 0; k < 6; k++) spiSend(d[k]); + LOOP_L_N(k, 6) spiSend(d[k]); #else // Send command @@ -246,7 +246,7 @@ bool Sd2Card::init(const uint8_t sckRateID, const pin_t chipSelectPin) { spiInit(spiRate_); // Must supply min of 74 clock cycles with CS high. - for (uint8_t i = 0; i < 10; i++) spiSend(0xFF); + LOOP_L_N(i, 10) spiSend(0xFF); watchdog_refresh(); // In case init takes too long @@ -272,7 +272,7 @@ bool Sd2Card::init(const uint8_t sckRateID, const pin_t chipSelectPin) { } // Get the last byte of r7 response - for (uint8_t i = 0; i < 4; i++) status_ = spiRec(); + LOOP_L_N(i, 4) status_ = spiRec(); if (status_ == 0xAA) { type(SD_CARD_TYPE_SD2); break; @@ -303,7 +303,7 @@ bool Sd2Card::init(const uint8_t sckRateID, const pin_t chipSelectPin) { } if ((spiRec() & 0xC0) == 0xC0) type(SD_CARD_TYPE_SDHC); // Discard rest of ocr - contains allowed voltage range - for (uint8_t i = 0; i < 3; i++) spiRec(); + LOOP_L_N(i, 3) spiRec(); } chipDeselect(); diff --git a/Marlin/src/sd/SdBaseFile.cpp b/Marlin/src/sd/SdBaseFile.cpp index cdb1072cbe..27c191a6a6 100644 --- a/Marlin/src/sd/SdBaseFile.cpp +++ b/Marlin/src/sd/SdBaseFile.cpp @@ -204,7 +204,7 @@ bool SdBaseFile::dirEntry(dir_t* dir) { */ void SdBaseFile::dirName(const dir_t& dir, char* name) { uint8_t j = 0; - for (uint8_t i = 0; i < 11; i++) { + LOOP_L_N(i, 11) { if (dir.name[i] == ' ')continue; if (i == 8) name[j++] = '.'; name[j++] = dir.name[i]; @@ -345,10 +345,10 @@ int8_t SdBaseFile::lsPrintNext(uint8_t flags, uint8_t indent) { && DIR_IS_FILE_OR_SUBDIR(&dir)) break; } // indent for dir level - for (uint8_t i = 0; i < indent; i++) SERIAL_CHAR(' '); + LOOP_L_N(i, indent) SERIAL_CHAR(' '); // print name - for (uint8_t i = 0; i < 11; i++) { + LOOP_L_N(i, 11) { if (dir.name[i] == ' ')continue; if (i == 8) { SERIAL_CHAR('.'); @@ -478,7 +478,7 @@ bool SdBaseFile::mkdir(SdBaseFile* parent, const uint8_t dname[11]) { // make entry for '.' memcpy(&d, p, sizeof(d)); d.name[0] = '.'; - for (uint8_t i = 1; i < 11; i++) d.name[i] = ' '; + LOOP_S_L_N(i, 1, 11) d.name[i] = ' '; // cache block for '.' and '..' block = vol_->clusterStartBlock(firstCluster_); @@ -1088,7 +1088,7 @@ int8_t SdBaseFile::readDir(dir_t* dir, char* longFilename) { if (WITHIN(seq, 1, MAX_VFAT_ENTRIES)) { // TODO: Store the filename checksum to verify if a long-filename-unaware system modified the file table. n = (seq - 1) * (FILENAME_LENGTH); - for (uint8_t i = 0; i < FILENAME_LENGTH; i++) + LOOP_L_N(i, FILENAME_LENGTH) longFilename[n + i] = (i < 5) ? VFAT->name1[i] : (i < 11) ? VFAT->name2[i - 5] : VFAT->name3[i - 11]; // If this VFAT entry is the last one, add a NUL terminator at the end of the string if (VFAT->sequenceNumber & 0x40) longFilename[n + FILENAME_LENGTH] = '\0'; diff --git a/Marlin/src/sd/cardreader.cpp b/Marlin/src/sd/cardreader.cpp index b2b0d90e96..aadd355afd 100644 --- a/Marlin/src/sd/cardreader.cpp +++ b/Marlin/src/sd/cardreader.cpp @@ -35,11 +35,11 @@ #include "../module/configuration_store.h" #if ENABLED(EMERGENCY_PARSER) - #include "../feature/emergency_parser.h" + #include "../feature/e_parser.h" #endif #if ENABLED(POWER_LOSS_RECOVERY) - #include "../feature/power_loss_recovery.h" + #include "../feature/powerloss.h" #endif #if ENABLED(ADVANCED_PAUSE_FEATURE) @@ -143,7 +143,7 @@ CardReader::CardReader() { // char *createFilename(char * const buffer, const dir_t &p) { char *pos = buffer; - for (uint8_t i = 0; i < 11; i++) { + LOOP_L_N(i, 11) { if (p.name[i] == ' ') continue; if (i == 8) *pos++ = '.'; *pos++ = p.name[i]; @@ -370,7 +370,7 @@ void CardReader::mount() { else { flag.mounted = true; SERIAL_ECHO_MSG(STR_SD_CARD_OK); - #if ENABLED(EEPROM_SETTINGS) && NONE(FLASH_EEPROM_EMULATION, SPI_EEPROM, I2C_EEPROM) + #if ENABLED(SDCARD_EEPROM_EMULATION) settings.first_load(); #endif } @@ -435,7 +435,7 @@ void CardReader::getAbsFilename(char *dst) { if (cnt < MAXPATHNAMELENGTH) { *dst = '/'; dst++; cnt++; } }; - for (uint8_t i = 0; i < workDirDepth; i++) // Loop down to current work dir + LOOP_L_N(i, workDirDepth) // Loop down to current work dir appendAtom(workDirParents[i]); if (cnt < MAXPATHNAMELENGTH - (FILENAME_LENGTH) - 1) { // Leave room for filename and nul @@ -451,10 +451,12 @@ void openFailed(const char * const fname) { void announceOpen(const uint8_t doing, const char * const path) { if (doing) { + PORT_REDIRECT(SERIAL_BOTH); SERIAL_ECHO_START(); SERIAL_ECHOPGM("Now "); serialprintPGM(doing == 1 ? PSTR("doing") : PSTR("fresh")); SERIAL_ECHOLNPAIR(" file: ", path); + PORT_RESTORE(); } } @@ -511,8 +513,11 @@ void CardReader::openFileRead(char * const path, const uint8_t subcall_type/*=0* if (file.open(curDir, fname, O_READ)) { filesize = file.fileSize(); sdpos = 0; + + PORT_REDIRECT(SERIAL_BOTH); SERIAL_ECHOLNPAIR(STR_SD_FILE_OPENED, fname, STR_SD_SIZE, filesize); SERIAL_ECHOLNPGM(STR_SD_FILE_SELECTED); + PORT_RESTORE(); selectFileByName(fname); ui.set_status(longFilename[0] ? longFilename : fname); @@ -617,7 +622,7 @@ void CardReader::checkautostart() { if (autostart_index < 0 || flag.sdprinting) return; if (!isMounted()) mount(); - #if ENABLED(EEPROM_SETTINGS) && NONE(FLASH_EEPROM_EMULATION, SPI_EEPROM, I2C_EEPROM) + #if ENABLED(SDCARD_EEPROM_EMULATION) else settings.first_load(); #endif @@ -1041,7 +1046,7 @@ void CardReader::cdroot() { #if ENABLED(SDSORT_DYNAMIC_RAM) delete sort_order; #if ENABLED(SDSORT_CACHE_NAMES) - for (uint8_t i = 0; i < sort_count; ++i) { + LOOP_L_N(i, sort_count) { free(sortshort[i]); // strdup free(sortnames[i]); // strdup } diff --git a/Marlin/src/sd/cardreader.h b/Marlin/src/sd/cardreader.h index be700401ee..749ece01d3 100644 --- a/Marlin/src/sd/cardreader.h +++ b/Marlin/src/sd/cardreader.h @@ -276,11 +276,7 @@ private: #if ENABLED(USB_FLASH_DRIVE_SUPPORT) #define IS_SD_INSERTED() Sd2Card::isInserted() #elif PIN_EXISTS(SD_DETECT) - #if ENABLED(SD_DETECT_INVERTED) - #define IS_SD_INSERTED() READ(SD_DETECT_PIN) - #else - #define IS_SD_INSERTED() !READ(SD_DETECT_PIN) - #endif + #define IS_SD_INSERTED() (READ(SD_DETECT_PIN) == SD_DETECT_STATE) #else // No card detect line? Assume the card is inserted. #define IS_SD_INSERTED() true diff --git a/buildroot/share/PlatformIO/variants/BIGTREE_BTT002/PeripheralPins.c b/buildroot/share/PlatformIO/variants/BIGTREE_BTT002/PeripheralPins.c index 3f639f092c..7f5ca78356 100644 --- a/buildroot/share/PlatformIO/variants/BIGTREE_BTT002/PeripheralPins.c +++ b/buildroot/share/PlatformIO/variants/BIGTREE_BTT002/PeripheralPins.c @@ -323,7 +323,7 @@ const PinMap PinMap_USB_OTG_HS[] = { /* {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 #else - #error "USB in HS mode isn't supported by the board" + #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 @@ -334,7 +334,8 @@ const PinMap PinMap_USB_OTG_HS[] = { /* {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 - #endif /* USE_USB_HS_IN_FS */ + #endif // USE_USB_HS_IN_FS + */ {NC, NP, 0} }; #endif diff --git a/buildroot/share/PlatformIO/variants/BIGTREE_SKR_PRO_1v1/PeripheralPins.c b/buildroot/share/PlatformIO/variants/BIGTREE_SKR_PRO_1v1/PeripheralPins.c index fd1f296459..a772f64fb7 100644 --- a/buildroot/share/PlatformIO/variants/BIGTREE_SKR_PRO_1v1/PeripheralPins.c +++ b/buildroot/share/PlatformIO/variants/BIGTREE_SKR_PRO_1v1/PeripheralPins.c @@ -355,7 +355,7 @@ const PinMap PinMap_USB_OTG_HS[] = { /* {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 #else - #error "USB in HS mode isn't supported by the board" + #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 @@ -366,7 +366,8 @@ const PinMap PinMap_USB_OTG_HS[] = { /* {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 - #endif /* USE_USB_HS_IN_FS */ + #endif // USE_USB_HS_IN_FS + */ {NC, NP, 0} }; #endif diff --git a/buildroot/share/PlatformIO/variants/FYSETC_S6/variant.h b/buildroot/share/PlatformIO/variants/FYSETC_S6/variant.h index be04ef6b86..de34697fb3 100644 --- a/buildroot/share/PlatformIO/variants/FYSETC_S6/variant.h +++ b/buildroot/share/PlatformIO/variants/FYSETC_S6/variant.h @@ -115,7 +115,7 @@ extern "C" { #define NUM_ANALOG_FIRST 80 // PWM resolution -#define PWM_RESOLUTION 8 +#define PWM_RESOLUTION 12 #define PWM_FREQUENCY 20000 // >= 20 Khz => inaudible noise for fans #define PWM_MAX_DUTY_CYCLE 255 diff --git a/buildroot/share/git/mftest b/buildroot/share/git/mftest index 0b2d9ef78f..62186a5f82 100755 --- a/buildroot/share/git/mftest +++ b/buildroot/share/git/mftest @@ -34,9 +34,9 @@ case $TESTENV in lin*) TESTENV='linux_native' ;; lpc?(8)) TESTENV='LPC1768' ;; lpc9) TESTENV='LPC1769' ;; - m128) TESTENV='megaatmega1280' ;; - m256) TESTENV='megaatmega2560' ;; - mega) TESTENV='megaatmega2560' ;; + m128) TESTENV='mega1280' ;; + m256) TESTENV='mega2560' ;; + mega) TESTENV='mega2560' ;; stm) TESTENV='STM32F103RE' ;; f1) TESTENV='STM32F103RE' ;; f4) TESTENV='STM32F4' ;; @@ -215,6 +215,9 @@ echo "$OUT" | { done } +# Make clear it's a TEST +opt_set CUSTOM_MACHINE_NAME "\"$TESTENV-tests ($CHOICE)\"" + # Get a -y parameter the lazy way [[ "$2" == "-y" || "$3" == "-y" ]] && BUILD_YES='Y' diff --git a/buildroot/share/scripts/MarlinMesh.scad b/buildroot/share/scripts/MarlinMesh.scad index 7616ded699..6d78bb9649 100644 --- a/buildroot/share/scripts/MarlinMesh.scad +++ b/buildroot/share/scripts/MarlinMesh.scad @@ -10,17 +10,13 @@ * * \**************************************/ -//$t = 0.15; // comment out during animation +$t = 0.15; // comment out during animation! +X = 0; Y = 1; +L = 0; R = 1; F = 2; B = 3; // -// Mesh info and points +// Sample Mesh - Replace with your own // - -mesh_width = 200; // X Size in mm of the probed area -mesh_height = 200; // Y Size... -zprobe_offset = 0; // Added to the points -NAN = 0; // Z to use for un-measured points - measured_z = [ [ -1.20, -1.13, -1.09, -1.03, -1.19 ], [ -1.16, -1.25, -1.27, -1.25, -1.08 ], @@ -29,6 +25,28 @@ measured_z = [ [ -1.13, -0.99, -1.03, -1.06, -1.32 ] ]; +// +// An offset to add to all points in the mesh +// +zadjust = 0; + +// +// Mesh characteristics +// +bed_size = [ 200, 200 ]; + +mesh_inset = [ 10, 10, 10, 10 ]; // L, F, R, B + +mesh_bounds = [ + [ mesh_inset[L], mesh_inset[F] ], + [ bed_size[X] - mesh_inset[R], bed_size[Y] - mesh_inset[B] ] +]; + +mesh_size = mesh_bounds[1] - mesh_bounds[0]; + + // NOTE: Marlin meshes already subtract the probe offset +NAN = 0; // Z to use for un-measured points + // // Geometry // @@ -45,6 +63,7 @@ alternation = 2; // direction change modulus (try it) show_plane = true; show_labels = true; +show_coords = true; arrow_length = 5; label_font_lg = "Arial"; @@ -62,8 +81,8 @@ mean_value = (big_z + lil_z) / 2.0; mesh_points_y = len(measured_z); mesh_points_x = len(measured_z[0]); -xspace = mesh_width / (mesh_points_x - 1); -yspace = mesh_height / (mesh_points_y - 1); +xspace = mesh_size[X] / (mesh_points_x - 1); +yspace = mesh_size[Y] / (mesh_points_y - 1); // At $t=0 and $t=1 scale will be 100% z_scale_factor = min_z_scale + (($t > 0.5) ? 1.0 - $t : $t) * (max_z_scale - min_z_scale) * 2; @@ -72,6 +91,8 @@ z_scale_factor = min_z_scale + (($t > 0.5) ? 1.0 - $t : $t) * (max_z_scale - min // Min and max recursive functions for 1D and 2D arrays // Return the smallest or largest value in the array // +function some_1D(b,i) = (i - - + @@ -57,24 +57,24 @@ monitor_speed = 250000 # # ATmega2560 # -[env:megaatmega2560] +[env:mega2560] platform = atmelavr board = megaatmega2560 board_build.f_cpu = 16000000L lib_deps = ${common.lib_deps} TMC26XStepper=https://github.com/trinamic/TMC26XStepper/archive/master.zip -src_filter = ${common.default_src_filter} + +src_filter = ${common.default_src_filter} + # # ATmega1280 # -[env:megaatmega1280] +[env:mega1280] platform = atmelavr board = megaatmega1280 board_build.f_cpu = 16000000L lib_deps = ${common.lib_deps} TMC26XStepper=https://github.com/trinamic/TMC26XStepper/archive/master.zip -src_filter = ${common.default_src_filter} + +src_filter = ${common.default_src_filter} + # # RAMBo @@ -85,7 +85,7 @@ board = reprap_rambo board_build.f_cpu = 16000000L lib_deps = ${common.lib_deps} TMC26XStepper=https://github.com/trinamic/TMC26XStepper/archive/master.zip -src_filter = ${common.default_src_filter} + +src_filter = ${common.default_src_filter} + # # FYSETC F6 V1.3 @@ -96,7 +96,7 @@ board = fysetc_f6_13 board_build.f_cpu = 16000000L lib_deps = ${common.lib_deps} TMC26XStepper=https://github.com/trinamic/TMC26XStepper/archive/master.zip -src_filter = ${common.default_src_filter} + +src_filter = ${common.default_src_filter} + # # FYSETC F6 V1.4 @@ -107,27 +107,27 @@ board = fysetc_f6_14 board_build.f_cpu = 16000000L lib_deps = ${common.lib_deps} TMC26XStepper=https://github.com/trinamic/TMC26XStepper/archive/master.zip -src_filter = ${common.default_src_filter} + +src_filter = ${common.default_src_filter} + # # Sanguinololu (ATmega644p) # -[env:sanguino_atmega644p] +[env:sanguino644p] platform = atmelavr board = sanguino_atmega644p lib_deps = ${common.lib_deps} TMC26XStepper=https://github.com/trinamic/TMC26XStepper/archive/master.zip -src_filter = ${common.default_src_filter} + +src_filter = ${common.default_src_filter} + # # Sanguinololu (ATmega1284p) # -[env:sanguino_atmega1284p] +[env:sanguino1284p] platform = atmelavr board = sanguino_atmega1284p lib_deps = ${common.lib_deps} TMC26XStepper=https://github.com/trinamic/TMC26XStepper/archive/master.zip -src_filter = ${common.default_src_filter} + +src_filter = ${common.default_src_filter} + # # Melzi and clones (ATmega1284p) @@ -137,7 +137,7 @@ platform = atmelavr board = sanguino_atmega1284p lib_deps = ${common.lib_deps} TMC26XStepper=https://github.com/trinamic/TMC26XStepper/archive/master.zip -src_filter = ${common.default_src_filter} + +src_filter = ${common.default_src_filter} + lib_ignore = TMCStepper upload_speed = 57600 @@ -149,7 +149,7 @@ platform = atmelavr board = sanguino_atmega1284p lib_deps = ${common.lib_deps} TMC26XStepper=https://github.com/trinamic/TMC26XStepper/archive/master.zip -src_filter = ${common.default_src_filter} + +src_filter = ${common.default_src_filter} + lib_ignore = TMCStepper upload_speed = 115200 @@ -166,7 +166,7 @@ board = at90usb1286 lib_deps = ${common.lib_deps} TMC26XStepper=https://github.com/trinamic/TMC26XStepper/archive/master.zip lib_ignore = TMCStepper -src_filter = ${common.default_src_filter} + +src_filter = ${common.default_src_filter} + # # AT90USB1286 boards using DFU bootloader @@ -179,7 +179,7 @@ platform = teensy board = at90usb1286 lib_deps = ${common.lib_deps} lib_ignore = TMCStepper -src_filter = ${common.default_src_filter} + +src_filter = ${common.default_src_filter} + # # Due (Atmel SAM3X8E ARM Cortex-M3) @@ -190,18 +190,18 @@ src_filter = ${common.default_src_filter} + [env:DUE] platform = atmelsam board = due -src_filter = ${common.default_src_filter} + +src_filter = ${common.default_src_filter} + [env:DUE_USB] platform = atmelsam board = dueUSB -src_filter = ${common.default_src_filter} + +src_filter = ${common.default_src_filter} + [env:DUE_debug] # Used when WATCHDOG_RESET_MANUAL is enabled platform = atmelsam board = due -src_filter = ${common.default_src_filter} + +src_filter = ${common.default_src_filter} + build_flags = ${common.build_flags} -funwind-tables -mpoke-function-name @@ -212,14 +212,14 @@ build_flags = ${common.build_flags} [env:LPC1768] platform = https://github.com/p3p/pio-nxplpc-arduino-lpc176x/archive/0.1.2.zip board = nxp_lpc1768 -build_flags = -DU8G_HAL_LINKS -IMarlin/src/HAL/HAL_LPC1768/include -IMarlin/src/HAL/HAL_LPC1768/u8g ${common.build_flags} +build_flags = -DU8G_HAL_LINKS -IMarlin/src/HAL/LPC1768/include -IMarlin/src/HAL/LPC1768/u8g ${common.build_flags} # debug options for backtrace # -funwind-tables # -mpoke-function-name lib_ldf_mode = off lib_compat_mode = strict -extra_scripts = Marlin/src/HAL/HAL_LPC1768/upload_extra_script.py -src_filter = ${common.default_src_filter} + +extra_scripts = Marlin/src/HAL/LPC1768/upload_extra_script.py +src_filter = ${common.default_src_filter} + lib_deps = Servo LiquidCrystal U8glib-HAL=https://github.com/MarlinFirmware/U8glib-HAL/archive/bugfix.zip @@ -230,14 +230,14 @@ lib_deps = Servo [env:LPC1769] platform = https://github.com/p3p/pio-nxplpc-arduino-lpc176x/archive/0.1.2.zip board = nxp_lpc1769 -build_flags = -DU8G_HAL_LINKS -IMarlin/src/HAL/HAL_LPC1768/include -IMarlin/src/HAL/HAL_LPC1768/u8g ${common.build_flags} +build_flags = -DU8G_HAL_LINKS -IMarlin/src/HAL/LPC1768/include -IMarlin/src/HAL/LPC1768/u8g ${common.build_flags} # debug options for backtrace # -funwind-tables # -mpoke-function-name lib_ldf_mode = off lib_compat_mode = strict -extra_scripts = Marlin/src/HAL/HAL_LPC1768/upload_extra_script.py -src_filter = ${common.default_src_filter} + +extra_scripts = Marlin/src/HAL/LPC1768/upload_extra_script.py +src_filter = ${common.default_src_filter} + lib_deps = Servo LiquidCrystal U8glib-HAL=https://github.com/MarlinFirmware/U8glib-HAL/archive/bugfix.zip @@ -252,10 +252,10 @@ lib_deps = Servo platform = ststm32 board = genericSTM32F103RC platform_packages = tool-stm32duino -build_flags = !python Marlin/src/HAL/HAL_STM32F1/build_flags.py +build_flags = !python Marlin/src/HAL/STM32F1/build_flags.py ${common.build_flags} -std=gnu++14 build_unflags = -std=gnu++11 -src_filter = ${common.default_src_filter} + +src_filter = ${common.default_src_filter} + lib_deps = ${common.lib_deps} SoftwareSerialM=https://github.com/FYSETC/SoftwareSerialM/archive/master.zip lib_ignore = Adafruit NeoPixel, SPI @@ -269,11 +269,11 @@ platform = ststm32 board = genericSTM32F103RC #board_build.core = maple platform_packages = tool-stm32duino -build_flags = !python Marlin/src/HAL/HAL_STM32F1/build_flags.py +build_flags = !python Marlin/src/HAL/STM32F1/build_flags.py ${common.build_flags} -std=gnu++14 -DDEBUG_LEVEL=0 -DHAVE_SW_SERIAL build_unflags = -std=gnu++11 extra_scripts = buildroot/share/PlatformIO/scripts/STM32F103RC_fysetc.py -src_filter = ${common.default_src_filter} + +src_filter = ${common.default_src_filter} + lib_deps = ${common.lib_deps} SoftwareSerialM=https://github.com/FYSETC/SoftwareSerialM/archive/master.zip lib_ignore = Adafruit NeoPixel, SPI @@ -284,65 +284,65 @@ upload_protocol = serial # # BigTree SKR Mini V1.1 / SKR mini E3 / SKR E3 DIP (STM32F103RCT6 ARM Cortex-M3) # -# STM32F103RC_bigtree ............. RCT6 with 256K -# STM32F103RC_bigtree_USB ......... RCT6 with 256K (USB mass storage) -# STM32F103RC_bigtree_512K ........ RCT6 with 512K -# STM32F103RC_bigtree_512K_USB .... RCT6 with 512K (USB mass storage) +# STM32F103RC_btt ............. RCT6 with 256K +# STM32F103RC_btt_USB ......... RCT6 with 256K (USB mass storage) +# STM32F103RC_btt_512K ........ RCT6 with 512K +# STM32F103RC_btt_512K_USB .... RCT6 with 512K (USB mass storage) # -[env:STM32F103RC_bigtree] +[env:STM32F103RC_btt] platform = ststm32 board = genericSTM32F103RC platform_packages = tool-stm32duino -build_flags = !python Marlin/src/HAL/HAL_STM32F1/build_flags.py +build_flags = !python Marlin/src/HAL/STM32F1/build_flags.py ${common.build_flags} -DDEBUG_LEVEL=0 -std=gnu++14 -DHAVE_SW_SERIAL -DSS_TIMER=4 build_unflags = -std=gnu++11 extra_scripts = buildroot/share/PlatformIO/scripts/STM32F103RC_SKR_MINI.py -src_filter = ${common.default_src_filter} + +src_filter = ${common.default_src_filter} + lib_deps = ${common.lib_deps} SoftwareSerialM=https://github.com/FYSETC/SoftwareSerialM/archive/master.zip lib_ignore = Adafruit NeoPixel, SPI monitor_speed = 115200 -[env:STM32F103RC_bigtree_USB] +[env:STM32F103RC_btt_USB] platform = ststm32 board = genericSTM32F103RC platform_packages = tool-stm32duino -build_flags = !python Marlin/src/HAL/HAL_STM32F1/build_flags.py +build_flags = !python Marlin/src/HAL/STM32F1/build_flags.py ${common.build_flags} -DDEBUG_LEVEL=0 -std=gnu++14 -DHAVE_SW_SERIAL -DSS_TIMER=4 -DUSE_USB_COMPOSITE build_unflags = -std=gnu++11 extra_scripts = buildroot/share/PlatformIO/scripts/STM32F103RC_SKR_MINI.py -src_filter = ${common.default_src_filter} + +src_filter = ${common.default_src_filter} + lib_deps = ${common.lib_deps} SoftwareSerialM=https://github.com/FYSETC/SoftwareSerialM/archive/master.zip lib_ignore = Adafruit NeoPixel, SPI monitor_speed = 115200 -[env:STM32F103RC_bigtree_512K] +[env:STM32F103RC_btt_512K] platform = ststm32 board = genericSTM32F103RC board_upload.maximum_size=524288 platform_packages = tool-stm32duino -build_flags = !python Marlin/src/HAL/HAL_STM32F1/build_flags.py +build_flags = !python Marlin/src/HAL/STM32F1/build_flags.py ${common.build_flags} -DDEBUG_LEVEL=0 -std=gnu++14 -DHAVE_SW_SERIAL -DSS_TIMER=4 -DSTM32_FLASH_SIZE=512 build_unflags = -std=gnu++11 extra_scripts = buildroot/share/PlatformIO/scripts/STM32F103RC_SKR_MINI.py -src_filter = ${common.default_src_filter} + +src_filter = ${common.default_src_filter} + lib_deps = ${common.lib_deps} SoftwareSerialM=https://github.com/FYSETC/SoftwareSerialM/archive/master.zip lib_ignore = Adafruit NeoPixel, SPI monitor_speed = 115200 -[env:STM32F103RC_bigtree_512K_USB] +[env:STM32F103RC_btt_512K_USB] platform = ststm32 board = genericSTM32F103RC board_upload.maximum_size=524288 platform_packages = tool-stm32duino -build_flags = !python Marlin/src/HAL/HAL_STM32F1/build_flags.py +build_flags = !python Marlin/src/HAL/STM32F1/build_flags.py ${common.build_flags} -DDEBUG_LEVEL=0 -std=gnu++14 -DHAVE_SW_SERIAL -DSS_TIMER=4 -DSTM32_FLASH_SIZE=512 -DUSE_USB_COMPOSITE build_unflags = -std=gnu++11 extra_scripts = buildroot/share/PlatformIO/scripts/STM32F103RC_SKR_MINI.py -src_filter = ${common.default_src_filter} + +src_filter = ${common.default_src_filter} + lib_deps = ${common.lib_deps} SoftwareSerialM=https://github.com/FYSETC/SoftwareSerialM/archive/master.zip lib_ignore = Adafruit NeoPixel, SPI @@ -355,28 +355,28 @@ monitor_speed = 115200 platform = ststm32 board = genericSTM32F103RE platform_packages = tool-stm32duino -build_flags = !python Marlin/src/HAL/HAL_STM32F1/build_flags.py +build_flags = !python Marlin/src/HAL/STM32F1/build_flags.py ${common.build_flags} -std=gnu++14 build_unflags = -std=gnu++11 -src_filter = ${common.default_src_filter} + +src_filter = ${common.default_src_filter} + lib_deps = ${common.lib_deps} SoftwareSerialM=https://github.com/FYSETC/SoftwareSerialM/archive/master.zip lib_ignore = Adafruit NeoPixel, SPI monitor_speed = 115200 # -# STM32F103RE_bigtree ............. RET6 -# STM32F103RE_bigtree_USB ......... RET6 (USB mass storage) +# STM32F103RE_btt ............. RET6 +# STM32F103RE_btt_USB ......... RET6 (USB mass storage) # -[env:STM32F103RE_bigtree] +[env:STM32F103RE_btt] platform = ststm32 board = genericSTM32F103RE platform_packages = tool-stm32duino -build_flags = !python Marlin/src/HAL/HAL_STM32F1/build_flags.py +build_flags = !python Marlin/src/HAL/STM32F1/build_flags.py ${common.build_flags} -DDEBUG_LEVEL=0 -std=gnu++14 -DHAVE_SW_SERIAL -DSS_TIMER=4 build_unflags = -std=gnu++11 extra_scripts = buildroot/share/PlatformIO/scripts/STM32F103RE_SKR_E3_DIP.py -src_filter = ${common.default_src_filter} + +src_filter = ${common.default_src_filter} + lib_deps = ${common.lib_deps} SoftwareSerialM=https://github.com/FYSETC/SoftwareSerialM/archive/master.zip lib_ignore = Adafruit NeoPixel, SPI @@ -384,15 +384,15 @@ debug_tool = stlink upload_protocol = stlink monitor_speed = 115200 -[env:STM32F103RE_bigtree_USB] +[env:STM32F103RE_btt_USB] platform = ststm32 board = genericSTM32F103RE platform_packages = tool-stm32duino -build_flags = !python Marlin/src/HAL/HAL_STM32F1/build_flags.py +build_flags = !python Marlin/src/HAL/STM32F1/build_flags.py ${common.build_flags} -DDEBUG_LEVEL=0 -std=gnu++14 -DHAVE_SW_SERIAL -DSS_TIMER=4 -DUSE_USB_COMPOSITE build_unflags = -std=gnu++11 extra_scripts = buildroot/share/PlatformIO/scripts/STM32F103RE_SKR_E3_DIP.py -src_filter = ${common.default_src_filter} + +src_filter = ${common.default_src_filter} + lib_deps = ${common.lib_deps} SoftwareSerialM=https://github.com/FYSETC/SoftwareSerialM/archive/master.zip lib_ignore = Adafruit NeoPixel, SPI @@ -408,7 +408,7 @@ platform = ststm32 board = disco_f407vg build_flags = ${common.build_flags} -DUSE_STM32GENERIC -DSTM32GENERIC -DSTM32F4 -DMENU_USB_SERIAL -DMENU_SERIAL=SerialUSB -DHAL_IWDG_MODULE_ENABLED lib_ignore = Adafruit NeoPixel, TMCStepper -src_filter = ${common.default_src_filter} + - +src_filter = ${common.default_src_filter} + - # # STM32F7 with STM32GENERIC @@ -418,7 +418,7 @@ platform = ststm32 board = remram_v1 build_flags = ${common.build_flags} -DUSE_STM32GENERIC -DSTM32GENERIC -DSTM32F7 -DMENU_USB_SERIAL -DMENU_SERIAL=SerialUSB -DHAL_IWDG_MODULE_ENABLED lib_ignore = Adafruit NeoPixel, TMCStepper -src_filter = ${common.default_src_filter} + - +src_filter = ${common.default_src_filter} + - # # ARMED (STM32) @@ -429,9 +429,9 @@ board = armed_v1 build_flags = ${common.build_flags} -DUSBCON -DUSBD_VID=0x0483 '-DUSB_MANUFACTURER="Unknown"' '-DUSB_PRODUCT="ARMED_V1"' -DUSBD_USE_CDC -O2 -ffreestanding -fsigned-char -fno-move-loop-invariants -fno-strict-aliasing -std=gnu11 -std=gnu++11 - -IMarlin/src/HAL/HAL_STM32 + -IMarlin/src/HAL/STM32 lib_ignore = Adafruit NeoPixel, SoftwareSerial -src_filter = ${common.default_src_filter} + +src_filter = ${common.default_src_filter} + # # Geeetech GTM32 (STM32F103VET6) @@ -439,12 +439,12 @@ src_filter = ${common.default_src_filter} + [env:STM32F103VE_GTM32] platform = ststm32 board = genericSTM32F103VE -build_flags = !python Marlin/src/HAL/HAL_STM32F1/build_flags.py +build_flags = !python Marlin/src/HAL/STM32F1/build_flags.py ${common.build_flags} -DDEBUG_LEVEL=DEBUG_NONE -std=gnu++14 -MMD -ffunction-sections -fdata-sections -nostdlib -DBOARD_generic_stm32f103v -DARDUINO_GENERIC_STM32F103V -DARDUINO_ARCH_STM32F1 -DCONFIG_MAPLE_MINI_NO_DISABLE_DEBUG=1 -DVECT_TAB_ADDR=0x8000000 -DERROR_LED_PORT=GPIOE -DERROR_LED_PIN=6 build_unflags = -std=gnu++11 -src_filter = ${common.default_src_filter} + +src_filter = ${common.default_src_filter} + lib_ignore = Adafruit NeoPixel, SPI upload_protocol = serial @@ -454,12 +454,12 @@ upload_protocol = serial [env:STM32F103VE_longer] platform = ststm32 board = genericSTM32F103VE -build_flags = !python Marlin/src/HAL/HAL_STM32F1/build_flags.py +build_flags = !python Marlin/src/HAL/STM32F1/build_flags.py ${common.build_flags} -std=gnu++14 -USERIAL_USB -DSTM32F1xx -DU20 -DTS_V12 build_unflags = -std=gnu++11 -DCONFIG_MAPLE_MINI_NO_DISABLE_DEBUG=1 -DERROR_LED_PORT=GPIOE -DERROR_LED_PIN=6 extra_scripts = buildroot/share/PlatformIO/scripts/STM32F103VE_longer.py -src_filter = ${common.default_src_filter} + +src_filter = ${common.default_src_filter} + lib_ignore = Adafruit NeoPixel, LiquidTWI2, SPI # @@ -468,11 +468,11 @@ lib_ignore = Adafruit NeoPixel, LiquidTWI2, SPI [env:mks_robin_mini] platform = ststm32 board = genericSTM32F103VE -build_flags = !python Marlin/src/HAL/HAL_STM32F1/build_flags.py +build_flags = !python Marlin/src/HAL/STM32F1/build_flags.py ${common.build_flags} -std=gnu++14 build_unflags = -std=gnu++11 extra_scripts = buildroot/share/PlatformIO/scripts/mks_robin_mini.py -src_filter = ${common.default_src_filter} + +src_filter = ${common.default_src_filter} + lib_ignore = Adafruit NeoPixel, SPI # @@ -482,11 +482,11 @@ lib_ignore = Adafruit NeoPixel, SPI platform = ststm32 board = genericSTM32F103VE platform_packages = tool-stm32duino -build_flags = !python Marlin/src/HAL/HAL_STM32F1/build_flags.py +build_flags = !python Marlin/src/HAL/STM32F1/build_flags.py ${common.build_flags} -std=gnu++14 -DHAVE_SW_SERIAL -DSS_TIMER=4 build_unflags = -std=gnu++11 extra_scripts = buildroot/share/PlatformIO/scripts/mks_robin_nano.py -src_filter = ${common.default_src_filter} + +src_filter = ${common.default_src_filter} + lib_deps = ${common.lib_deps} SoftwareSerialM=https://github.com/FYSETC/SoftwareSerialM/archive/master.zip lib_ignore = Adafruit NeoPixel, SPI @@ -497,11 +497,11 @@ lib_ignore = Adafruit NeoPixel, SPI [env:mks_robin] platform = ststm32 board = genericSTM32F103ZE -build_flags = !python Marlin/src/HAL/HAL_STM32F1/build_flags.py +build_flags = !python Marlin/src/HAL/STM32F1/build_flags.py ${common.build_flags} -std=gnu++14 -DSTM32_XL_DENSITY build_unflags = -std=gnu++11 extra_scripts = buildroot/share/PlatformIO/scripts/mks_robin.py -src_filter = ${common.default_src_filter} + +src_filter = ${common.default_src_filter} + lib_ignore = Adafruit NeoPixel, SPI # @@ -511,10 +511,10 @@ lib_ignore = Adafruit NeoPixel, SPI platform = ststm32 board = genericSTM32F103ZE extra_scripts = buildroot/share/PlatformIO/scripts/mks_robin_pro.py -build_flags = !python Marlin/src/HAL/HAL_STM32F1/build_flags.py +build_flags = !python Marlin/src/HAL/STM32F1/build_flags.py ${common.build_flags} -std=gnu++14 -DSTM32_XL_DENSITY build_unflags = -std=gnu++11 -src_filter = ${common.default_src_filter} + +src_filter = ${common.default_src_filter} + lib_deps = ${common.lib_deps} lib_ignore = Adafruit NeoPixel, SPI, TMCStepper @@ -524,11 +524,11 @@ lib_ignore = Adafruit NeoPixel, SPI, TMCStepper [env:mks_robin_lite] platform = ststm32 board = genericSTM32F103RC -build_flags = !python Marlin/src/HAL/HAL_STM32F1/build_flags.py +build_flags = !python Marlin/src/HAL/STM32F1/build_flags.py ${common.build_flags} -std=gnu++14 build_unflags = -std=gnu++11 extra_scripts = buildroot/share/PlatformIO/scripts/mks_robin_lite.py -src_filter = ${common.default_src_filter} + +src_filter = ${common.default_src_filter} + lib_ignore = Adafruit NeoPixel, SPI # @@ -538,10 +538,10 @@ lib_ignore = Adafruit NeoPixel, SPI platform = ststm32 board = genericSTM32F103RC extra_scripts = buildroot/share/PlatformIO/scripts/mks_robin_lite3.py -build_flags = !python Marlin/src/HAL/HAL_STM32F1/build_flags.py +build_flags = !python Marlin/src/HAL/STM32F1/build_flags.py ${common.build_flags} -std=gnu++14 build_unflags = -std=gnu++11 -src_filter = ${common.default_src_filter} + +src_filter = ${common.default_src_filter} + lib_deps = ${common.lib_deps} lib_ignore = Adafruit NeoPixel, SPI @@ -551,11 +551,11 @@ lib_ignore = Adafruit NeoPixel, SPI [env:jgaurora_a5s_a1] platform = ststm32 board = genericSTM32F103ZE -build_flags = !python Marlin/src/HAL/HAL_STM32F1/build_flags.py +build_flags = !python Marlin/src/HAL/STM32F1/build_flags.py ${common.build_flags} -DSTM32F1xx -std=gnu++14 -DSTM32_XL_DENSITY build_unflags = -std=gnu++11 extra_scripts = buildroot/share/PlatformIO/scripts/jgaurora_a5s_a1_with_bootloader.py -src_filter = ${common.default_src_filter} + +src_filter = ${common.default_src_filter} + lib_ignore = Adafruit NeoPixel, SPI # @@ -564,9 +564,9 @@ lib_ignore = Adafruit NeoPixel, SPI [env:STM32F103CB_malyan] platform = ststm32 board = malyanM200 -build_flags = !python Marlin/src/HAL/HAL_STM32F1/build_flags.py -DMCU_STM32F103CB -D __STM32F1__=1 -std=c++1y -D MOTHERBOARD="BOARD_MALYAN_M200" -DSERIAL_USB -ffunction-sections -fdata-sections -Wl,--gc-sections +build_flags = !python Marlin/src/HAL/STM32F1/build_flags.py -DMCU_STM32F103CB -D __STM32F1__=1 -std=c++1y -D MOTHERBOARD="BOARD_MALYAN_M200" -DSERIAL_USB -ffunction-sections -fdata-sections -Wl,--gc-sections -DDEBUG_LEVEL=0 -D__MARLIN_FIRMWARE__ -src_filter = ${common.default_src_filter} + +src_filter = ${common.default_src_filter} + lib_ignore = Adafruit NeoPixel, LiquidCrystal, LiquidTWI2, TMCStepper, U8glib-HAL, SPI # @@ -575,11 +575,11 @@ lib_ignore = Adafruit NeoPixel, LiquidCrystal, LiquidTWI2, TMCStepper, U8glib-H [env:chitu_f103] platform = ststm32 board = genericSTM32F103ZE -build_flags = !python Marlin/src/HAL/HAL_STM32F1/build_flags.py +build_flags = !python Marlin/src/HAL/STM32F1/build_flags.py ${common.build_flags} -DSTM32F1xx -std=gnu++14 -DSTM32_XL_DENSITY build_unflags = -std=gnu++11 -DCONFIG_MAPLE_MINI_NO_DISABLE_DEBUG= -DERROR_LED_PORT=GPIOE -DERROR_LED_PIN=6 extra_scripts = buildroot/share/PlatformIO/scripts/chitu_crypt.py -src_filter = ${common.default_src_filter} + +src_filter = ${common.default_src_filter} + lib_ignore = Adafruit NeoPixel # @@ -594,12 +594,12 @@ build_flags = ${common.build_flags} -DTARGET_STM32F4 -DARDUINO_STEVAL -DSTM32F401xE -DUSBCON -DUSBD_USE_CDC -DUSBD_VID=0x0483 -DUSB_PRODUCT=\"STEVAL_F401VE\" -DDISABLE_GENERIC_SERIALUSB - -IMarlin/src/HAL/HAL_STM32 + -IMarlin/src/HAL/STM32 build_unflags = -std=gnu++11 extra_scripts = pre:buildroot/share/PlatformIO/scripts/generic_create_variant.py buildroot/share/PlatformIO/scripts/STEVAL__F401XX.py lib_ignore = Adafruit NeoPixel, TMCStepper, SailfishLCD, SailfishRGB_LED, SlowSoftI2CMaster, SoftwareSerial -src_filter = ${common.default_src_filter} + +src_filter = ${common.default_src_filter} + # # FLYF407ZG @@ -611,11 +611,11 @@ platform_packages = framework-arduinoststm32@>=3.107,<4 build_flags = ${common.build_flags} -DSTM32F4 -DUSBCON -DUSBD_USE_CDC -DUSBD_VID=0x0483 -DUSB_PRODUCT=\"STM32F407ZG\" -DTARGET_STM32F4 -DVECT_TAB_OFFSET=0x8000 - -IMarlin/src/HAL/HAL_STM32 + -IMarlin/src/HAL/STM32 build_unflags = -std=gnu++11 extra_scripts = pre:buildroot/share/PlatformIO/scripts/generic_create_variant.py lib_ignore = Adafruit NeoPixel, TMCStepper, SailfishLCD, SailfishRGB_LED, SlowSoftI2CMaster, SoftwareSerial -src_filter = ${common.default_src_filter} + +src_filter = ${common.default_src_filter} + # @@ -624,14 +624,16 @@ src_filter = ${common.default_src_filter} + [env:FYSETC_S6] platform = ststm32 board = fysetc_s6 -platform_packages = tool-stm32duino +platform_packages = + tool-stm32duino + framework-arduinoststm32@>=3.107,<4 build_flags = ${common.build_flags} -DTARGET_STM32F4 -std=gnu++14 -DVECT_TAB_OFFSET=0x10000 -DUSBCON -DUSBD_USE_CDC -DHAL_PCD_MODULE_ENABLED -DUSBD_VID=0x0483 '-DUSB_PRODUCT="FYSETC_S6"' build_unflags = -std=gnu++11 extra_scripts = pre:buildroot/share/PlatformIO/scripts/fysetc_STM32S6.py -src_filter = ${common.default_src_filter} + +src_filter = ${common.default_src_filter} + lib_ignore = Arduino-L6470 debug_tool = stlink #upload_protocol = stlink @@ -649,11 +651,11 @@ platform_packages = framework-arduinoststm32@>=3.107,<4 build_flags = ${common.build_flags} -DTARGET_STM32F4 -DARDUINO_BLACK_F407VE -DUSBCON -DUSBD_USE_CDC -DUSBD_VID=0x0483 -DUSB_PRODUCT=\"BLACK_F407VE\" - -IMarlin/src/HAL/HAL_STM32 + -IMarlin/src/HAL/STM32 build_unflags = -std=gnu++11 extra_scripts = pre:buildroot/share/PlatformIO/scripts/generic_create_variant.py lib_ignore = Adafruit NeoPixel, TMCStepper, SailfishLCD, SailfishRGB_LED, SlowSoftI2CMaster, SoftwareSerial -src_filter = ${common.default_src_filter} + +src_filter = ${common.default_src_filter} + # # BigTreeTech SKR Pro (STM32F407ZGT6 ARM Cortex-M4) @@ -665,11 +667,11 @@ platform_packages = framework-arduinoststm32@>=3.107,<4 build_flags = ${common.build_flags} -DUSBCON -DUSBD_USE_CDC -DUSBD_VID=0x0483 -DUSB_PRODUCT=\"STM32F407ZG\" -DTARGET_STM32F4 -DSTM32F407_5ZX -DVECT_TAB_OFFSET=0x8000 - -IMarlin/src/HAL/HAL_STM32 + -IMarlin/src/HAL/STM32 build_unflags = -std=gnu++11 extra_scripts = pre:buildroot/share/PlatformIO/scripts/generic_create_variant.py lib_ignore = SoftwareSerial, SoftwareSerialM -src_filter = ${common.default_src_filter} + +src_filter = ${common.default_src_filter} + #upload_protocol = stlink #upload_command = "$PROJECT_PACKAGES_DIR/tool-stm32duino/stlink/ST-LINK_CLI.exe" -c SWD -P "$BUILD_DIR/firmware.bin" 0x8008000 -Rst -Run debug_tool = stlink @@ -681,14 +683,13 @@ debug_init_break = [env:BIGTREE_GTR_V1_0] platform = ststm32@>=5.7.0 framework = arduino -platform_packages = framework-arduinoststm32@>=3.10700.191028 +platform_packages = framework-arduinoststm32@>=3.107,<4 board = BigTree_SKR_Pro extra_scripts = pre:buildroot/share/PlatformIO/scripts/generic_create_variant.py build_flags = ${common.build_flags} -DUSBCON -DUSBD_USE_CDC -DUSBD_VID=0x0483 -DUSB_PRODUCT=\"STM32F407IG\" -DTARGET_STM32F4 -DSTM32F407IX -DVECT_TAB_OFFSET=0x8000 - - -IMarlin/src/HAL/HAL_STM32 + -IMarlin/src/HAL/STM32 lib_deps = U8glib-HAL=https://github.com/MarlinFirmware/U8glib-HAL/archive/bugfix.zip LiquidCrystal @@ -697,7 +698,7 @@ lib_deps = LiquidTWI2=https://github.com/lincomatic/LiquidTWI2/archive/master.zip Arduino-L6470=https://github.com/ameyer/Arduino-L6470/archive/0.7.0.zip lib_ignore = SoftwareSerial, SoftwareSerialM -src_filter = ${common.default_src_filter} + +src_filter = ${common.default_src_filter} + monitor_speed = 250000 # @@ -717,7 +718,7 @@ build_flags = ${common.build_flags} build_unflags = -std=gnu++11 extra_scripts = pre:buildroot/share/PlatformIO/scripts/generic_create_variant.py lib_ignore = Adafruit NeoPixel, SailfishLCD, SailfishRGB_LED, SlowSoftI2CMaster -src_filter = ${common.default_src_filter} + +src_filter = ${common.default_src_filter} + # # Teensy 3.1 / 3.2 (ARM Cortex-M4) @@ -728,7 +729,7 @@ board = teensy31 lib_deps = ${common.lib_deps} TMC26XStepper=https://github.com/trinamic/TMC26XStepper/archive/master.zip lib_ignore = Adafruit NeoPixel -src_filter = ${common.default_src_filter} + +src_filter = ${common.default_src_filter} + # # Teensy 3.5 / 3.6 (ARM Cortex-M4) @@ -739,7 +740,7 @@ board = teensy35 lib_deps = ${common.lib_deps} TMC26XStepper=https://github.com/trinamic/TMC26XStepper/archive/master.zip lib_ignore = Adafruit NeoPixel -src_filter = ${common.default_src_filter} + +src_filter = ${common.default_src_filter} + # # Espressif ESP32 @@ -755,7 +756,7 @@ lib_deps = ${common.lib_deps} arduinoWebSockets=https://github.com/Links2004/arduinoWebSockets.git ESP32SSDP=https://github.com/luc-github/ESP32SSDP.git lib_ignore = LiquidCrystal, LiquidTWI2, SailfishLCD, SailfishRGB_LED, ESPAsyncTCP -src_filter = ${common.default_src_filter} + +src_filter = ${common.default_src_filter} + upload_speed = 115200 #upload_port = marlinesp.local #board_build.flash_mode = qio @@ -768,24 +769,24 @@ upload_speed = 115200 platform = native framework = build_flags = -D__PLAT_LINUX__ -std=gnu++17 -ggdb -g -lrt -lpthread -D__MARLIN_FIRMWARE__ -Wno-expansion-to-defined -src_build_flags = -Wall -IMarlin/src/HAL/HAL_LINUX/include +src_build_flags = -Wall -IMarlin/src/HAL/LINUX/include build_unflags = -Wall lib_ldf_mode = off lib_deps = -extra_scripts = -src_filter = ${common.default_src_filter} + +src_filter = ${common.default_src_filter} + # # Adafruit Grand Central M4 (Atmel SAMD51P20A ARM Cortex-M4) # [env:SAMD51_grandcentral_m4] -platform = atmelsam -board = adafruit_grandcentral_m4 -build_flags = ${common.build_flags} -std=gnu++17 -extra_scripts = ${common.extra_scripts} -build_unflags = -std=gnu++11 -src_filter = ${common.default_src_filter} + -debug_tool = jlink +platform = atmelsam +board = adafruit_grandcentral_m4 +build_flags = ${common.build_flags} -std=gnu++17 -Wno-register +build_unflags = -std=gnu++11 +src_filter = ${common.default_src_filter} + +lib_deps = ${common.lib_deps} + SoftwareSerialM=https://github.com/FYSETC/SoftwareSerialM/archive/master.zip +debug_tool = jlink # # RUMBA32 @@ -809,7 +810,7 @@ build_flags = ${common.build_flags} -DHAL_UART_MODULE_ENABLED -Os lib_ignore = Adafruit NeoPixel -src_filter = ${common.default_src_filter} + +src_filter = ${common.default_src_filter} + monitor_speed = 500000 upload_protocol = dfu @@ -830,7 +831,7 @@ build_flags = ${common.build_flags} -DHAL_UART_MODULE_ENABLED -Os lib_ignore = Adafruit NeoPixel -src_filter = ${common.default_src_filter} + + - +src_filter = ${common.default_src_filter} + + - upload_protocol = dfu #